From 3518cf5480a1f2491dd554436b6a71f9a8828a07 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 4 Nov 2014 16:18:35 +1100 Subject: [PATCH] AP_InertialSensor: fixed default MPU9250 orientation for NavIO --- libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp index 1137e6558c..0c574ebb11 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp @@ -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);