Browse Source

AP_AHRS: added AHRS_ORIENTATION parameter

master
Andrew Tridgell 12 years ago
parent
commit
848fc3e32d
  1. 7
      libraries/AP_AHRS/AP_AHRS.cpp
  2. 5
      libraries/AP_AHRS/AP_AHRS.h
  3. 4
      libraries/AP_AHRS/AP_AHRS_MPU6000.cpp

7
libraries/AP_AHRS/AP_AHRS.cpp

@ -75,6 +75,13 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { @@ -75,6 +75,13 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
// @User: Advanced
AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
// @Param: ORIENTATION
// @DisplayName: Board Orientation
// @Description: Overall board orientation. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. This option takes affect on next boot. After changing you will need to re-level your vehicle.
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315
// @User: Advanced
AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
AP_GROUPEND
};

5
libraries/AP_AHRS/AP_AHRS.h

@ -40,8 +40,9 @@ public: @@ -40,8 +40,9 @@ public:
_gyro_drift_limit = ins->get_gyro_drift_rate();
}
// empty init
// init sets up INS board orientation
virtual void init() {
_ins->set_board_orientation((enum Rotation)_board_orientation.get());
};
// Accessors
@ -50,6 +51,7 @@ public: @@ -50,6 +51,7 @@ public:
}
void set_compass(Compass *compass) {
_compass = compass;
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
}
void set_barometer(AP_Baro *barometer) {
_barometer = barometer;
@ -157,6 +159,7 @@ public: @@ -157,6 +159,7 @@ public:
AP_Int8 _gps_use;
AP_Int8 _baro_use;
AP_Int8 _wind_max;
AP_Int8 _board_orientation;
// for holding parameters
static const struct AP_Param::GroupInfo var_info[];

4
libraries/AP_AHRS/AP_AHRS_MPU6000.cpp

@ -1,3 +1,4 @@ @@ -1,3 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* AP_AHRS_MPU6000.cpp
*
@ -32,6 +33,9 @@ extern const AP_HAL::HAL& hal; @@ -32,6 +33,9 @@ extern const AP_HAL::HAL& hal;
void
AP_AHRS_MPU6000::init()
{
// call parent init
AP_AHRS::init();
// suspend timer so interrupts on spi bus do not interfere with
// communication to mpu6000
hal.scheduler->suspend_timer_procs();

Loading…
Cancel
Save