AP_InertialSensor: make single rotation on MPU9250

The previous implementation made some boards apply two rotations to suit
their default orientation. That was happening because there was an
unconditional rotation being done (commented as "rotate for bbone
default").

This commit makes that unconditional rotation as a default rotation
instead and adjusts the former additional rotations to be single
rotations.
This commit is contained in:
Gustavo Jose de Sousa 2015-06-08 17:06:17 -03:00 committed by Andrew Tridgell
parent 3dad768e8b
commit c72dc9bd45
2 changed files with 17 additions and 18 deletions

View File

@ -180,7 +180,17 @@ AP_InertialSensor_MPU9250::AP_InertialSensor_MPU9250(AP_InertialSensor &imu) :
_shared_data_idx(0),
_accel_filter(1000, 15),
_gyro_filter(1000, 15),
_have_sample_available(false)
_have_sample_available(false),
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
_default_rotation(ROTATION_ROLL_180_YAW_270)
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
/* no rotation needed */
_default_rotation(ROTATION_NONE)
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
_default_rotation(ROTATION_YAW_270)
#else /* rotate for bbone default (and other boards) */
_default_rotation(ROTATION_ROLL_180_YAW_90)
#endif
{
}
@ -273,23 +283,8 @@ bool AP_InertialSensor_MPU9250::update( void )
accel *= MPU9250_ACCEL_SCALE_1G;
gyro *= GYRO_SCALE;
// rotate for bbone default
accel.rotate(ROTATION_ROLL_180_YAW_90);
gyro.rotate(ROTATION_ROLL_180_YAW_90);
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
// PXF has an additional YAW 180
accel.rotate(ROTATION_YAW_180);
gyro.rotate(ROTATION_YAW_180);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
// NavIO has different orientation, assuming RaspberryPi is right
// way up, and PWM pins on NavIO are at the back of the aircraft
accel.rotate(ROTATION_ROLL_180_YAW_90);
gyro.rotate(ROTATION_ROLL_180_YAW_90);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
accel.rotate(ROTATION_ROLL_180);
gyro.rotate(ROTATION_ROLL_180);
#endif
accel.rotate(_default_rotation);
gyro.rotate(_default_rotation);
_publish_gyro(_gyro_instance, gyro);
_publish_accel(_accel_instance, accel);

View File

@ -72,6 +72,10 @@ private:
uint8_t _gyro_instance;
uint8_t _accel_instance;
// The default rotation for the IMU, its value depends on how the IMU is
// placed by default on the system
enum Rotation _default_rotation;
#if MPU9250_DEBUG
void _dump_registers(void);
#endif