From 865ff753f3c7a732169112108d071104ccd8c1ea Mon Sep 17 00:00:00 2001 From: Georgii Staroselskii Date: Mon, 21 Nov 2016 13:35:58 +0300 Subject: [PATCH] AP_Compass: use LSM9DS1 as primary for Navio 2 This compass has been proved to work better on Navio boards. Users also don't like high offsets (even though, they don't really mean much in this context) reported by AK8963 in MPU9250 on Navio 2. --- 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 e06c480ca4..34d025ded9 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -597,10 +597,10 @@ void Compass::_detect_backends(void) true), AP_Compass_HMC5843::name, true); #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2 - ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0), - AP_Compass_AK8963::name, false); ADD_BACKEND(AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m"), ROTATION_ROLL_180), AP_Compass_LSM9DS1::name, false); + ADD_BACKEND(AP_Compass_AK8963::probe_mpu9250(*this, 0), + AP_Compass_AK8963::name, false); ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true), AP_Compass_HMC5843::name, true); #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO