AP_InertialSensor: Add HAL_COMPASS_AK8963_MPU9250_I2C to _detect_backends()

This commit is contained in:
José Roberto de Souza 2015-09-28 17:55:07 -03:00 committed by Andrew Tridgell
parent 6ece4d60aa
commit 17e105640e
1 changed files with 3 additions and 0 deletions

View File

@ -442,6 +442,9 @@ void Compass::_detect_backends(void)
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
_add_backend(AP_Compass_AK8963::detect_i2c(*this, hal.i2c1,
HAL_COMPASS_AK8963_I2C_ADDR));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
_add_backend(AP_Compass_AK8963::detect_mpu9250_i2c(*this, HAL_COMPASS_AK8963_I2C_POINTER,
HAL_COMPASS_AK8963_I2C_ADDR));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
_add_backend(AP_Compass_PX4::detect(*this));
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250