AP_Compass: fixed external handling for BMM150
This commit is contained in:
parent
3d4a8829f3
commit
09603e29ce
@ -1167,7 +1167,7 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
FOREACH_I2C_EXTERNAL(i) {
|
||||
for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {
|
||||
ADD_BACKEND(DRIVER_BMM150,
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), ROTATION_NONE));
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
|
||||
}
|
||||
}
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
@ -1235,7 +1235,7 @@ void Compass::_detect_backends(void)
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_PCNC1:
|
||||
ADD_BACKEND(DRIVER_BMM150,
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), ROTATION_NONE));
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), false, ROTATION_NONE));
|
||||
break;
|
||||
case AP_BoardConfig::VRX_BOARD_BRAIN54: {
|
||||
// external i2c bus
|
||||
|
@ -63,12 +63,12 @@
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, enum Rotation rotation)
|
||||
AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, bool force_external, enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev), rotation);
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev), force_external, rotation);
|
||||
if (!sensor || !sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
@ -77,8 +77,8 @@ AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> d
|
||||
return sensor;
|
||||
}
|
||||
|
||||
AP_Compass_BMM150::AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, enum Rotation rotation)
|
||||
: _dev(std::move(dev)), _rotation(rotation)
|
||||
AP_Compass_BMM150::AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, bool force_external, enum Rotation rotation)
|
||||
: _dev(std::move(dev)), _rotation(rotation), _force_external(force_external)
|
||||
{
|
||||
}
|
||||
|
||||
@ -219,6 +219,9 @@ bool AP_Compass_BMM150::init()
|
||||
|
||||
set_rotation(_compass_instance, _rotation);
|
||||
|
||||
if (_force_external) {
|
||||
set_external(_compass_instance, true);
|
||||
}
|
||||
|
||||
_perf_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "BMM150_err");
|
||||
|
||||
|
@ -30,14 +30,14 @@
|
||||
class AP_Compass_BMM150 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, enum Rotation rotation);
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, bool force_external, enum Rotation rotation);
|
||||
|
||||
void read() override;
|
||||
|
||||
static constexpr const char *name = "BMM150";
|
||||
|
||||
private:
|
||||
AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, enum Rotation rotation);
|
||||
AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, bool force_external, enum Rotation rotation);
|
||||
|
||||
/**
|
||||
* Device periodic callback to read data from the sensor.
|
||||
@ -69,4 +69,5 @@ private:
|
||||
uint32_t _last_read_ms;
|
||||
AP_HAL::Util::perf_counter_t _perf_err;
|
||||
enum Rotation _rotation;
|
||||
bool _force_external;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user