mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_Compass: add and use AP_COMPASS_ICM20948_ENABLED
This commit is contained in:
parent
648fe94d2e
commit
ee6b44113d
@ -1107,7 +1107,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
// AK09916 on ICM20948
|
||||
#if AP_COMPASS_AK09916_ENABLED
|
||||
#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
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),
|
||||
@ -1127,7 +1127,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
all_external, ROTATION_PITCH_180_YAW_90));
|
||||
}
|
||||
#endif
|
||||
#endif // AP_COMPASS_AK09916_ENABLED
|
||||
#endif // AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if AP_COMPASS_LIS3MDL_ENABLED
|
||||
@ -1380,7 +1380,7 @@ void Compass::_detect_backends(void)
|
||||
// first MPU9250 to run without disturbance at high rate
|
||||
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
|
||||
#endif
|
||||
#if AP_COMPASS_AK09916_ENABLED
|
||||
#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
|
||||
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
|
||||
#endif
|
||||
break;
|
||||
|
@ -438,7 +438,9 @@ private:
|
||||
#if AP_COMPASS_IST8310_ENABLED
|
||||
DRIVER_IST8310 =7,
|
||||
#endif
|
||||
#if AP_COMPASS_ICM20948_ENABLED
|
||||
DRIVER_ICM20948 =8,
|
||||
#endif
|
||||
DRIVER_MMC3416 =9,
|
||||
#if AP_COMPASS_UAVCAN_ENABLED
|
||||
DRIVER_UAVCAN =11,
|
||||
|
@ -100,6 +100,7 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
return sensor;
|
||||
}
|
||||
|
||||
#if AP_COMPASS_ICM20948_ENABLED
|
||||
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,
|
||||
@ -221,6 +222,7 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_I2C(uint8_t inv2_instance
|
||||
|
||||
return sensor;
|
||||
}
|
||||
#endif // AP_COMPASS_ICM20948_ENABLED
|
||||
|
||||
bool AP_Compass_AK09916::init()
|
||||
{
|
||||
|
@ -52,6 +52,7 @@ public:
|
||||
bool force_external,
|
||||
enum Rotation rotation);
|
||||
|
||||
#if AP_COMPASS_ICM20948_ENABLED
|
||||
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
||||
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
||||
@ -66,6 +67,7 @@ public:
|
||||
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
||||
static AP_Compass_Backend *probe_ICM20948_I2C(uint8_t mpu9250_instance,
|
||||
enum Rotation rotation);
|
||||
#endif
|
||||
|
||||
static constexpr const char *name = "AK09916";
|
||||
|
||||
|
@ -59,6 +59,10 @@
|
||||
#define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_ICM20948_ENABLED
|
||||
#define AP_COMPASS_ICM20948_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_IST8308_ENABLED
|
||||
#define AP_COMPASS_IST8308_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user