From 86cbc445bd0cc7e2f953330c1b9f63369116c306 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 8 Jan 2018 22:18:04 +0900 Subject: [PATCH] AP_Compass: ICM20948 default rotation to Pitch180Yaw90 --- libraries/AP_Compass/AP_Compass.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 10180c94a0..c437cb6e4b 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -594,13 +594,13 @@ void Compass::_detect_backends(void) ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_AK09916_I2C_ADDR), hal.i2c_mgr->get_device(1, HAL_COMPASS_ICM20948_I2C_ADDR), - true, ROTATION_NONE), + true, ROTATION_PITCH_180_YAW_90), AP_Compass_AK09916::name, true); ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_AK09916_I2C_ADDR), hal.i2c_mgr->get_device(0, HAL_COMPASS_ICM20948_I2C_ADDR), - both_i2c_external, ROTATION_NONE), + both_i2c_external, ROTATION_PITCH_180_YAW_90), AP_Compass_AK09916::name, true); // lis3mdl on bus 0 with default address