mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: enable in-tree drivers for PHMINI
This commit is contained in:
parent
03b7bc9e65
commit
b363a65c2e
|
@ -495,7 +495,8 @@ void Compass::_detect_backends(void)
|
||||||
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V1 ||
|
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V1 ||
|
||||||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V2 ||
|
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V2 ||
|
||||||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3 ||
|
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3 ||
|
||||||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
|
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4 ||
|
||||||
|
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PHMINI) {
|
||||||
// external i2c bus
|
// external i2c bus
|
||||||
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||||
true, ROTATION_ROLL_180),
|
true, ROTATION_ROLL_180),
|
||||||
|
@ -524,6 +525,10 @@ void Compass::_detect_backends(void)
|
||||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
|
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
|
||||||
AP_Compass_AK8963::name, false);
|
AP_Compass_AK8963::name, false);
|
||||||
}
|
}
|
||||||
|
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PHMINI) {
|
||||||
|
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180),
|
||||||
|
AP_Compass_AK8963::name, false);
|
||||||
|
}
|
||||||
// also add any px4 level drivers (for canbus magnetometers)
|
// also add any px4 level drivers (for canbus magnetometers)
|
||||||
_add_backend(AP_Compass_PX4::detect(*this), nullptr, false);
|
_add_backend(AP_Compass_PX4::detect(*this), nullptr, false);
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
||||||
|
|
Loading…
Reference in New Issue