mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Compass: stop passing frontend pointer
Let AP_Compass_Backend call AP::compass() *once* instead of passing the frontend pointer over and over.
This commit is contained in:
parent
585b6dce0d
commit
4039b51810
@ -586,7 +586,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
bool both_i2c_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
|
||||
// external i2c bus
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
}
|
||||
@ -595,7 +595,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {
|
||||
// internal i2c bus
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
|
||||
AP_Compass_HMC5843::name, both_i2c_external);
|
||||
}
|
||||
@ -603,14 +603,14 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
|
||||
//external i2c bus
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL),
|
||||
AP_Compass_QMC5883L::name, true);
|
||||
}
|
||||
|
||||
//internal i2c bus
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
both_i2c_external,
|
||||
both_i2c_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL),
|
||||
AP_Compass_QMC5883L::name,both_i2c_external);
|
||||
@ -619,16 +619,14 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
// AK09916 on ICM20948
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(*this,
|
||||
GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
|
||||
true, ROTATION_PITCH_180_YAW_90),
|
||||
AP_Compass_AK09916::name, true);
|
||||
}
|
||||
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(*this,
|
||||
GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
|
||||
both_i2c_external, ROTATION_PITCH_180_YAW_90),
|
||||
AP_Compass_AK09916::name, true);
|
||||
@ -636,40 +634,40 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
|
||||
// lis3mdl on bus 0 with default address
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE),
|
||||
AP_Compass_LIS3MDL::name, both_i2c_external);
|
||||
}
|
||||
|
||||
// lis3mdl on bus 0 with alternate address
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE),
|
||||
AP_Compass_LIS3MDL::name, both_i2c_external);
|
||||
}
|
||||
|
||||
// external lis3mdl on bus 1 with default address
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
true, ROTATION_YAW_90),
|
||||
AP_Compass_LIS3MDL::name, true);
|
||||
}
|
||||
|
||||
// external lis3mdl on bus 1 with alternate address
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
|
||||
true, ROTATION_YAW_90),
|
||||
AP_Compass_LIS3MDL::name, true);
|
||||
}
|
||||
|
||||
// AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
true, ROTATION_YAW_270),
|
||||
AP_Compass_AK09916::name, true);
|
||||
}
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE),
|
||||
AP_Compass_AK09916::name, both_i2c_external);
|
||||
}
|
||||
@ -685,12 +683,12 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
}
|
||||
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, default_rotation), AP_Compass_IST8310::name, true);
|
||||
}
|
||||
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
both_i2c_external, default_rotation), AP_Compass_IST8310::name, both_i2c_external);
|
||||
}
|
||||
}
|
||||
@ -703,7 +701,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
void Compass::_detect_backends(void)
|
||||
{
|
||||
if (_hil_mode) {
|
||||
_add_backend(AP_Compass_HIL::detect(*this), nullptr, false);
|
||||
_add_backend(AP_Compass_HIL::detect(), nullptr, false);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -715,7 +713,7 @@ void Compass::_detect_backends(void)
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL(*this), nullptr, false);
|
||||
ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL(), nullptr, false);
|
||||
return;
|
||||
#endif
|
||||
|
||||
@ -729,7 +727,7 @@ void Compass::_detect_backends(void)
|
||||
#endif
|
||||
|
||||
#if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
|
||||
ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect(*this), nullptr, false);
|
||||
ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect(), nullptr, false);
|
||||
#elif AP_FEATURE_BOARD_DETECT
|
||||
switch (AP_BoardConfig::get_board_type()) {
|
||||
case AP_BoardConfig::PX4_BOARD_PX4V1:
|
||||
@ -752,17 +750,17 @@ void Compass::_detect_backends(void)
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PCNC1:
|
||||
ADD_BACKEND(DRIVER_BMM150,
|
||||
AP_Compass_BMM150::probe(*this, GET_I2C_DEVICE(0, 0x10)),
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10)),
|
||||
AP_Compass_BMM150::name, true);
|
||||
break;
|
||||
case AP_BoardConfig::VRX_BOARD_BRAIN54: {
|
||||
// external i2c bus
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
}
|
||||
// internal i2c bus
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
false, ROTATION_YAW_270),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
break;
|
||||
@ -774,7 +772,7 @@ void Compass::_detect_backends(void)
|
||||
case AP_BoardConfig::VRX_BOARD_UBRAIN51:
|
||||
case AP_BoardConfig::VRX_BOARD_UBRAIN52: {
|
||||
// external i2c bus
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
}
|
||||
@ -785,78 +783,78 @@ void Compass::_detect_backends(void)
|
||||
}
|
||||
switch (AP_BoardConfig::get_board_type()) {
|
||||
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
|
||||
false, ROTATION_PITCH_180),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270),
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
// we run the AK8963 only on the 2nd MPU9250, which leaves the
|
||||
// first MPU9250 to run without disturbance at high rate
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 1, ROTATION_YAW_270),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_FMUV5:
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180_YAW_90), AP_Compass_IST8310::name, true);
|
||||
}
|
||||
FOREACH_I2C_INTERNAL(i) {
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
false, ROTATION_ROLL_180_YAW_90), AP_Compass_IST8310::name, false);
|
||||
}
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_SP01:
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 1, ROTATION_NONE),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PIXRACER:
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
|
||||
false, ROTATION_PITCH_180),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
// R15 has LIS3MDL on spi bus instead of HMC; same CS pin
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
|
||||
false, ROTATION_NONE),
|
||||
AP_Compass_LIS3MDL::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
|
||||
false, ROTATION_NONE),
|
||||
AP_Compass_LIS3MDL::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PHMINI:
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_AUAV21:
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_ROLL_180_YAW_90),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_YAW_270),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270),
|
||||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_MINDPXV2:
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
false, ROTATION_YAW_90),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270),
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
break;
|
||||
|
||||
@ -865,108 +863,108 @@ void Compass::_detect_backends(void)
|
||||
}
|
||||
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0), AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0), AP_Compass_AK8963::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 1),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1),
|
||||
AP_Compass_AK8963::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m"), ROTATION_ROLL_180),
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(hal.spi->get_device("lsm9ds1_m"), ROTATION_ROLL_180),
|
||||
AP_Compass_LSM9DS1::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_OCPOC_ZYNQ
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
ADD_BACKEND(DRIVER_AK8963,AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963,AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_EDGE
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
|
||||
#ifndef HAL_COMPASS_HMC5843_ROTATION
|
||||
# define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE
|
||||
#endif
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
false, HAL_COMPASS_HMC5843_ROTATION),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
#if defined(HAL_COMPASS_HMC5843_I2C_EXT_BUS) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_EXT_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_EXT_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#endif
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe_mpu6000(*this),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe_mpu6000(),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
AP_Compass_AK8963::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(GET_I2C_DEVICE(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
|
||||
AP_Compass_AK8963::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AERO
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
AP_Compass_BMM150::name, false);
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_LIS3MDL
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME), false, ROTATION_ROLL_180_YAW_90),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME), false, ROTATION_ROLL_180_YAW_90),
|
||||
AP_Compass_LIS3MDL::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_MAG3110
|
||||
ADD_BACKEND(DRIVER_MAG3110, AP_Compass_MAG3110::probe(*this, GET_I2C_DEVICE(HAL_MAG3110_I2C_BUS, HAL_MAG3110_I2C_ADDR), ROTATION_NONE),
|
||||
ADD_BACKEND(DRIVER_MAG3110, AP_Compass_MAG3110::probe(GET_I2C_DEVICE(HAL_MAG3110_I2C_BUS, HAL_MAG3110_I2C_ADDR), ROTATION_NONE),
|
||||
AP_Compass_MAG3110::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_IST8310
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
true, ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL),
|
||||
AP_Compass_QMC5883L::name, true);
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
false, HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL),
|
||||
AP_Compass_QMC5883L::name, false);
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0),
|
||||
AP_Compass_AK8963::name, false);
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(*this, hal.spi->get_device("lsm9ds1_m")),
|
||||
ADD_BACKEND(DRIVER_LSM9DS1, AP_Compass_LSM9DS1::probe(hal.spi->get_device("lsm9ds1_m")),
|
||||
AP_Compass_LSM9DS1::name, false);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BMM150_I2C
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(GET_I2C_DEVICE(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
AP_Compass_BMM150::name, true);
|
||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE
|
||||
// no compass
|
||||
@ -977,50 +975,50 @@ void Compass::_detect_backends(void)
|
||||
|
||||
#if defined(BOARD_I2C_BUS_EXT) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
// autodetect external i2c bus
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
true,ROTATION_NONE),
|
||||
AP_Compass_QMC5883L::name, true);
|
||||
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
|
||||
|
||||
// lis3mdl
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_LIS3MDL_I2C_ADDR),
|
||||
true, ROTATION_NONE),
|
||||
AP_Compass_LIS3MDL::name, true);
|
||||
|
||||
// AK09916
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_AK09916_I2C_ADDR),
|
||||
true, ROTATION_NONE),
|
||||
AP_Compass_AK09916::name, true);
|
||||
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_IST8310_I2C_ADDR),
|
||||
ROTATION_NONE),
|
||||
AP_Compass_IST8310::name, true);
|
||||
|
||||
#ifdef HAL_COMPASS_BMM150_I2C_ADDR
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_BMM150_I2C_ADDR)),
|
||||
AP_Compass_BMM150::name, true);
|
||||
#endif
|
||||
|
||||
ADD_BACKEND(DRIVER_MAG3110, AP_Compass_MAG3110::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_MAG3110_I2C_ADDR), ROTATION_NONE),
|
||||
ADD_BACKEND(DRIVER_MAG3110, AP_Compass_MAG3110::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_MAG3110_I2C_ADDR), ROTATION_NONE),
|
||||
AP_Compass_MAG3110::name, true);
|
||||
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_QMC5883L_I2C_ADDR), ROTATION_NONE),
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(BOARD_I2C_BUS_EXT, HAL_COMPASS_QMC5883L_I2C_ADDR), ROTATION_NONE),
|
||||
AP_Compass_QMC5883L::name, true);
|
||||
#endif
|
||||
|
||||
/* for chibios external board coniguration */
|
||||
#ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
||||
ADD_BACKEND(DRIVER_UAVCAN, AP_Compass_UAVCAN::probe(*this), "UAVCAN", true);
|
||||
ADD_BACKEND(DRIVER_UAVCAN, AP_Compass_UAVCAN::probe(), "UAVCAN", true);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -48,15 +48,14 @@ extern const AP_HAL::HAL &hal;
|
||||
/*
|
||||
probe for AK09916 directly on I2C
|
||||
*/
|
||||
AP_Compass_Backend *AP_Compass_AK09916::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), nullptr,
|
||||
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(std::move(dev), nullptr,
|
||||
force_external,
|
||||
rotation, AK09916_I2C);
|
||||
if (!sensor || !sensor->init()) {
|
||||
@ -71,8 +70,7 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(Compass &compass,
|
||||
/*
|
||||
probe for AK09916 connected via an ICM20948
|
||||
*/
|
||||
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
@ -80,7 +78,7 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(Compass &compass,
|
||||
if (!dev || !dev_icm) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), std::move(dev_icm),
|
||||
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(std::move(dev), std::move(dev_icm),
|
||||
force_external,
|
||||
rotation, AK09916_ICM20948_I2C);
|
||||
if (!sensor || !sensor->init()) {
|
||||
@ -91,14 +89,12 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_AK09916::AP_Compass_AK09916(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
AP_Compass_AK09916::AP_Compass_AK09916(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev_icm,
|
||||
bool _force_external,
|
||||
enum Rotation _rotation,
|
||||
enum bus_type _bus_type)
|
||||
: AP_Compass_Backend(compass)
|
||||
, bus_type(_bus_type)
|
||||
: bus_type(_bus_type)
|
||||
, dev(std::move(_dev))
|
||||
, dev_icm(std::move(_dev_icm))
|
||||
, force_external(_force_external)
|
||||
|
@ -34,14 +34,12 @@
|
||||
class AP_Compass_AK09916 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
// separate probe function for when behind a ICM20948 IMU
|
||||
static AP_Compass_Backend *probe_ICM20948(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
@ -56,8 +54,7 @@ private:
|
||||
AK09916_ICM20948_I2C,
|
||||
} bus_type;
|
||||
|
||||
AP_Compass_AK09916(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_AK09916(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev_icm,
|
||||
bool force_external,
|
||||
enum Rotation rotation,
|
||||
|
@ -52,10 +52,9 @@ struct PACKED sample_regs {
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus,
|
||||
AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
|
||||
enum Rotation rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _bus(bus)
|
||||
: _bus(bus)
|
||||
, _rotation(rotation)
|
||||
{
|
||||
}
|
||||
@ -65,8 +64,7 @@ AP_Compass_AK8963::~AP_Compass_AK8963()
|
||||
delete _bus;
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
@ -77,7 +75,7 @@ AP_Compass_Backend *AP_Compass_AK8963::probe(Compass &compass,
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus, rotation);
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -86,8 +84,7 @@ AP_Compass_Backend *AP_Compass_AK8963::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
@ -98,10 +95,10 @@ AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(Compass &compass,
|
||||
/* Allow MPU9250 to shortcut auxiliary bus and host bus */
|
||||
ins.detect_backends();
|
||||
|
||||
return probe(compass, std::move(dev), rotation);
|
||||
return probe(std::move(dev), rotation);
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(Compass &compass, uint8_t mpu9250_instance,
|
||||
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(uint8_t mpu9250_instance,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
||||
@ -112,7 +109,7 @@ AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(Compass &compass, uint8_t m
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus, rotation);
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -18,17 +18,15 @@ class AP_Compass_AK8963 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
/* Probe for AK8963 standalone on I2C bus */
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
|
||||
static AP_Compass_Backend *probe_mpu9250(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
|
||||
static AP_Compass_Backend *probe_mpu9250(Compass &compass, uint8_t mpu9250_instance,
|
||||
static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "AK8963";
|
||||
@ -38,7 +36,7 @@ public:
|
||||
void read() override;
|
||||
|
||||
private:
|
||||
AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus,
|
||||
AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
bool init();
|
||||
|
@ -63,13 +63,12 @@
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_Backend *AP_Compass_BMM150::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(compass, std::move(dev));
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev));
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -78,10 +77,8 @@ AP_Compass_Backend *AP_Compass_BMM150::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_BMM150::AP_Compass_BMM150(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
AP_Compass_BMM150::AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: _dev(std::move(dev))
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -27,15 +27,14 @@
|
||||
class AP_Compass_BMM150 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
void read() override;
|
||||
|
||||
static constexpr const char *name = "BMM150";
|
||||
|
||||
private:
|
||||
AP_Compass_BMM150(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
/**
|
||||
* Device periodic callback to read data from the sensor.
|
||||
|
@ -6,10 +6,10 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Compass_Backend::AP_Compass_Backend(Compass &compass) :
|
||||
_compass(compass)
|
||||
AP_Compass_Backend::AP_Compass_Backend()
|
||||
: _compass(AP::compass())
|
||||
{
|
||||
_sem = hal.util->new_semaphore();
|
||||
_sem = hal.util->new_semaphore();
|
||||
}
|
||||
|
||||
void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
|
||||
|
@ -25,7 +25,7 @@ class Compass; // forward declaration
|
||||
class AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
AP_Compass_Backend(Compass &compass);
|
||||
AP_Compass_Backend();
|
||||
|
||||
// we declare a virtual destructor so that drivers can
|
||||
// override with a custom destructor if need be.
|
||||
|
@ -25,17 +25,16 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_Compass_HIL::AP_Compass_HIL(Compass &compass):
|
||||
AP_Compass_Backend(compass)
|
||||
AP_Compass_HIL::AP_Compass_HIL()
|
||||
{
|
||||
memset(_compass_instance, 0, sizeof(_compass_instance));
|
||||
_compass._setup_earth_field();
|
||||
}
|
||||
|
||||
// detect the sensor
|
||||
AP_Compass_Backend *AP_Compass_HIL::detect(Compass &compass)
|
||||
AP_Compass_Backend *AP_Compass_HIL::detect()
|
||||
{
|
||||
AP_Compass_HIL *sensor = new AP_Compass_HIL(compass);
|
||||
AP_Compass_HIL *sensor = new AP_Compass_HIL();
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -7,12 +7,12 @@
|
||||
class AP_Compass_HIL : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
AP_Compass_HIL(Compass &compass);
|
||||
AP_Compass_HIL();
|
||||
void read(void);
|
||||
bool init(void);
|
||||
|
||||
// detect the sensor
|
||||
static AP_Compass_Backend *detect(Compass &compass);
|
||||
static AP_Compass_Backend *detect();
|
||||
|
||||
private:
|
||||
uint8_t _compass_instance[HIL_NUM_COMPASSES];
|
||||
|
@ -94,10 +94,9 @@ extern const AP_HAL::HAL& hal;
|
||||
#define HMC5843_REG_ID_A 0x0A
|
||||
|
||||
|
||||
AP_Compass_HMC5843::AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus,
|
||||
AP_Compass_HMC5843::AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,
|
||||
bool force_external, enum Rotation rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _bus(bus)
|
||||
: _bus(bus)
|
||||
, _rotation(rotation)
|
||||
, _force_external(force_external)
|
||||
{
|
||||
@ -108,8 +107,7 @@ AP_Compass_HMC5843::~AP_Compass_HMC5843()
|
||||
delete _bus;
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_Backend *AP_Compass_HMC5843::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
@ -121,7 +119,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, force_external, rotation);
|
||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, force_external, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -130,7 +128,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(Compass &compass, enum Rotation rotation)
|
||||
AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation)
|
||||
{
|
||||
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
||||
|
||||
@ -141,7 +139,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(Compass &compass, enum Rot
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, false, rotation);
|
||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, false, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -16,13 +16,11 @@ class AP_HMC5843_BusDriver;
|
||||
class AP_Compass_HMC5843 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
static AP_Compass_Backend *probe_mpu6000(Compass &compass,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "HMC5843";
|
||||
|
||||
@ -31,7 +29,7 @@ public:
|
||||
void read() override;
|
||||
|
||||
private:
|
||||
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus,
|
||||
AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,
|
||||
bool force_external, enum Rotation rotation);
|
||||
|
||||
bool init();
|
||||
|
@ -75,8 +75,7 @@ static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
@ -84,7 +83,7 @@ AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass,
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(compass, std::move(dev), force_external, rotation);
|
||||
AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(std::move(dev), force_external, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -93,12 +92,10 @@ AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_IST8310::AP_Compass_IST8310(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_IST8310::AP_Compass_IST8310(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
: _dev(std::move(dev))
|
||||
, _rotation(rotation)
|
||||
, _force_external(force_external)
|
||||
{
|
||||
|
@ -31,8 +31,7 @@
|
||||
class AP_Compass_IST8310 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
@ -41,8 +40,7 @@ public:
|
||||
static constexpr const char *name = "IST8310";
|
||||
|
||||
private:
|
||||
AP_Compass_IST8310(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_IST8310(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
|
||||
|
@ -48,15 +48,14 @@
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_Backend *AP_Compass_LIS3MDL::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_LIS3MDL *sensor = new AP_Compass_LIS3MDL(compass, std::move(dev), force_external, rotation);
|
||||
AP_Compass_LIS3MDL *sensor = new AP_Compass_LIS3MDL(std::move(dev), force_external, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -65,12 +64,10 @@ AP_Compass_Backend *AP_Compass_LIS3MDL::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
bool _force_external,
|
||||
enum Rotation _rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, dev(std::move(_dev))
|
||||
: dev(std::move(_dev))
|
||||
, force_external(_force_external)
|
||||
, rotation(_rotation)
|
||||
{
|
||||
|
@ -33,8 +33,7 @@
|
||||
class AP_Compass_LIS3MDL : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
@ -43,7 +42,7 @@ public:
|
||||
static constexpr const char *name = "LIS3MDL";
|
||||
|
||||
private:
|
||||
AP_Compass_LIS3MDL(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
|
||||
|
@ -150,20 +150,18 @@ extern const AP_HAL::HAL &hal;
|
||||
#define LSM303D_MAG_DEFAULT_RANGE_GA 2
|
||||
#define LSM303D_MAG_DEFAULT_RATE 100
|
||||
|
||||
AP_Compass_LSM303D::AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
AP_Compass_LSM303D::AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: _dev(std::move(dev))
|
||||
{
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_LSM303D::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_Backend *AP_Compass_LSM303D::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(compass, std::move(dev));
|
||||
AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(std::move(dev));
|
||||
if (!sensor || !sensor->init(rotation)) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -11,8 +11,7 @@
|
||||
class AP_Compass_LSM303D : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "LSM303D";
|
||||
@ -22,7 +21,7 @@ public:
|
||||
virtual ~AP_Compass_LSM303D() { }
|
||||
|
||||
private:
|
||||
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
bool init(enum Rotation rotation);
|
||||
uint8_t _register_read(uint8_t reg);
|
||||
|
@ -57,23 +57,20 @@ struct PACKED sample_regs {
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_LSM9DS1::AP_Compass_LSM9DS1(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_LSM9DS1::AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
: _dev(std::move(dev))
|
||||
, _rotation(rotation)
|
||||
{
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_LSM9DS1::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_Backend *AP_Compass_LSM9DS1::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(compass, std::move(dev), rotation);
|
||||
AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(std::move(dev), rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -11,8 +11,7 @@
|
||||
class AP_Compass_LSM9DS1 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "LSM9DS1";
|
||||
@ -22,7 +21,7 @@ public:
|
||||
virtual ~AP_Compass_LSM9DS1() {}
|
||||
|
||||
private:
|
||||
AP_Compass_LSM9DS1(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
bool init();
|
||||
bool _check_id(void);
|
||||
|
@ -80,20 +80,18 @@ RUS:
|
||||
|
||||
|
||||
|
||||
AP_Compass_MAG3110::AP_Compass_MAG3110(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
AP_Compass_MAG3110::AP_Compass_MAG3110(AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: _dev(std::move(dev))
|
||||
{
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_MAG3110::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_Backend *AP_Compass_MAG3110::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_MAG3110 *sensor = new AP_Compass_MAG3110(compass, std::move(dev));
|
||||
AP_Compass_MAG3110 *sensor = new AP_Compass_MAG3110(std::move(dev));
|
||||
if (!sensor || !sensor->init(rotation)) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -16,8 +16,7 @@
|
||||
class AP_Compass_MAG3110 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "MAG3110";
|
||||
@ -27,7 +26,7 @@ public:
|
||||
~AP_Compass_MAG3110() { }
|
||||
|
||||
private:
|
||||
AP_Compass_MAG3110(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
AP_Compass_MAG3110(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
bool init(enum Rotation rotation);
|
||||
|
||||
|
@ -41,15 +41,14 @@ extern const AP_HAL::HAL &hal;
|
||||
// datasheet says 50ms min for refill
|
||||
#define MIN_DELAY_SET_RESET 50
|
||||
|
||||
AP_Compass_Backend *AP_Compass_MMC3416::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_MMC3416 *sensor = new AP_Compass_MMC3416(compass, std::move(dev), force_external, rotation);
|
||||
AP_Compass_MMC3416 *sensor = new AP_Compass_MMC3416(std::move(dev), force_external, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -58,12 +57,10 @@ AP_Compass_Backend *AP_Compass_MMC3416::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_MMC3416::AP_Compass_MMC3416(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
AP_Compass_MMC3416::AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||
bool _force_external,
|
||||
enum Rotation _rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, dev(std::move(_dev))
|
||||
: dev(std::move(_dev))
|
||||
, force_external(_force_external)
|
||||
, rotation(_rotation)
|
||||
{
|
||||
|
@ -29,8 +29,7 @@
|
||||
class AP_Compass_MMC3416 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external = false,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
@ -39,7 +38,7 @@ public:
|
||||
static constexpr const char *name = "MMC3416";
|
||||
|
||||
private:
|
||||
AP_Compass_MMC3416(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
|
||||
|
@ -57,16 +57,15 @@
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_Backend *AP_Compass_QMC5883L::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AP_Compass_QMC5883L *sensor = new AP_Compass_QMC5883L(compass, std::move(dev),force_external,rotation);
|
||||
AP_Compass_QMC5883L *sensor = new AP_Compass_QMC5883L(std::move(dev),force_external,rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -75,12 +74,10 @@ AP_Compass_Backend *AP_Compass_QMC5883L::probe(Compass &compass,
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_QMC5883L::AP_Compass_QMC5883L(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
: AP_Compass_Backend(compass)
|
||||
, _dev(std::move(dev))
|
||||
AP_Compass_QMC5883L::AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation)
|
||||
: _dev(std::move(dev))
|
||||
, _rotation(rotation)
|
||||
, _force_external(force_external)
|
||||
{
|
||||
|
@ -42,8 +42,7 @@
|
||||
class AP_Compass_QMC5883L : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation = ROTATION_NONE);
|
||||
|
||||
@ -52,10 +51,9 @@ public:
|
||||
static constexpr const char *name = "QMC5883L";
|
||||
|
||||
private:
|
||||
AP_Compass_QMC5883L(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
|
||||
void _dump_registers();
|
||||
bool _check_whoami();
|
||||
|
@ -5,16 +5,15 @@
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Compass_SITL::AP_Compass_SITL(Compass &compass):
|
||||
AP_Compass_SITL::AP_Compass_SITL():
|
||||
_sitl(AP::sitl()),
|
||||
_has_sample(false),
|
||||
AP_Compass_Backend(compass)
|
||||
{
|
||||
if (_sitl != nullptr) {
|
||||
_compass._setup_earth_field();
|
||||
for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
|
||||
// default offsets to correct value
|
||||
compass.set_offsets(i, _sitl->mag_ofs);
|
||||
_compass.set_offsets(i, _sitl->mag_ofs);
|
||||
|
||||
_compass_instance[i] = register_compass();
|
||||
set_dev_id(_compass_instance[i], AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 0, DEVTYPE_SITL));
|
||||
|
@ -13,7 +13,7 @@
|
||||
|
||||
class AP_Compass_SITL : public AP_Compass_Backend {
|
||||
public:
|
||||
AP_Compass_SITL(Compass &);
|
||||
AP_Compass_SITL();
|
||||
|
||||
void read(void);
|
||||
|
||||
|
@ -38,15 +38,12 @@ UC_REGISTRY_BINDER(Mag2Cb, uavcan::equipment::ahrs::MagneticFieldStrength2);
|
||||
AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[] = {0};
|
||||
AP_HAL::Semaphore* AP_Compass_UAVCAN::_sem_registry = nullptr;
|
||||
|
||||
/*
|
||||
constructor - registers instance at top Compass driver
|
||||
*/
|
||||
AP_Compass_UAVCAN::AP_Compass_UAVCAN(Compass &compass, AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id):
|
||||
AP_Compass_Backend(compass),
|
||||
_ap_uavcan(ap_uavcan),
|
||||
_node_id(node_id),
|
||||
_sensor_id(sensor_id)
|
||||
{}
|
||||
AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id)
|
||||
: _ap_uavcan(ap_uavcan)
|
||||
, _node_id(node_id)
|
||||
, _sensor_id(sensor_id)
|
||||
{
|
||||
}
|
||||
|
||||
void AP_Compass_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
|
||||
{
|
||||
@ -86,7 +83,7 @@ void AP_Compass_UAVCAN::give_registry()
|
||||
_sem_registry->give();
|
||||
}
|
||||
|
||||
AP_Compass_Backend* AP_Compass_UAVCAN::probe(Compass& _frontend)
|
||||
AP_Compass_Backend* AP_Compass_UAVCAN::probe()
|
||||
{
|
||||
if (!take_registry()) {
|
||||
return nullptr;
|
||||
@ -95,7 +92,7 @@ AP_Compass_Backend* AP_Compass_UAVCAN::probe(Compass& _frontend)
|
||||
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
||||
if (!_detected_modules[i].driver && _detected_modules[i].ap_uavcan) {
|
||||
// Register new Compass mode to a backend
|
||||
driver = new AP_Compass_UAVCAN(_frontend, _detected_modules[i].ap_uavcan, _detected_modules[i].node_id, _detected_modules[i].sensor_id);
|
||||
driver = new AP_Compass_UAVCAN(_detected_modules[i].ap_uavcan, _detected_modules[i].node_id, _detected_modules[i].sensor_id);
|
||||
if (driver) {
|
||||
_detected_modules[i].driver = driver;
|
||||
driver->init();
|
||||
|
@ -10,12 +10,12 @@ class Mag2Cb;
|
||||
|
||||
class AP_Compass_UAVCAN : public AP_Compass_Backend {
|
||||
public:
|
||||
AP_Compass_UAVCAN(Compass &compass, AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id);
|
||||
AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id);
|
||||
|
||||
void read(void) override;
|
||||
|
||||
static void subscribe_msgs(AP_UAVCAN* ap_uavcan);
|
||||
static AP_Compass_Backend* probe(Compass& _frontend);
|
||||
static AP_Compass_Backend* probe();
|
||||
|
||||
static void handle_magnetic_field(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MagCb &cb);
|
||||
static void handle_magnetic_field_2(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Mag2Cb &cb);
|
||||
|
Loading…
Reference in New Issue
Block a user