mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Compass: AK8963: be agnostic to I2C bus/address
This decision is better made by the caller rather than polluting the driver with board-specific details.
This commit is contained in:
parent
d92c2ac9f5
commit
a5df93bf10
@ -79,10 +79,6 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(HAL_COMPASS_AK8963_I2C_ADDR)
|
|
||||||
#define HAL_COMPASS_AK8963_I2C_ADDR 0xC
|
|
||||||
#endif
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus) :
|
AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus) :
|
||||||
@ -112,11 +108,13 @@ AP_Compass_Backend *AP_Compass_AK8963::detect_mpu9250(Compass &compass)
|
|||||||
return sensor;
|
return sensor;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_Backend *AP_Compass_AK8963::detect_i2c1(Compass &compass)
|
|
||||||
|
AP_Compass_Backend *AP_Compass_AK8963::detect_i2c(Compass &compass,
|
||||||
|
AP_HAL::I2CDriver *i2c,
|
||||||
|
uint8_t addr)
|
||||||
{
|
{
|
||||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass,
|
AP_Compass_AK8963 *sensor =
|
||||||
new AP_AK8963_SerialBus_I2C(
|
new AP_Compass_AK8963(compass, new AP_AK8963_SerialBus_I2C(i2c, addr));
|
||||||
hal.i2c1, HAL_COMPASS_AK8963_I2C_ADDR));
|
|
||||||
|
|
||||||
if (sensor == nullptr) {
|
if (sensor == nullptr) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -37,7 +37,9 @@ public:
|
|||||||
AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus);
|
AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus);
|
||||||
|
|
||||||
static AP_Compass_Backend *detect_mpu9250(Compass &compass);
|
static AP_Compass_Backend *detect_mpu9250(Compass &compass);
|
||||||
static AP_Compass_Backend *detect_i2c1(Compass &compass);
|
static AP_Compass_Backend *detect_i2c(Compass &compass,
|
||||||
|
AP_HAL::I2CDriver *i2c,
|
||||||
|
uint8_t addr);
|
||||||
|
|
||||||
bool init(void);
|
bool init(void);
|
||||||
void read(void);
|
void read(void);
|
||||||
|
@ -348,7 +348,8 @@ void Compass::_detect_backends(void)
|
|||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
|
||||||
_add_backend(AP_Compass_HMC5843::detect(*this));
|
_add_backend(AP_Compass_HMC5843::detect(*this));
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
|
||||||
_add_backend(AP_Compass_AK8963::detect_i2c1(*this));
|
_add_backend(AP_Compass_AK8963::detect_i2c(*this, hal.i2c1,
|
||||||
|
HAL_COMPASS_AK8963_I2C_ADDR));
|
||||||
#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
|
||||||
_add_backend(AP_Compass_PX4::detect(*this));
|
_add_backend(AP_Compass_PX4::detect(*this));
|
||||||
#else
|
#else
|
||||||
|
Loading…
Reference in New Issue
Block a user