AP_Compass: set orientation ROLL_180 for LSM9DS1 on Navio2

This commit is contained in:
Alexey Bulatov 2016-11-11 16:41:01 +03:00 committed by Lucas De Marchi
parent 163fa07ac0
commit 96db31635d
2 changed files with 1 additions and 5 deletions

View File

@ -599,7 +599,7 @@ void Compass::_detect_backends(void)
#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")),
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_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
AP_Compass_HMC5843::name, true);

View File

@ -204,10 +204,6 @@ void AP_Compass_LSM9DS1::read()
_sem->give();
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
field.rotate(ROTATION_ROLL_180);
#endif
publish_filtered_field(field, _compass_instance);
}