From 23803df038463771fc74d420d9edba8550d70534 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 4 Feb 2018 21:43:12 +1100 Subject: [PATCH] AP_Compass: allows boards to define orientation of HMC5843 --- libraries/AP_Compass/AP_Compass.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index f7423de77b..aa4469c6ce 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -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),