Path: blob/master/libraries/AP_Compass/AP_Compass_AK8963.cpp
9460 views
/*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::Device> 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::Device> 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())) {165goto fail;166}167168set_rotation(_rotation);169bus_sem->give();170171_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));172173return true;174175fail:176bus_sem->give();177return false;178}179180void AP_Compass_AK8963::read()181{182if (!_initialized) {183return;184}185186drain_accumulated_samples();187}188189void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const190{191static const float ADC_16BIT_RESOLUTION = 0.15f;192193field *= ADC_16BIT_RESOLUTION;194}195196void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const197{198field.x *= _magnetometer_ASA[0];199field.y *= _magnetometer_ASA[1];200field.z *= _magnetometer_ASA[2];201}202203void AP_Compass_AK8963::_update()204{205struct sample_regs regs;206Vector3f raw_field;207208if (!_bus->block_read(AK8963_HXL, (uint8_t *) ®s, sizeof(regs))) {209return;210}211212/* Check for overflow. See AK8963's datasheet, section213* 6.4.3.6 - Magnetic Sensor Overflow. */214if ((regs.st2 & 0x08)) {215return;216}217218raw_field = Vector3f(regs.val[0], regs.val[1], regs.val[2]);219220if (is_zero(raw_field.x) && is_zero(raw_field.y) && is_zero(raw_field.z)) {221return;222}223224_make_factory_sensitivity_adjustment(raw_field);225_make_adc_sensitivity_adjustment(raw_field);226raw_field *= AK8963_MILLIGAUSS_SCALE;227228accumulate_sample(raw_field, 10);229}230231bool AP_Compass_AK8963::_check_id()232{233for (int i = 0; i < 5; i++) {234uint8_t deviceid = 0;235236/* Read AK8963's id */237if (_bus->register_read(AK8963_WIA, &deviceid) &&238deviceid == AK8963_Device_ID) {239return true;240}241}242243return false;244}245246bool AP_Compass_AK8963::_setup_mode() {247return _bus->register_write(AK8963_CNTL1, AK8963_CONTINUOUS_MODE2 | AK8963_16BIT_ADC);248}249250bool AP_Compass_AK8963::_reset()251{252return _bus->register_write(AK8963_CNTL2, AK8963_RESET);253}254255256bool AP_Compass_AK8963::_calibrate()257{258/* Enable FUSE-mode in order to be able to read calibration data */259_bus->register_write(AK8963_CNTL1, AK8963_FUSE_MODE | AK8963_16BIT_ADC);260261uint8_t response[3];262263_bus->block_read(AK8963_ASAX, response, 3);264265for (int i = 0; i < 3; i++) {266float data = response[i];267_magnetometer_ASA[i] = ((data - 128) / 256 + 1);268}269270return true;271}272273/* AP_HAL::Device implementation of the AK8963 */274AP_AK8963_BusDriver_HALDevice::AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)275: _dev(std::move(dev))276{277}278279bool AP_AK8963_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)280{281return _dev->read_registers(reg, buf, size);282}283284bool AP_AK8963_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)285{286return _dev->read_registers(reg, val, 1);287}288289bool AP_AK8963_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)290{291return _dev->write_register(reg, val);292}293294AP_HAL::Semaphore *AP_AK8963_BusDriver_HALDevice::get_semaphore()295{296return _dev->get_semaphore();297}298299AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)300{301return _dev->register_periodic_callback(period_usec, cb);302}303304/* AK8963 on an auxiliary bus of IMU driver */305AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,306uint8_t backend_instance, uint8_t addr)307{308/*309* Only initialize members. Fails are handled by configure or while310* getting the semaphore311*/312#if AP_INERTIALSENSOR_ENABLED313_bus = ins.get_auxiliary_bus(backend_id, backend_instance);314if (!_bus) {315return;316}317318_slave = _bus->request_next_slave(addr);319#endif320}321322AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary()323{324/* After started it's owned by AuxiliaryBus */325if (!_started) {326delete _slave;327}328}329330bool AP_AK8963_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)331{332if (_started) {333/*334* We can only read a block when reading the block of sample values -335* calling with any other value is a mistake336*/337if (reg != AK8963_HXL) {338return false;339}340341int n = _slave->read(buf);342return n == static_cast<int>(size);343}344345int r = _slave->passthrough_read(reg, buf, size);346347return r > 0 && static_cast<uint32_t>(r) == size;348}349350bool AP_AK8963_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)351{352return _slave->passthrough_read(reg, val, 1) == 1;353}354355bool AP_AK8963_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)356{357return _slave->passthrough_write(reg, val) == 1;358}359360AP_HAL::Semaphore *AP_AK8963_BusDriver_Auxiliary::get_semaphore()361{362return _bus ? _bus->get_semaphore() : nullptr;363}364365bool AP_AK8963_BusDriver_Auxiliary::configure()366{367if (!_bus || !_slave) {368return false;369}370return true;371}372373bool AP_AK8963_BusDriver_Auxiliary::start_measurements()374{375if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) {376return false;377}378379_started = true;380381return true;382}383384AP_HAL::Device::PeriodicHandle AP_AK8963_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)385{386return _bus->register_periodic_callback(period_usec, cb);387}388389// set device type within a device class390void AP_AK8963_BusDriver_Auxiliary::set_device_type(uint8_t devtype)391{392_bus->set_device_type(devtype);393}394395// return 24 bit bus identifier396uint32_t AP_AK8963_BusDriver_Auxiliary::get_bus_id(void) const397{398return _bus->get_bus_id();399}400401#endif // AP_COMPASS_AK8963_ENABLED402403404