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_AK8963.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Compass_AK8963.h"1617#if AP_COMPASS_AK8963_ENABLED1819#include <assert.h>20#include <utility>2122#include <AP_Math/AP_Math.h>23#include <AP_HAL/AP_HAL.h>2425#include <AP_InertialSensor/AP_InertialSensor_Invensense.h>2627#define AK8963_I2C_ADDR 0x0c2829#define AK8963_WIA 0x0030# define AK8963_Device_ID 0x483132#define AK8963_HXL 0x033334/* bit definitions for AK8963 CNTL1 */35#define AK8963_CNTL1 0x0A36# define AK8963_CONTINUOUS_MODE1 0x0237# define AK8963_CONTINUOUS_MODE2 0x0638# define AK8963_SELFTEST_MODE 0x0839# define AK8963_POWERDOWN_MODE 0x0040# define AK8963_FUSE_MODE 0x0f41# define AK8963_16BIT_ADC 0x1042# define AK8963_14BIT_ADC 0x004344#define AK8963_CNTL2 0x0B45# define AK8963_RESET 0x014647#define AK8963_ASAX 0x104849#define AK8963_MILLIGAUSS_SCALE 10.0f5051extern const AP_HAL::HAL &hal;5253AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus,54enum Rotation rotation)55: _bus(bus)56, _rotation(rotation)57{58}5960AP_Compass_AK8963::~AP_Compass_AK8963()61{62delete _bus;63}6465AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,66enum Rotation rotation)67{68if (!dev) {69return nullptr;70}71AP_AK8963_BusDriver *bus = NEW_NOTHROW AP_AK8963_BusDriver_HALDevice(std::move(dev));72if (!bus) {73return nullptr;74}7576AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation);77if (!sensor || !sensor->init()) {78delete sensor;79return nullptr;80}8182return sensor;83}8485AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,86enum Rotation rotation)87{88if (!dev) {89return nullptr;90}91#if AP_INERTIALSENSOR_ENABLED92AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();9394/* Allow MPU9250 to shortcut auxiliary bus and host bus */95ins.detect_backends();96#endif9798return probe(std::move(dev), rotation);99}100101AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(uint8_t mpu9250_instance,102enum Rotation rotation)103{104#if AP_INERTIALSENSOR_ENABLED105AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();106107AP_AK8963_BusDriver *bus =108NEW_NOTHROW AP_AK8963_BusDriver_Auxiliary(ins, HAL_INS_MPU9250_SPI, mpu9250_instance, AK8963_I2C_ADDR);109if (!bus) {110return nullptr;111}112113AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation);114if (!sensor || !sensor->init()) {115delete sensor;116return nullptr;117}118119return sensor;120#else121return nullptr;122#endif123124}125126bool AP_Compass_AK8963::init()127{128AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();129130if (!bus_sem) {131return false;132}133_bus->get_semaphore()->take_blocking();134135if (!_bus->configure()) {136DEV_PRINTF("AK8963: Could not configure the bus\n");137goto fail;138}139140if (!_check_id()) {141DEV_PRINTF("AK8963: Wrong id\n");142goto fail;143}144145if (!_calibrate()) {146DEV_PRINTF("AK8963: Could not read calibration data\n");147goto fail;148}149150if (!_setup_mode()) {151DEV_PRINTF("AK8963: Could not setup mode\n");152goto fail;153}154155if (!_bus->start_measurements()) {156DEV_PRINTF("AK8963: Could not start measurements\n");157goto fail;158}159160_initialized = true;161162/* register the compass instance in the frontend */163_bus->set_device_type(DEVTYPE_AK8963);164if (!register_compass(_bus->get_bus_id(), _compass_instance)) {165goto fail;166}167set_dev_id(_compass_instance, _bus->get_bus_id());168169set_rotation(_compass_instance, _rotation);170bus_sem->give();171172_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));173174return true;175176fail:177bus_sem->give();178return false;179}180181void AP_Compass_AK8963::read()182{183if (!_initialized) {184return;185}186187drain_accumulated_samples(_compass_instance);188}189190void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const191{192static const float ADC_16BIT_RESOLUTION = 0.15f;193194field *= ADC_16BIT_RESOLUTION;195}196197void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const198{199field.x *= _magnetometer_ASA[0];200field.y *= _magnetometer_ASA[1];201field.z *= _magnetometer_ASA[2];202}203204void AP_Compass_AK8963::_update()205{206struct sample_regs regs;207Vector3f raw_field;208209if (!_bus->block_read(AK8963_HXL, (uint8_t *) ®s, sizeof(regs))) {210return;211}212213/* Check for overflow. See AK8963's datasheet, section214* 6.4.3.6 - Magnetic Sensor Overflow. */215if ((regs.st2 & 0x08)) {216return;217}218219raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);220221if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {222return;223}224225_make_factory_sensitivity_adjustment(raw_field);226_make_adc_sensitivity_adjustment(raw_field);227raw_field *= AK8963_MILLIGAUSS_SCALE;228229accumulate_sample(raw_field, _compass_instance, 10);230}231232bool AP_Compass_AK8963::_check_id()233{234for (int i = 0; i < 5; i++) {235uint8_t deviceid = 0;236237/* Read AK8963's id */238if (_bus->register_read(AK8963_WIA, &deviceid) &&239deviceid == AK8963_Device_ID) {240return true;241}242}243244return false;245}246247bool AP_Compass_AK8963::_setup_mode() {248return _bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);249}250251bool AP_Compass_AK8963::_reset()252{253return _bus->register_write(AK8963_CNTL2, AK8963_RESET);254}255256257bool AP_Compass_AK8963::_calibrate()258{259/* Enable FUSE-mode in order to be able to read calibration data */260_bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);261262uint8_t response[3];263264_bus->block_read(AK8963_ASAX, response, 3);265266for (int i = 0; i < 3; i++) {267float data = response[i];268_magnetometer_ASA[i] = ((data - 128) / 256 + 1);269}270271return true;272}273274/* AP_HAL::I2CDevice implementation of the AK8963 */275AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)276: _dev(std::move(dev))277{278}279280bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)281{282return _dev->read_registers(reg, buf, size);283}284285bool AP_AK8963_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)286{287return _dev->read_registers(reg, val, 1);288}289290bool AP_AK8963_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)291{292return _dev->write_register(reg, val);293}294295AP_HAL::Semaphore *AP_AK8963_BusDriver_HALDevice::get_semaphore()296{297return _dev->get_semaphore();298}299300AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)301{302return _dev->register_periodic_callback(period_usec, cb);303}304305/* AK8963 on an auxiliary bus of IMU driver */306AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,307uint8_t backend_instance, uint8_t addr)308{309/*310* Only initialize members. Fails are handled by configure or while311* getting the semaphore312*/313#if AP_INERTIALSENSOR_ENABLED314_bus = ins.get_auxiliary_bus(backend_id, backend_instance);315if (!_bus) {316return;317}318319_slave = _bus->request_next_slave(addr);320#endif321}322323AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary()324{325/* After started it's owned by AuxiliaryBus */326if (!_started) {327delete _slave;328}329}330331bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)332{333if (_started) {334/*335* We can only read a block when reading the block of sample values -336* calling with any other value is a mistake337*/338if (reg != AK8963_HXL) {339return false;340}341342int n = _slave->read(buf);343return n == static_cast<int>(size);344}345346int r = _slave->passthrough_read(reg, buf, size);347348return r > 0 && static_cast<uint32_t>(r) == size;349}350351bool AP_AK8963_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)352{353return _slave->passthrough_read(reg, val, 1) == 1;354}355356bool AP_AK8963_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)357{358return _slave->passthrough_write(reg, val) == 1;359}360361AP_HAL::Semaphore *AP_AK8963_BusDriver_Auxiliary::get_semaphore()362{363return _bus ? _bus->get_semaphore() : nullptr;364}365366bool AP_AK8963_BusDriver_Auxiliary::configure()367{368if (!_bus || !_slave) {369return false;370}371return true;372}373374bool AP_AK8963_BusDriver_Auxiliary::start_measurements()375{376if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) {377return false;378}379380_started = true;381382return true;383}384385AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)386{387return _bus->register_periodic_callback(period_usec, cb);388}389390// set device type within a device class391void AP_AK8963_BusDriver_Auxiliary::set_device_type(uint8_t devtype)392{393_bus->set_device_type(devtype);394}395396// return 24 bit bus identifier397uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const398{399return _bus->get_bus_id();400}401402#endif // AP_COMPASS_AK8963_ENABLED403404405