AP_Compass: allows boards to define orientation of HMC5843

This commit is contained in:
Andrew Tridgell 2018-02-04 21:43:12 +11:00
parent 077aa24c6d
commit 23803df038

View File

@ -813,7 +813,11 @@ void Compass::_detect_backends(void)
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
AP_Compass_AK8963::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
#ifndef HAL_COMPASS_HMC5843_ROTATION
# define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE
#endif
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
false, HAL_COMPASS_HMC5843_ROTATION),
AP_Compass_HMC5843::name, false);
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe_mpu6000(*this),