mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Compass: HMC5843: add parameter force_external to constructor
And to the detection probe() method. That way we don't need to use a board `#ifdef` inside the class code. Additionally, we make raspilot board use it.
This commit is contained in:
parent
54fd3702c3
commit
670b0071f9
@ -440,7 +440,7 @@ void Compass::_detect_backends(void)
|
|||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QURT
|
||||||
_add_backend(AP_Compass_QURT::detect(*this));
|
_add_backend(AP_Compass_QURT::detect(*this));
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RASPILOT
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_RASPILOT
|
||||||
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)));
|
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR), true));
|
||||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device("lsm9ds0_am")));
|
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device("lsm9ds0_am")));
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
|
||||||
// detect_mpu9250() failed will cause panic if no actual mpu9250 backend,
|
// detect_mpu9250() failed will cause panic if no actual mpu9250 backend,
|
||||||
|
@ -88,9 +88,11 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#define HMC5843_REG_DATA_OUTPUT_X_MSB 0x03
|
#define HMC5843_REG_DATA_OUTPUT_X_MSB 0x03
|
||||||
|
|
||||||
AP_Compass_HMC5843::AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus)
|
AP_Compass_HMC5843::AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus,
|
||||||
|
bool force_external)
|
||||||
: AP_Compass_Backend(compass)
|
: AP_Compass_Backend(compass)
|
||||||
, _bus(bus)
|
, _bus(bus)
|
||||||
|
, _force_external(force_external)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -100,14 +102,15 @@ AP_Compass_HMC5843::~AP_Compass_HMC5843()
|
|||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
|
bool force_external)
|
||||||
{
|
{
|
||||||
AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
|
AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
|
||||||
if (!bus) {
|
if (!bus) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus);
|
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, force_external);
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -127,7 +130,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(Compass &compass)
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus);
|
AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(compass, bus, false);
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -181,10 +184,9 @@ bool AP_Compass_HMC5843::init()
|
|||||||
_compass_instance = register_compass();
|
_compass_instance = register_compass();
|
||||||
set_dev_id(_compass_instance, _product_id);
|
set_dev_id(_compass_instance, _product_id);
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
if (_force_external) {
|
||||||
// FIXME: wrong way to force external compass
|
set_external(_compass_instance, true);
|
||||||
set_external(_compass_instance, true);
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
|
@ -18,7 +18,8 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(Compass &compass,
|
static AP_Compass_Backend *probe(Compass &compass,
|
||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
|
bool force_external = false);
|
||||||
|
|
||||||
static AP_Compass_Backend *probe_mpu6000(Compass &compass);
|
static AP_Compass_Backend *probe_mpu6000(Compass &compass);
|
||||||
|
|
||||||
@ -29,7 +30,8 @@ public:
|
|||||||
void accumulate() override;
|
void accumulate() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus);
|
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus,
|
||||||
|
bool force_external);
|
||||||
|
|
||||||
bool _detect_version();
|
bool _detect_version();
|
||||||
bool _calibrate();
|
bool _calibrate();
|
||||||
@ -61,6 +63,7 @@ private:
|
|||||||
uint8_t _product_id;
|
uint8_t _product_id;
|
||||||
|
|
||||||
bool _initialised;
|
bool _initialised;
|
||||||
|
bool _force_external;
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_HMC5843_BusDriver
|
class AP_HMC5843_BusDriver
|
||||||
|
Loading…
Reference in New Issue
Block a user