Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Compass/AP_Compass_AK09916.cpp
Views: 1798
/*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::I2CDevice> 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::I2CDevice> dev,97AP_HAL::OwnPtr<AP_HAL::I2CDevice> 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{177#if AP_INERTIALSENSOR_ENABLED178AP_InertialSensor &ins = AP::ins();179180AP_AK09916_BusDriver *bus =181NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);182if (!bus) {183return nullptr;184}185186AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);187if (!sensor || !sensor->init()) {188delete sensor;189return nullptr;190}191192return sensor;193#else194return nullptr;195#endif196}197198AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_I2C(uint8_t inv2_instance,199enum Rotation rotation)200{201AP_InertialSensor &ins = AP::ins();202203AP_AK09916_BusDriver *bus =204NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_I2C, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR);205if (!bus) {206return nullptr;207}208209AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation);210if (!sensor || !sensor->init()) {211delete sensor;212return nullptr;213}214215return sensor;216}217#endif // AP_COMPASS_ICM20948_ENABLED218219bool AP_Compass_AK09916::init()220{221AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();222223if (!bus_sem) {224return false;225}226_bus->get_semaphore()->take_blocking();227228if (!_bus->configure()) {229DEV_PRINTF("AK09916: Could not configure the bus\n");230goto fail;231}232233if (!_reset()) {234goto fail;235}236237if (!_check_id()) {238goto fail;239}240241// one checked register for mode242_bus->setup_checked_registers(1);243244if (!_setup_mode()) {245DEV_PRINTF("AK09916: Could not setup mode\n");246goto fail;247}248249if (!_bus->start_measurements()) {250DEV_PRINTF("AK09916: Could not start measurements\n");251goto fail;252}253254_initialized = true;255256/* register the compass instance in the frontend */257_bus->set_device_type(_devtype);258if (!register_compass(_bus->get_bus_id(), _compass_instance)) {259goto fail;260}261set_dev_id(_compass_instance, _bus->get_bus_id());262263if (_force_external) {264set_external(_compass_instance, true);265}266267set_rotation(_compass_instance, _rotation);268269bus_sem->give();270271_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK09916::_update, void));272273return true;274275fail:276bus_sem->give();277return false;278}279280void AP_Compass_AK09916::read()281{282if (!_initialized) {283return;284}285286drain_accumulated_samples(_compass_instance);287}288289void AP_Compass_AK09916::_make_adc_sensitivity_adjustment(Vector3f& field) const290{291static const float ADC_16BIT_RESOLUTION = 0.15f;292293field *= ADC_16BIT_RESOLUTION;294}295296void AP_Compass_AK09916::_update()297{298struct sample_regs regs = {0};299Vector3f raw_field;300301if (!_bus->block_read(REG_ST1, (uint8_t *) ®s, sizeof(regs))) {302goto check_registers;303}304305if (!(regs.st1 & 0x01)) {306no_data++;307if (no_data == 5) {308_reset();309_setup_mode();310no_data = 0;311}312goto check_registers;313}314no_data = 0;315316/* Check for overflow. See AK09916's datasheet*/317if ((regs.st2 & 0x08)) {318goto check_registers;319}320321raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);322323if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {324goto check_registers;325}326327_make_adc_sensitivity_adjustment(raw_field);328raw_field *= AK09916_MILLIGAUSS_SCALE;329330accumulate_sample(raw_field, _compass_instance, 10);331332check_registers:333_bus->check_next_register();334}335336bool AP_Compass_AK09916::_check_id()337{338for (int i = 0; i < 5; i++) {339uint8_t deviceid = 0;340341/* Read AK09916's id */342if (_bus->register_read(REG_DEVICE_ID, &deviceid)) {343switch (deviceid) {344case AK09915_Device_ID:345_devtype = DEVTYPE_AK09915;346return true;347case AK09916_Device_ID:348_devtype = DEVTYPE_AK09916;349return true;350case AK09918_Device_ID:351_devtype = DEVTYPE_AK09918;352return true;353}354}355}356357return false;358}359360bool AP_Compass_AK09916::_setup_mode() {361return _bus->register_write(REG_CNTL2, 0x08, true); //Continuous Mode 2362}363364bool AP_Compass_AK09916::_reset()365{366return _bus->register_write(REG_CNTL3, 0x01); //Soft Reset367}368369/* AP_HAL::I2CDevice implementation of the AK09916 */370AP_AK09916_BusDriver_HALDevice::AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)371: _dev(std::move(dev))372{373}374375bool AP_AK09916_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)376{377return _dev->read_registers(reg, buf, size);378}379380bool AP_AK09916_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)381{382return _dev->read_registers(reg, val, 1);383}384385bool AP_AK09916_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val, bool checked)386{387return _dev->write_register(reg, val, checked);388}389390AP_HAL::Semaphore *AP_AK09916_BusDriver_HALDevice::get_semaphore()391{392return _dev->get_semaphore();393}394395AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)396{397return _dev->register_periodic_callback(period_usec, cb);398}399400/* AK09916 on an auxiliary bus of IMU driver */401AP_AK09916_BusDriver_Auxiliary::AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,402uint8_t backend_instance, uint8_t addr)403{404/*405* Only initialize members. Fails are handled by configure or while406* getting the semaphore407*/408#if AP_INERTIALSENSOR_ENABLED409_bus = ins.get_auxiliary_bus(backend_id, backend_instance);410if (!_bus) {411return;412}413414_slave = _bus->request_next_slave(addr);415#endif416}417418AP_AK09916_BusDriver_Auxiliary::~AP_AK09916_BusDriver_Auxiliary()419{420/* After started it's owned by AuxiliaryBus */421if (!_started) {422delete _slave;423}424}425426bool AP_AK09916_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)427{428if (_started) {429/*430* We can only read a block when reading the block of sample values -431* calling with any other value is a mistake432*/433if (reg != REG_ST1) {434return false;435}436437int n = _slave->read(buf);438return n == static_cast<int>(size);439}440441int r = _slave->passthrough_read(reg, buf, size);442443return r > 0 && static_cast<uint32_t>(r) == size;444}445446bool AP_AK09916_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)447{448return _slave->passthrough_read(reg, val, 1) == 1;449}450451bool AP_AK09916_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val, bool checked)452{453(void)checked;454return _slave->passthrough_write(reg, val) == 1;455}456457AP_HAL::Semaphore *AP_AK09916_BusDriver_Auxiliary::get_semaphore()458{459return _bus ? _bus->get_semaphore() : nullptr;460}461462bool AP_AK09916_BusDriver_Auxiliary::configure()463{464if (!_bus || !_slave) {465return false;466}467return true;468}469470bool AP_AK09916_BusDriver_Auxiliary::start_measurements()471{472if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(AP_Compass_AK09916::sample_regs)) < 0) {473return false;474}475476_started = true;477478return true;479}480481AP_HAL::Device::PeriodicHandle AP_AK09916_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)482{483return _bus->register_periodic_callback(period_usec, cb);484}485486// set device type within a device class487void AP_AK09916_BusDriver_Auxiliary::set_device_type(uint8_t devtype)488{489_bus->set_device_type(devtype);490}491492// return 24 bit bus identifier493uint32_t AP_AK09916_BusDriver_Auxiliary::get_bus_id(void) const494{495return _bus->get_bus_id();496}497498#endif // AP_COMPASS_AK09916_ENABLED499500501