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_HMC5843.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/*16* AP_Compass_HMC5843.cpp - Arduino Library for HMC5843 I2C magnetometer17* Code by Jordi Muñoz and Jose Julio. DIYDrones.com18*19* Sensor is connected to I2C port20* Sensor is initialized in Continuos mode (10Hz)21*22*/23#include "AP_Compass_HMC5843.h"2425#if AP_COMPASS_HMC5843_ENABLED2627#include <assert.h>28#include <utility>29#include <stdio.h>3031#include <AP_Math/AP_Math.h>32#include <AP_HAL/utility/sparse-endian.h>33#include <AP_HAL/AP_HAL.h>34#include <AP_InertialSensor/AP_InertialSensor.h>35#include <AP_InertialSensor/AuxiliaryBus.h>3637extern const AP_HAL::HAL& hal;3839/*40* Default address: 0x1E41*/4243#define HMC5843_REG_CONFIG_A 0x0044// Valid sample averaging for 5883L45#define HMC5843_SAMPLE_AVERAGING_1 (0x00 << 5)46#define HMC5843_SAMPLE_AVERAGING_2 (0x01 << 5)47#define HMC5843_SAMPLE_AVERAGING_4 (0x02 << 5)48#define HMC5843_SAMPLE_AVERAGING_8 (0x03 << 5)4950#define HMC5843_CONF_TEMP_ENABLE (0x80)5152// Valid data output rates for 5883L53#define HMC5843_OSR_0_75HZ (0x00 << 2)54#define HMC5843_OSR_1_5HZ (0x01 << 2)55#define HMC5843_OSR_3HZ (0x02 << 2)56#define HMC5843_OSR_7_5HZ (0x03 << 2)57#define HMC5843_OSR_15HZ (0x04 << 2)58#define HMC5843_OSR_30HZ (0x05 << 2)59#define HMC5843_OSR_75HZ (0x06 << 2)60// Sensor operation modes61#define HMC5843_OPMODE_NORMAL 0x0062#define HMC5843_OPMODE_POSITIVE_BIAS 0x0163#define HMC5843_OPMODE_NEGATIVE_BIAS 0x0264#define HMC5843_OPMODE_MASK 0x036566#define HMC5843_REG_CONFIG_B 0x0167#define HMC5883L_GAIN_0_88_GA (0x00 << 5)68#define HMC5883L_GAIN_1_30_GA (0x01 << 5)69#define HMC5883L_GAIN_1_90_GA (0x02 << 5)70#define HMC5883L_GAIN_2_50_GA (0x03 << 5)71#define HMC5883L_GAIN_4_00_GA (0x04 << 5)72#define HMC5883L_GAIN_4_70_GA (0x05 << 5)73#define HMC5883L_GAIN_5_60_GA (0x06 << 5)74#define HMC5883L_GAIN_8_10_GA (0x07 << 5)7576#define HMC5843_GAIN_0_70_GA (0x00 << 5)77#define HMC5843_GAIN_1_00_GA (0x01 << 5)78#define HMC5843_GAIN_1_50_GA (0x02 << 5)79#define HMC5843_GAIN_2_00_GA (0x03 << 5)80#define HMC5843_GAIN_3_20_GA (0x04 << 5)81#define HMC5843_GAIN_3_80_GA (0x05 << 5)82#define HMC5843_GAIN_4_50_GA (0x06 << 5)83#define HMC5843_GAIN_6_50_GA (0x07 << 5)8485#define HMC5843_REG_MODE 0x0286#define HMC5843_MODE_CONTINUOUS 0x0087#define HMC5843_MODE_SINGLE 0x018889#define HMC5843_REG_DATA_OUTPUT_X_MSB 0x039091#define HMC5843_REG_ID_A 0x0A929394AP_Compass_HMC5843::AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,95bool force_external, enum Rotation rotation)96: _bus(bus)97, _rotation(rotation)98, _force_external(force_external)99{100}101102AP_Compass_HMC5843::~AP_Compass_HMC5843()103{104delete _bus;105}106107AP_Compass_Backend *AP_Compass_HMC5843::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,108bool force_external,109enum Rotation rotation)110{111if (!dev) {112return nullptr;113}114AP_HMC5843_BusDriver *bus = NEW_NOTHROW AP_HMC5843_BusDriver_HALDevice(std::move(dev));115if (!bus) {116return nullptr;117}118119AP_Compass_HMC5843 *sensor = NEW_NOTHROW AP_Compass_HMC5843(bus, force_external, rotation);120if (!sensor || !sensor->init()) {121delete sensor;122return nullptr;123}124125return sensor;126}127128#if AP_INERTIALSENSOR_ENABLED129AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation)130{131AP_InertialSensor &ins = *AP_InertialSensor::get_singleton();132133AP_HMC5843_BusDriver *bus =134NEW_NOTHROW AP_HMC5843_BusDriver_Auxiliary(ins, HAL_INS_MPU60XX_SPI,135HAL_COMPASS_HMC5843_I2C_ADDR);136if (!bus) {137return nullptr;138}139140AP_Compass_HMC5843 *sensor = NEW_NOTHROW AP_Compass_HMC5843(bus, false, rotation);141if (!sensor || !sensor->init()) {142delete sensor;143return nullptr;144}145146return sensor;147}148#endif149150bool AP_Compass_HMC5843::init()151{152AP_HAL::Semaphore *bus_sem = _bus->get_semaphore();153154if (!bus_sem) {155DEV_PRINTF("HMC5843: Unable to get bus semaphore\n");156return false;157}158bus_sem->take_blocking();159160// high retries for init161_bus->set_retries(10);162163if (!_bus->configure()) {164DEV_PRINTF("HMC5843: Could not configure the bus\n");165goto errout;166}167168if (!_check_whoami()) {169goto errout;170}171172if (!_calibrate()) {173DEV_PRINTF("HMC5843: Could not calibrate sensor\n");174goto errout;175}176177if (!_setup_sampling_mode()) {178goto errout;179}180181if (!_bus->start_measurements()) {182DEV_PRINTF("HMC5843: Could not start measurements on bus\n");183goto errout;184}185186_initialised = true;187188// lower retries for run189_bus->set_retries(3);190191bus_sem->give();192193// perform an initial read194read();195196//register compass instance197_bus->set_device_type(DEVTYPE_HMC5883);198if (!register_compass(_bus->get_bus_id(), _compass_instance)) {199return false;200}201set_dev_id(_compass_instance, _bus->get_bus_id());202203set_rotation(_compass_instance, _rotation);204205if (_force_external) {206set_external(_compass_instance, true);207}208209// read from sensor at 75Hz210_bus->register_periodic_callback(13333,211FUNCTOR_BIND_MEMBER(&AP_Compass_HMC5843::_timer, void));212213DEV_PRINTF("HMC5843 found on bus 0x%x\n", (unsigned)_bus->get_bus_id());214215return true;216217errout:218bus_sem->give();219return false;220}221222/*223* take a reading from the magnetometer224*225* bus semaphore has been taken already by HAL226*/227void AP_Compass_HMC5843::_timer()228{229bool result = _read_sample();230231// always ask for a new sample232_take_sample();233234if (!result) {235return;236}237238// get raw_field - sensor frame, uncorrected239Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);240raw_field *= _gain_scale;241242// rotate to the desired orientation243if (is_external(_compass_instance)) {244raw_field.rotate(ROTATION_YAW_90);245}246247// We expect to do reads at 10Hz, and we get new data at most 75Hz, so we248// don't expect to accumulate more than 8 before a read; let's make it249// 14 to give more room for the initialization phase250accumulate_sample(raw_field, _compass_instance, 14);251}252253/*254* Take accumulated reads from the magnetometer or try to read once if no255* valid data256*257* bus semaphore must not be locked258*/259void AP_Compass_HMC5843::read()260{261if (!_initialised) {262// someone has tried to enable a compass for the first time263// mid-flight .... we can't do that yet (especially as we won't264// have the right orientation!)265return;266}267268drain_accumulated_samples(_compass_instance, &_scaling);269}270271bool AP_Compass_HMC5843::_setup_sampling_mode()272{273_gain_scale = (1.0f / 1090) * 1000;274if (!_bus->register_write(HMC5843_REG_CONFIG_A,275HMC5843_CONF_TEMP_ENABLE |276HMC5843_OSR_75HZ |277HMC5843_SAMPLE_AVERAGING_1) ||278!_bus->register_write(HMC5843_REG_CONFIG_B,279HMC5883L_GAIN_1_30_GA) ||280!_bus->register_write(HMC5843_REG_MODE,281HMC5843_MODE_SINGLE)) {282return false;283}284return true;285}286287/*288* Read Sensor data - bus semaphore must be taken289*/290bool AP_Compass_HMC5843::_read_sample()291{292struct PACKED {293be16_t rx;294be16_t ry;295be16_t rz;296} val;297int16_t rx, ry, rz;298299if (!_bus->block_read(HMC5843_REG_DATA_OUTPUT_X_MSB, (uint8_t *) &val, sizeof(val))){300return false;301}302303rx = be16toh(val.rx);304ry = be16toh(val.rz);305rz = be16toh(val.ry);306307if (rx == -4096 || ry == -4096 || rz == -4096) {308// no valid data available309return false;310}311312_mag_x = -rx;313_mag_y = ry;314_mag_z = -rz;315316return true;317}318319320/*321ask for a new oneshot sample322*/323void AP_Compass_HMC5843::_take_sample()324{325_bus->register_write(HMC5843_REG_MODE,326HMC5843_MODE_SINGLE);327}328329bool AP_Compass_HMC5843::_check_whoami()330{331uint8_t id[3];332if (!_bus->block_read(HMC5843_REG_ID_A, id, 3)) {333// can't talk on bus334return false;335}336if (memcmp(id, "H43", 3) != 0) {337// not a HMC5x83 device338return false;339}340341return true;342}343344bool AP_Compass_HMC5843::_calibrate()345{346uint8_t calibration_gain;347int numAttempts = 0, good_count = 0;348bool success = false;349350calibration_gain = HMC5883L_GAIN_2_50_GA;351352/*353* the expected values are based on observation of real sensors354*/355float expected[3] = { 1.16*600, 1.08*600, 1.16*600 };356357uint8_t base_config = HMC5843_OSR_15HZ;358uint8_t num_samples = 0;359360while (success == 0 && numAttempts < 25 && good_count < 5) {361numAttempts++;362363// force positiveBias (compass should return 715 for all channels)364if (!_bus->register_write(HMC5843_REG_CONFIG_A,365base_config | HMC5843_OPMODE_POSITIVE_BIAS)) {366// compass not responding on the bus367continue;368}369370hal.scheduler->delay(50);371372// set gains373if (!_bus->register_write(HMC5843_REG_CONFIG_B, calibration_gain) ||374!_bus->register_write(HMC5843_REG_MODE, HMC5843_MODE_SINGLE)) {375continue;376}377378// read values from the compass379hal.scheduler->delay(50);380if (!_read_sample()) {381// we didn't read valid values382continue;383}384385num_samples++;386387float cal[3];388389// hal.console->printf("mag %d %d %d\n", _mag_x, _mag_y, _mag_z);390391cal[0] = fabsf(expected[0] / _mag_x);392cal[1] = fabsf(expected[1] / _mag_y);393cal[2] = fabsf(expected[2] / _mag_z);394395// hal.console->printf("cal=%.2f %.2f %.2f\n", cal[0], cal[1], cal[2]);396397// we throw away the first two samples as the compass may398// still be changing its state from the application of the399// strap excitation. After that we accept values in a400// reasonable range401if (numAttempts <= 2) {402continue;403}404405#define IS_CALIBRATION_VALUE_VALID(val) (val > 0.7f && val < 1.35f)406407if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&408IS_CALIBRATION_VALUE_VALID(cal[1]) &&409IS_CALIBRATION_VALUE_VALID(cal[2])) {410// hal.console->printf("car=%.2f %.2f %.2f good\n", cal[0], cal[1], cal[2]);411good_count++;412413_scaling[0] += cal[0];414_scaling[1] += cal[1];415_scaling[2] += cal[2];416}417418#undef IS_CALIBRATION_VALUE_VALID419420#if 0421/* useful for debugging */422hal.console->printf("MagX: %d MagY: %d MagZ: %d\n", (int)_mag_x, (int)_mag_y, (int)_mag_z);423hal.console->printf("CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);424#endif425}426427_bus->register_write(HMC5843_REG_CONFIG_A, base_config);428429if (good_count >= 5) {430_scaling[0] = _scaling[0] / good_count;431_scaling[1] = _scaling[1] / good_count;432_scaling[2] = _scaling[2] / good_count;433success = true;434} else {435/* best guess */436_scaling[0] = 1.0;437_scaling[1] = 1.0;438_scaling[2] = 1.0;439if (num_samples > 5) {440// a sensor can be broken for calibration but still441// otherwise workable, accept it if we are reading samples442success = true;443}444}445446#if 0447printf("scaling: %.2f %.2f %.2f\n",448_scaling[0], _scaling[1], _scaling[2]);449#endif450451return success;452}453454/* AP_HAL::Device implementation of the HMC5843 */455AP_HMC5843_BusDriver_HALDevice::AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)456: _dev(std::move(dev))457{458// set read and auto-increment flags on SPI459if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {460_dev->set_read_flag(0xC0);461}462}463464bool AP_HMC5843_BusDriver_HALDevice::block_read(uint8_t reg, uint8_t *buf, uint32_t size)465{466return _dev->read_registers(reg, buf, size);467}468469bool AP_HMC5843_BusDriver_HALDevice::register_read(uint8_t reg, uint8_t *val)470{471return _dev->read_registers(reg, val, 1);472}473474bool AP_HMC5843_BusDriver_HALDevice::register_write(uint8_t reg, uint8_t val)475{476return _dev->write_register(reg, val);477}478479AP_HAL::Semaphore *AP_HMC5843_BusDriver_HALDevice::get_semaphore()480{481return _dev->get_semaphore();482}483484AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_HALDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)485{486return _dev->register_periodic_callback(period_usec, cb);487}488489490#if AP_INERTIALSENSOR_ENABLED491/* HMC5843 on an auxiliary bus of IMU driver */492AP_HMC5843_BusDriver_Auxiliary::AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,493uint8_t addr)494{495/*496* Only initialize members. Fails are handled by configure or while497* getting the semaphore498*/499_bus = ins.get_auxiliary_bus(backend_id);500if (!_bus) {501return;502}503504_slave = _bus->request_next_slave(addr);505}506507AP_HMC5843_BusDriver_Auxiliary::~AP_HMC5843_BusDriver_Auxiliary()508{509/* After started it's owned by AuxiliaryBus */510if (!_started) {511delete _slave;512}513}514515bool AP_HMC5843_BusDriver_Auxiliary::block_read(uint8_t reg, uint8_t *buf, uint32_t size)516{517if (_started) {518/*519* We can only read a block when reading the block of sample values -520* calling with any other value is a mistake521*/522if (reg != HMC5843_REG_DATA_OUTPUT_X_MSB) {523return false;524}525526int n = _slave->read(buf);527return n == static_cast<int>(size);528}529530int r = _slave->passthrough_read(reg, buf, size);531532return r > 0 && static_cast<uint32_t>(r) == size;533}534535bool AP_HMC5843_BusDriver_Auxiliary::register_read(uint8_t reg, uint8_t *val)536{537return _slave->passthrough_read(reg, val, 1) == 1;538}539540bool AP_HMC5843_BusDriver_Auxiliary::register_write(uint8_t reg, uint8_t val)541{542return _slave->passthrough_write(reg, val) == 1;543}544545AP_HAL::Semaphore *AP_HMC5843_BusDriver_Auxiliary::get_semaphore()546{547return _bus->get_semaphore();548}549550551bool AP_HMC5843_BusDriver_Auxiliary::configure()552{553if (!_bus || !_slave) {554return false;555}556return true;557}558559bool AP_HMC5843_BusDriver_Auxiliary::start_measurements()560{561if (_bus->register_periodic_read(_slave, HMC5843_REG_DATA_OUTPUT_X_MSB, 6) < 0) {562return false;563}564565_started = true;566567return true;568}569570AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_Auxiliary::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)571{572return _bus->register_periodic_callback(period_usec, cb);573}574575// set device type within a device class576void AP_HMC5843_BusDriver_Auxiliary::set_device_type(uint8_t devtype)577{578_bus->set_device_type(devtype);579}580581// return 24 bit bus identifier582uint32_t AP_HMC5843_BusDriver_Auxiliary::get_bus_id(void) const583{584return _bus->get_bus_id();585}586#endif // AP_INERTIALSENSOR_ENABLED587588#endif // AP_COMPASS_HMC5843_ENABLED589590591