mirror of https://github.com/ArduPilot/ardupilot
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.
This commit is contained in:
parent
96db31635d
commit
865ff753f3
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue