|
|
@ -288,6 +288,9 @@ bool AP_InertialSensor_MPU9250::update( void ) |
|
|
|
// way up, and PWM pins on NavIO are at the back of the aircraft
|
|
|
|
// way up, and PWM pins on NavIO are at the back of the aircraft
|
|
|
|
accel.rotate(ROTATION_ROLL_180_YAW_90); |
|
|
|
accel.rotate(ROTATION_ROLL_180_YAW_90); |
|
|
|
gyro.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 |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
_rotate_and_offset_gyro(_gyro_instance, gyro); |
|
|
|
_rotate_and_offset_gyro(_gyro_instance, gyro); |
|
|
|