mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed default MPU9250 orientation for NavIO
This commit is contained in:
parent
c682a6ee96
commit
3518cf5480
|
@ -283,6 +283,11 @@ bool AP_InertialSensor_MPU9250::update( void )
|
|||
// 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);
|
||||
#endif
|
||||
|
||||
_rotate_and_offset_gyro(_gyro_instance, gyro);
|
||||
|
|
Loading…
Reference in New Issue