Path: blob/master/libraries/AP_Compass/AP_Compass_AK09916.cpp
9447 views
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15Driver by Andrew Tridgell, Nov 201616*/17#include "AP_Compass_AK09916.h"1819#if AP_COMPASS_AK09916_ENABLED2021#include <assert.h>22#include <AP_HAL/AP_HAL.h>23#include <utility>24#include <AP_Math/AP_Math.h>25#include <stdio.h>26#include <AP_InertialSensor/AP_InertialSensor_Invensensev2.h>27#include <GCS_MAVLink/GCS.h>28#include <AP_BoardConfig/AP_BoardConfig.h>2930extern const AP_HAL::HAL &hal;3132#define REG_COMPANY_ID 0x0033#define REG_DEVICE_ID 0x0134#define REG_ST1 0x1035#define REG_HXL 0x1136#define REG_HXH 0x1237#define REG_HYL 0x1338#define REG_HYH 0x1439#define REG_HZL 0x1540#define REG_HZH 0x1641#define REG_TMPS 0x1742#define REG_ST2 0x1843#define REG_CNTL1 0x3044#define REG_CNTL2 0x3145#define REG_CNTL3 0x324647#define REG_ICM_WHOAMI 0x0048#define REG_ICM_PWR_MGMT_1 0x0649#define REG_ICM_INT_PIN_CFG 0x0f5051#define ICM_WHOAMI_VAL 0xEA5253#define AK09915_Device_ID 0x1054#define AK09916_Device_ID 0x0955#define AK09918_Device_ID 0x0c56#define AK09916_MILLIGAUSS_SCALE 10.0f5758extern const AP_HAL::HAL &hal;5960AP_Compass_AK09916::AP_Compass_AK09916(AP_AK09916_BusDriver *bus,61bool force_external,62enum Rotation rotation)63: _bus(bus)64, _force_external(force_external)65, _rotation(rotation)66{67}6869AP_Compass_AK09916::~AP_Compass_AK09916()70{71delete _bus;72}7374AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,75bool force_external,76enum Rotation rotation)77{78if (!dev) {79return nullptr;80}81AP_AK09916_BusDriver *bus = NEW_NOTHROW AP_AK09916_BusDriver_HALDevice(std::move(dev));82if (!bus) {83return nullptr;84}8586AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, force_external, rotation);87if (!sensor || !sensor->init()) {88delete sensor;89return nullptr;90}9192return sensor;93}9495#if AP_COMPASS_ICM20948_ENABLED96AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::Device> dev,97AP_HAL::OwnPtr<AP_HAL::Device> dev_icm,98bool force_external,99enum Rotation rotation)100{101if (!dev || !dev_icm) {102return nullptr;103}104105dev->get_semaphore()->take_blocking();106107/* Allow ICM20x48 to shortcut auxiliary bus and host bus */108uint8_t rval;109uint16_t whoami;110uint8_t retries = 5;111if (!dev_icm->read_registers(REG_ICM_WHOAMI, &rval, 1) ||112rval != ICM_WHOAMI_VAL) {113// not an ICM_WHOAMI114goto fail;115}116do {117// reset then bring sensor out of sleep mode118if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x80)) {119goto fail;120}121hal.scheduler->delay(10);122123if (!dev_icm->write_register(REG_ICM_PWR_MGMT_1, 0x00)) {124goto fail;125}126hal.scheduler->delay(10);127128// see if ICM20948 is sleeping129if (!dev_icm->read_registers(REG_ICM_PWR_MGMT_1, &rval, 1)) {130goto fail;131}132if ((rval & 0x40) == 0) {133break;134}135} while (retries--);136137if (rval & 0x40) {138// it didn't come out of sleep139goto fail;140}141142// initially force i2c bypass off143dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x00);144hal.scheduler->delay(1);145146// now check if a AK09916 shows up on the bus. If it does then147// we have both a real AK09916 and a ICM20948 with an embedded148// AK09916. In that case we will fail the driver load and use149// the main AK09916 driver150if (dev->read_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2)) {151// a device is replying on the AK09916 I2C address, don't152// load the ICM20948153DEV_PRINTF("ICM20948: AK09916 bus conflict\n");154goto fail;155}156157// now force bypass on158dev_icm->write_register(REG_ICM_INT_PIN_CFG, 0x02);159hal.scheduler->delay(1);160dev->get_semaphore()->give();161return probe(std::move(dev), force_external, rotation);162fail:163dev->get_semaphore()->give();164return nullptr;165}166167// un-named, assume SPI for compat168AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(uint8_t inv2_instance,169enum Rotation rotation)170{171return probe_ICM20948_SPI(inv2_instance,rotation);172}173174AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_SPI(uint8_t inv2_instance,175enum Rotation rotation)176{177AP_InertialSensor &ins = AP::ins();178179AP_AK09916_BusDriver *bus =180NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);181if (!bus) {182return nullptr;183}184185AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);186if (!sensor || !sensor->init()) {187delete sensor;188return nullptr;189}190191return sensor;192}193194AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_I2C(uint8_t inv2_instance,195enum Rotation rotation)196{197AP_InertialSensor &ins = AP::ins();198199AP_AK09916_BusDriver *bus =200NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_I2C, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);201if (!bus) {202return nullptr;203}204205AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);206if (!sensor || !sensor->init()) {207delete sensor;208return nullptr;209}210211return sensor;212}213#endif // AP_COMPASS_ICM20948_ENABLED214215bool AP_Compass_AK09916::init()216{217AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();218219if (!bus_sem) {220return false;221}222_bus->get_semaphore()->take_blocking();223224if (!_bus->configure()) {225DEV_PRINTF("AK09916: Could not configure the bus\n");226goto fail;227}228229if (!_reset()) {230goto fail;231}232233if (!_check_id()) {234goto fail;235}236237// one checked register for mode238_bus->setup_checked_registers(1);239240if (!_setup_mode()) {241DEV_PRINTF("AK09916: Could not setup mode\n");242goto fail;243}244245if (!_bus->start_measurements()) {246DEV_PRINTF("AK09916: Could not start measurements\n");247goto fail;248}249250_initialized = true;251252/* register the compass instance in the frontend */253_bus->set_device_type(_devtype);254if (!register_compass(_bus->get_bus_id())) {255goto fail;256}257258if (_force_external) {259set_external(true);260}261262set_rotation(_rotation);263264bus_sem->give();265266_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK09916::_update, void));267268return true;269270fail:271bus_sem->give();272return false;273}274275void AP_Compass_AK09916::read()276{277if (!_initialized) {278return;279}280281drain_accumulated_samples();282}283284void AP_Compass_AK09916::_make_adc_sensitivity_adjustment(Vector3f& field) const285{286static const float ADC_16BIT_RESOLUTION = 0.15f;287288field *= ADC_16BIT_RESOLUTION;289}290291void AP_Compass_AK09916::_update()292{293struct sample_regs regs = {0};294Vector3f raw_field;295296if (!_bus->block_read(REG_ST1, (uint8_t *) ®s, sizeof(regs))) {297goto check_registers;298}299300if (!(regs.st1 & 0x01)) {301no_data++;302if (no_data == 5) {303_reset();304_setup_mode();305no_data = 0;306}307goto check_registers;308}309no_data = 0;310311/* Check for overflow. See AK09916's datasheet*/312if ((regs.st2 & 0x08)) {313goto check_registers;314}315316raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);317318if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {319goto check_registers;320}321322_make_adc_sensitivity_adjustment(raw_field);323raw_field *= AK09916_MILLIGAUSS_SCALE;324325accumulate_sample(raw_field, 10);326327check_registers:328_bus->check_next_register();329}330331bool AP_Compass_AK09916::_check_id()332{333for (int i = 0; i < 5; i++) {334uint8_t deviceid = 0;335336/* Read AK09916's id */337if (_bus->register_read(REG_DEVICE_ID, &deviceid)) {338switch (deviceid) {339case AK09915_Device_ID:340_devtype = DEVTYPE_AK09915;341return true;342case AK09916_Device_ID:343_devtype = DEVTYPE_AK09916;344return true;345case AK09918_Device_ID:346_devtype = DEVTYPE_AK09918;347return true;348}349}350}351352return false;353}354355bool AP_Compass_AK09916::_setup_mode() {356return _bus->register_write(REG_CNTL2, 0x08, true); //Continuous Mode 2357}358359bool AP_Compass_AK09916::_reset()360{361return _bus->register_write(REG_CNTL3, 0x01); //Soft Reset362}363364/* AP_HAL::Device implementation of the AK09916 */365AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)366: _dev(std::move(dev))367{368}369370bool AP_AK09916_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)371{372return _dev->read_registers(reg, buf, size);373}374375bool AP_AK09916_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)376{377return _dev->read_registers(reg, val, 1);378}379380bool AP_AK09916_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val, bool checked)381{382return _dev->write_register(reg, val, checked);383}384385AP_HAL::Semaphore *AP_AK09916_BusDriver_HALDevice::get_semaphore()386{387return _dev->get_semaphore();388}389390AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)391{392return _dev->register_periodic_callback(period_usec, cb);393}394395/* AK09916 on an auxiliary bus of IMU driver */396AP_AK09916_BusDriver_Auxiliary::AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,397uint8_t backend_instance, uint8_t addr)398{399/*400* Only initialize members. Fails are handled by configure or while401* getting the semaphore402*/403#if AP_INERTIALSENSOR_ENABLED404_bus = ins.get_auxiliary_bus(backend_id, backend_instance);405if (!_bus) {406return;407}408409_slave = _bus->request_next_slave(addr);410#endif411}412413AP_AK09916_BusDriver_Auxiliary::~AP_AK09916_BusDriver_Auxiliary()414{415/* After started it's owned by AuxiliaryBus */416if (!_started) {417delete _slave;418}419}420421bool AP_AK09916_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)422{423if (_started) {424/*425* We can only read a block when reading the block of sample values -426* calling with any other value is a mistake427*/428if (reg != REG_ST1) {429return false;430}431432int n = _slave->read(buf);433return n == static_cast<int>(size);434}435436int r = _slave->passthrough_read(reg, buf, size);437438return r > 0 && static_cast<uint32_t>(r) == size;439}440441bool AP_AK09916_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)442{443return _slave->passthrough_read(reg, val, 1) == 1;444}445446bool AP_AK09916_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val, bool checked)447{448(void)checked;449return _slave->passthrough_write(reg, val) == 1;450}451452AP_HAL::Semaphore *AP_AK09916_BusDriver_Auxiliary::get_semaphore()453{454return _bus ? _bus->get_semaphore() : nullptr;455}456457bool AP_AK09916_BusDriver_Auxiliary::configure()458{459if (!_bus || !_slave) {460return false;461}462return true;463}464465bool AP_AK09916_BusDriver_Auxiliary::start_measurements()466{467if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(AP_Compass_AK09916::sample_regs)) < 0) {468return false;469}470471_started = true;472473return true;474}475476AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)477{478return _bus->register_periodic_callback(period_usec, cb);479}480481// set device type within a device class482void AP_AK09916_BusDriver_Auxiliary::set_device_type(uint8_t devtype)483{484_bus->set_device_type(devtype);485}486487// return 24 bit bus identifier488uint32_t AP_AK09916_BusDriver_Auxiliary::get_bus_id(void) const489{490return _bus->get_bus_id();491}492493#endif // AP_COMPASS_AK09916_ENABLED494495496