Browse Source

AP_Compass: add rotation option for AK8963_MPU9250

allows using non-neutrally rotated AK8963 compass on MPU9250 as internal
reference: https://github.com/ArduPilot/ardupilot/pull/9459
master
vierfuffzig 6 years ago committed by Andrew Tridgell
parent
commit
b455c7a769
  1. 5
      libraries/AP_Compass/AP_Compass.cpp

5
libraries/AP_Compass/AP_Compass.cpp

@ -862,7 +862,10 @@ void Compass::_detect_backends(void) @@ -862,7 +862,10 @@ void Compass::_detect_backends(void)
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0));
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0));
#ifndef HAL_COMPASS_AK8963_MPU9250_ROTATION
#define HAL_COMPASS_AK8963_MPU9250_ROTATION ROTATION_NONE
#endif
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, HAL_COMPASS_AK8963_MPU9250_ROTATION));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
#ifndef HAL_COMPASS_HMC5843_ROTATION
# define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE

Loading…
Cancel
Save