mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Compass: allow rotation of BMM150 compass
This commit is contained in:
parent
1cb775e2c2
commit
df387dc396
@ -789,7 +789,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)));
|
||||
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), 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)
|
||||
AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev));
|
||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev), 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)
|
||||
: _dev(std::move(dev))
|
||||
AP_Compass_BMM150::AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, enum Rotation rotation)
|
||||
: _dev(std::move(dev)), _rotation(rotation)
|
||||
{
|
||||
}
|
||||
|
||||
@ -216,6 +216,8 @@ bool AP_Compass_BMM150::init()
|
||||
/* register the compass instance in the frontend */
|
||||
_compass_instance = register_compass();
|
||||
|
||||
set_rotation(_compass_instance, _rotation);
|
||||
|
||||
_dev->set_device_type(DEVTYPE_BMM150);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
|
@ -27,14 +27,14 @@
|
||||
class AP_Compass_BMM150 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, enum Rotation rotation);
|
||||
|
||||
void read() override;
|
||||
|
||||
static constexpr const char *name = "BMM150";
|
||||
|
||||
private:
|
||||
AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
AP_Compass_BMM150(AP_HAL::OwnPtr<AP_HAL::Device> dev, enum Rotation rotation);
|
||||
|
||||
/**
|
||||
* Device periodic callback to read data from the sensor.
|
||||
@ -65,4 +65,5 @@ private:
|
||||
|
||||
uint32_t _last_read_ms;
|
||||
AP_HAL::Util::perf_counter_t _perf_err;
|
||||
enum Rotation _rotation;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user