AP_Compass: enable AK09916 inside a ICM20948

the ICM20948 has an AK09916 which can be accessed via I2C bypass
This commit is contained in:
Andrew Tridgell 2017-05-24 10:45:19 +02:00
parent 5936fc1ff8
commit d946d5da6f
4 changed files with 101 additions and 5 deletions

View File

@ -532,7 +532,22 @@ void Compass::_detect_backends(void)
ADD_BACKEND(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR),
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
AP_Compass_HMC5843::name, both_i2c_external);
#if !HAL_MINIMIZE_FEATURES
// AK09916 on ICM20948
ADD_BACKEND(AP_Compass_AK09916::probe_ICM20948(*this,
hal.i2c_mgr->get_device(1, HAL_COMPASS_AK09916_I2C_ADDR),
hal.i2c_mgr->get_device(1, HAL_COMPASS_ICM20948_I2C_ADDR),
true, ROTATION_NONE),
AP_Compass_AK09916::name, true);
ADD_BACKEND(AP_Compass_AK09916::probe_ICM20948(*this,
hal.i2c_mgr->get_device(0, HAL_COMPASS_AK09916_I2C_ADDR),
hal.i2c_mgr->get_device(0, HAL_COMPASS_ICM20948_I2C_ADDR),
both_i2c_external, ROTATION_NONE),
AP_Compass_AK09916::name, true);
#if 0
// lis3mdl - this is disabled for now due to an errata on pixhawk2 GPS unit, pending investigation
ADD_BACKEND(AP_Compass_LIS3MDL::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_LIS3MDL_I2C_ADDR),

View File

@ -37,8 +37,17 @@
#define REG_CNTL2 0x31
#define REG_CNTL3 0x32
#define REG_ICM_WHOAMI 0x00
#define REG_ICM_PWR_MGMT_1 0x06
#define REG_ICM_INT_PIN_CFG 0x0f
#define ICM_WHOAMI_VAL 0xEA
extern const AP_HAL::HAL &hal;
/*
probe for AK09916 directly on I2C
*/
AP_Compass_Backend *AP_Compass_AK09916::probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
bool force_external,
@ -47,7 +56,33 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(Compass &compass,
if (!dev) {
return nullptr;
}
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), force_external, rotation);
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), nullptr,
force_external,
rotation, AK09916_I2C);
if (!sensor || !sensor->init()) {
delete sensor;
return nullptr;
}
return sensor;
}
/*
probe for AK09916 connected via an ICM20948
*/
AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
bool force_external,
enum Rotation rotation)
{
if (!dev) {
return nullptr;
}
AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(compass, std::move(dev), std::move(dev_icm),
force_external,
rotation, AK09916_ICM20948_I2C);
if (!sensor || !sensor->init()) {
delete sensor;
return nullptr;
@ -58,12 +93,16 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(Compass &compass,
AP_Compass_AK09916::AP_Compass_AK09916(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
AP_HAL::OwnPtr<AP_HAL::Device> _dev_icm,
bool _force_external,
enum Rotation _rotation)
enum Rotation _rotation,
enum bus_type _bus_type)
: AP_Compass_Backend(compass)
, dev(std::move(_dev))
, dev_icm(std::move(_dev_icm))
, force_external(_force_external)
, rotation(_rotation)
, bus_type(_bus_type)
{
}
@ -73,6 +112,26 @@ bool AP_Compass_AK09916::init()
return false;
}
if (bus_type == AK09916_ICM20948_I2C && dev_icm) {
uint8_t rval;
if (!dev_icm->read_registers(REG_ICM_WHOAMI, &rval, 1) ||
rval != ICM_WHOAMI_VAL) {
// not an ICM_WHOAMI
goto fail;
}
// see if ICM20948 is sleeping
if (!dev_icm->read_registers(REG_ICM_PWR_MGMT_1, &rval, 1)) {
goto fail;
}
if (rval & 0x40) {
// bring out of sleep mode, use internal oscillator
dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x00);
hal.scheduler->delay(10);
}
// enable i2c bypass
dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x02);
}
uint16_t whoami;
if (!dev->read_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2) ||
whoami != 0x0948) {
@ -98,7 +157,7 @@ bool AP_Compass_AK09916::init()
set_external(compass_instance, true);
}
dev->set_device_type(DEVTYPE_AK09916);
dev->set_device_type(bus_type == AK09916_ICM20948_I2C?DEVTYPE_ICM20948:DEVTYPE_AK09916);
set_dev_id(compass_instance, dev->get_bus_id());
// call timer() at 100Hz

View File

@ -26,6 +26,11 @@
# define HAL_COMPASS_AK09916_I2C_ADDR 0x0C
#endif
// the AK09916 can be connected via an ICM20948
#ifndef HAL_COMPASS_ICM20948_I2C_ADDR
# define HAL_COMPASS_ICM20948_I2C_ADDR 0x69
#endif
class AP_Compass_AK09916 : public AP_Compass_Backend
{
public:
@ -34,16 +39,32 @@ public:
bool force_external = false,
enum Rotation rotation = ROTATION_NONE);
// separate probe function for when behind a ICM20948 IMU
static AP_Compass_Backend *probe_ICM20948(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
bool force_external = false,
enum Rotation rotation = ROTATION_NONE);
void read() override;
static constexpr const char *name = "AK09916";
private:
AP_Compass_AK09916(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum bus_type {
AK09916_I2C=0,
AK09916_ICM20948_I2C,
} bus_type;
AP_Compass_AK09916(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev_icm,
bool force_external,
enum Rotation rotation);
enum Rotation rotation,
enum bus_type bus_type);
AP_HAL::OwnPtr<AP_HAL::Device> dev;
AP_HAL::OwnPtr<AP_HAL::Device> dev_icm;
/**
* Device periodic callback to read data from the sensor.

View File

@ -59,6 +59,7 @@ public:
DEVTYPE_LIS3MDL = 0x08,
DEVTYPE_AK09916 = 0x09,
DEVTYPE_IST8310 = 0x0A,
DEVTYPE_ICM20948 = 0x0B,
};