|
|
|
@ -560,7 +560,7 @@ void Compass::_detect_backends(void)
@@ -560,7 +560,7 @@ void Compass::_detect_backends(void)
|
|
|
|
|
|
|
|
|
|
#if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL |
|
|
|
|
ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect(*this), nullptr, false); |
|
|
|
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN |
|
|
|
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN || defined(HAL_CHIBIOS_ARCH_FMUV3) |
|
|
|
|
switch (AP_BoardConfig::get_board_type()) { |
|
|
|
|
case AP_BoardConfig::PX4_BOARD_PX4V1: |
|
|
|
|
case AP_BoardConfig::PX4_BOARD_PIXHAWK: |
|
|
|
@ -802,6 +802,9 @@ void Compass::_detect_backends(void)
@@ -802,6 +802,9 @@ void Compass::_detect_backends(void)
|
|
|
|
|
AP_Compass_AK8963::name, false); |
|
|
|
|
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")), |
|
|
|
|
AP_Compass_LSM9DS1::name, false); |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 |
|
|
|
|
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(0, 0x10)), |
|
|
|
|
AP_Compass_BMM150::name, true); |
|
|
|
|
#else |
|
|
|
|
#error Unrecognised HAL_COMPASS_TYPE setting |
|
|
|
|
#endif |
|
|
|
|