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_MMC3416.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_MMC3416.h"1819#if AP_COMPASS_MMC3416_ENABLED2021#include <AP_HAL/AP_HAL.h>22#include <utility>23#include <AP_Math/AP_Math.h>24#include <stdio.h>25#include <AP_Logger/AP_Logger.h>2627extern const AP_HAL::HAL &hal;2829#define REG_PRODUCT_ID 0x2030#define REG_XOUT_L 0x0031#define REG_STATUS 0x0632#define REG_CONTROL0 0x0733#define REG_CONTROL1 0x083435// bits in REG_CONTROL036#define REG_CONTROL0_REFILL 0x8037#define REG_CONTROL0_RESET 0x4038#define REG_CONTROL0_SET 0x2039#define REG_CONTROL0_NB 0x1040#define REG_CONTROL0_TM 0x014142// datasheet says 50ms min for refill43#define MIN_DELAY_SET_RESET 504445AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,46bool force_external,47enum Rotation rotation)48{49if (!dev) {50return nullptr;51}52AP_Compass_MMC3416 *sensor = NEW_NOTHROW AP_Compass_MMC3416(std::move(dev), force_external, rotation);53if (!sensor || !sensor->init()) {54delete sensor;55return nullptr;56}5758return sensor;59}6061AP_Compass_MMC3416::AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> _dev,62bool _force_external,63enum Rotation _rotation)64: dev(std::move(_dev))65, force_external(_force_external)66, rotation(_rotation)67{68}6970bool AP_Compass_MMC3416::init()71{72dev->get_semaphore()->take_blocking();7374dev->set_retries(10);7576uint8_t whoami;77if (!dev->read_registers(REG_PRODUCT_ID, &whoami, 1) ||78whoami != 0x06) {79// not a MMC341680dev->get_semaphore()->give();81return false;82}8384// reset sensor85dev->write_register(REG_CONTROL1, 0x80);86hal.scheduler->delay(10);8788dev->write_register(REG_CONTROL0, 0x00); // single shot89dev->write_register(REG_CONTROL1, 0x00); // 16 bit, 7.92ms9091dev->get_semaphore()->give();9293/* register the compass instance in the frontend */94dev->set_device_type(DEVTYPE_MMC3416);95if (!register_compass(dev->get_bus_id(), compass_instance)) {96return false;97}9899set_dev_id(compass_instance, dev->get_bus_id());100101printf("Found a MMC3416 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance);102103set_rotation(compass_instance, rotation);104105if (force_external) {106set_external(compass_instance, true);107}108109dev->set_retries(1);110111// call timer() at 100Hz112dev->register_periodic_callback(10000,113FUNCTOR_BIND_MEMBER(&AP_Compass_MMC3416::timer, void));114115// wait 250ms for the compass to make it's initial readings116hal.scheduler->delay(250);117118return true;119}120121void AP_Compass_MMC3416::timer()122{123const uint16_t measure_count_limit = 50;124const uint16_t zero_offset = 32768; // 16 bit mode125const uint16_t sensitivity = 2048; // counts per Gauss, 16 bit mode126const float counts_to_milliGauss = 1.0e3f / sensitivity;127128uint32_t now = AP_HAL::millis();129if (now - last_sample_ms > 500) {130// seems to be stuck or on first sample, reset state machine131state = STATE_REFILL1;132last_sample_ms = now;133}134135/*136we use the SET/RESET method to remove bridge offset every137measure_count_limit measurements. This involves a fairly complex138state machine, but means we are much less sensitive to139temperature changes140*/141switch (state) {142case STATE_REFILL1:143if (dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {144state = STATE_REFILL1_WAIT;145refill_start_ms = AP_HAL::millis();146}147break;148149case STATE_REFILL1_WAIT: {150uint8_t status;151if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&152dev->read_registers(REG_STATUS, &status, 1) &&153(status & 0x02) == 0) {154if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_SET) ||155!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement156state = STATE_REFILL1;157} else {158state = STATE_MEASURE_WAIT1;159}160}161break;162}163164case STATE_MEASURE_WAIT1: {165uint8_t status;166if (dev->read_registers(REG_STATUS, &status, 1) && (status & 1)) {167if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data0[0], 6)) {168state = STATE_REFILL1;169break;170}171if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {172state = STATE_REFILL1;173} else {174state = STATE_REFILL2_WAIT;175refill_start_ms = AP_HAL::millis();176}177}178break;179}180181case STATE_REFILL2_WAIT: {182uint8_t status;183if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&184dev->read_registers(REG_STATUS, &status, 1) &&185(status & 0x02) == 0) {186if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_RESET) ||187!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement188state = STATE_REFILL1;189} else {190state = STATE_MEASURE_WAIT2;191}192}193break;194}195196case STATE_MEASURE_WAIT2: {197uint8_t status;198if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {199break;200}201uint16_t data1[3];202if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {203state = STATE_REFILL1;204break;205}206Vector3f field;207208/*209calculate field and offset210*/211Vector3f f1(float(data0[0]) - zero_offset,212float(data0[1]) - zero_offset,213float(data0[2]) - zero_offset);214Vector3f f2(float(data1[0]) - zero_offset,215float(data1[1]) - zero_offset,216float(data1[2]) - zero_offset);217field = (f1 - f2) * (counts_to_milliGauss / 2);218Vector3f new_offset = (f1 + f2) * (counts_to_milliGauss / 2);219if (!have_initial_offset) {220offset = new_offset;221have_initial_offset = true;222} else {223// low pass changes to the offset224offset = offset * 0.95f + new_offset * 0.05f;225}226227#if 0228// @LoggerMessage: MMO229// @Description: MMC3416 compass data230// @Field: TimeUS: Time since system startup231// @Field: Nx: new measurement X axis232// @Field: Ny: new measurement Y axis233// @Field: Nz: new measurement Z axis234// @Field: Ox: new offset X axis235// @Field: Oy: new offset Y axis236// @Field: Oz: new offset Z axis237AP::logger().Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",238AP_HAL::micros64(),239(double)new_offset.x,240(double)new_offset.y,241(double)new_offset.z,242(double)offset.x,243(double)offset.y,244(double)offset.z);245printf("F(%.1f %.1f %.1f) O(%.1f %.1f %.1f)\n",246field.x, field.y, field.z,247offset.x, offset.y, offset.z);248#endif249250last_sample_ms = AP_HAL::millis();251252// sensor is not FRD253field.y = -field.y;254255accumulate_sample(field, compass_instance);256257if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) {258state = STATE_REFILL1;259} else {260state = STATE_MEASURE_WAIT3;261}262break;263}264265case STATE_MEASURE_WAIT3: {266uint8_t status;267if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {268break;269}270uint16_t data1[3];271if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {272state = STATE_REFILL1;273break;274}275Vector3f field(float(data1[0]) - zero_offset,276float(data1[1]) - zero_offset,277float(data1[2]) - zero_offset);278field *= -counts_to_milliGauss;279field += offset;280281// sensor is not FRD282field.y = -field.y;283284last_sample_ms = AP_HAL::millis();285accumulate_sample(field, compass_instance);286287// we stay in STATE_MEASURE_WAIT3 for measure_count_limit cycles288if (measure_count++ >= measure_count_limit) {289measure_count = 0;290state = STATE_REFILL1;291} else {292if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement293state = STATE_REFILL1;294}295}296break;297}298}299}300301void AP_Compass_MMC3416::read()302{303drain_accumulated_samples(compass_instance);304}305306#endif // AP_COMPASS_MMC3416_ENABLED307308309