Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
197 changes: 118 additions & 79 deletions libraries/AP_Compass/AP_Compass.cpp

Large diffs are not rendered by default.

10 changes: 10 additions & 0 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -503,6 +503,16 @@ friend class AP_Compass_DroneCAN;
bool _driver_enabled(enum DriverType driver_type);
void add_backend(DriverType driver_type, AP_Compass_Backend *backend);

// helper probe functions
void probe_ak09916_via_icm20948(uint8_t i2c_bus, uint8_t ak09916_addr, uint8_t icm20948_addr, bool external, Rotation rotation);
void probe_ak09916_via_icm20948(uint8_t ins_instance, Rotation rotation);
void probe_ak8963_via_mpu9250(uint8_t imu_instance, Rotation rotation);
void probe_i2c_dev(DriverType driver_type, AP_Compass_Backend* (*probefn)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation), uint8_t i2c_bus, uint8_t i2c_addr, bool external, Rotation rotation);
void probe_spi_dev(DriverType driver_type, AP_Compass_Backend* (*probefn)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation), const char *name, bool external, Rotation rotation);
// short-lived method which expectes a probe function that doesn't
// offer the ability to specify an external rotation
void probe_spi_dev(DriverType driver_type, AP_Compass_Backend* (*probefn)(AP_HAL::OwnPtr<AP_HAL::Device>, Rotation), const char *name, Rotation rotation);

// backend objects
AP_Compass_Backend *_backends[COMPASS_MAX_BACKEND];
uint8_t _backend_count;
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_Compass/AP_Compass_AK09916.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ AP_Compass_AK09916::~AP_Compass_AK09916()
delete _bus;
}

AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand All @@ -94,8 +94,8 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice>
}

#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,
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::Device> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev_icm,
bool force_external,
enum Rotation rotation)
{
Expand Down Expand Up @@ -362,8 +362,8 @@ bool AP_Compass_AK09916::_reset()
return _bus->register_write(REG_CNTL3, 0x01); //Soft Reset
}

/* AP_HAL::I2CDevice implementation of the AK09916 */
AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
/* AP_HAL::Device implementation of the AK09916 */
AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)
: _dev(std::move(dev))
{
}
Expand Down
12 changes: 6 additions & 6 deletions libraries/AP_Compass/AP_Compass_AK09916.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand Down Expand Up @@ -48,14 +48,14 @@ class AP_Compass_AK09916 : public AP_Compass_Backend
{
public:
/* Probe for AK09916 standalone on I2C bus */
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
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,
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::Device> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev_icm,
bool force_external,
enum Rotation rotation);

Expand Down Expand Up @@ -141,7 +141,7 @@ class AP_AK09916_BusDriver
class AP_AK09916_BusDriver_HALDevice: public AP_AK09916_BusDriver
{
public:
AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);

virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
virtual bool register_read(uint8_t reg, uint8_t *val) override;
Expand Down Expand Up @@ -173,7 +173,7 @@ class AP_AK09916_BusDriver_HALDevice: public AP_AK09916_BusDriver
}

private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
};

class AP_AK09916_BusDriver_Auxiliary : public AP_AK09916_BusDriver
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Compass/AP_Compass_AK8963.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ AP_Compass_AK8963::~AP_Compass_AK8963()
delete _bus;
}

AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum Rotation rotation)
{
if (!dev) {
Expand All @@ -83,7 +83,7 @@ AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> d
return sensor;
}

AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum Rotation rotation)
{
if (!dev) {
Expand Down Expand Up @@ -271,8 +271,8 @@ bool AP_Compass_AK8963::_calibrate()
return true;
}

/* AP_HAL::I2CDevice implementation of the AK8963 */
AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
/* AP_HAL::Device implementation of the AK8963 */
AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)
: _dev(std::move(dev))
{
}
Expand Down
11 changes: 5 additions & 6 deletions libraries/AP_Compass/AP_Compass_AK8963.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/SPIDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand All @@ -22,11 +21,11 @@ class AP_Compass_AK8963 : public AP_Compass_Backend
{
public:
/* Probe for AK8963 standalone on I2C bus */
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum Rotation rotation);

/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum Rotation rotation);

/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
Expand Down Expand Up @@ -93,7 +92,7 @@ class AP_AK8963_BusDriver
class AP_AK8963_BusDriver_HALDevice: public AP_AK8963_BusDriver
{
public:
AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);

virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
virtual bool register_read(uint8_t reg, uint8_t *val) override;
Expand All @@ -113,7 +112,7 @@ class AP_AK8963_BusDriver_HALDevice: public AP_AK8963_BusDriver
}

private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
};

class AP_AK8963_BusDriver_Auxiliary : public AP_AK8963_BusDriver
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_BMM150.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@

extern const AP_HAL::HAL &hal;

AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, bool force_external, enum Rotation rotation)
AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev, bool force_external, enum Rotation rotation)
{
if (!dev) {
return nullptr;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_BMM150.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand All @@ -34,7 +34,7 @@
class AP_Compass_BMM150 : public AP_Compass_Backend
{
public:
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, bool force_external, enum Rotation rotation);
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev, bool force_external, enum Rotation rotation);

void read() override;

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_BMM350.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_IIS2MDC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

extern const AP_HAL::HAL &hal;

AP_Compass_Backend *AP_Compass_IIS2MDC::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_IIS2MDC::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_IIS2MDC.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#if AP_COMPASS_IIS2MDC_ENABLED

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>

#include "AP_Compass.h"
#include "AP_Compass_Backend.h"
Expand All @@ -40,7 +40,7 @@
class AP_Compass_IIS2MDC : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_IST8308.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@

extern const AP_HAL::HAL &hal;

AP_Compass_Backend *AP_Compass_IST8308::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_IST8308::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_IST8308.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>

#include "AP_Compass_Backend.h"

Expand All @@ -33,7 +33,7 @@
class AP_Compass_IST8308 : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_IST8310.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;

extern const AP_HAL::HAL &hal;

AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_IST8310.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass_Backend.h"
Expand All @@ -38,7 +38,7 @@
class AP_Compass_IST8310 : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_MMC3416.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ extern const AP_HAL::HAL &hal;
// datasheet says 50ms min for refill
#define MIN_DELAY_SET_RESET 50

AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_MMC3416.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand All @@ -33,7 +33,7 @@
class AP_Compass_MMC3416 : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_MMC5xx3.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_QMC5883L.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
#define QMC5883L_REG_ID 0x0D
#define QMC5883_ID_VAL 0xFF

AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_QMC5883L.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass.h"
Expand All @@ -46,7 +46,7 @@
class AP_Compass_QMC5883L : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Compass/AP_Compass_QMC5883P.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@
#define DEBUG 0
#endif

AP_Compass_Backend *AP_Compass_QMC5883P::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_Compass_Backend *AP_Compass_QMC5883P::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Compass/AP_Compass_QMC5883P.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#pragma once

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>

#include "AP_Compass_config.h"
Expand Down Expand Up @@ -45,7 +45,7 @@
class AP_Compass_QMC5883P : 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::Device> dev,
bool force_external,
enum Rotation rotation);

Expand Down
Loading