Path: blob/master/libraries/AP_Compass/AP_Compass_MMC3416.cpp
9432 views
/*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::Device> 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())) {96return false;97}9899printf("Found a MMC3416 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), instance);100101set_rotation(rotation);102103if (force_external) {104set_external(true);105}106107dev->set_retries(1);108109// call timer() at 100Hz110dev->register_periodic_callback(10000,111FUNCTOR_BIND_MEMBER(&AP_Compass_MMC3416::timer, void));112113// wait 250ms for the compass to make it's initial readings114hal.scheduler->delay(250);115116return true;117}118119void AP_Compass_MMC3416::timer()120{121const uint16_t measure_count_limit = 50;122const uint16_t zero_offset = 32768; // 16 bit mode123const uint16_t sensitivity = 2048; // counts per Gauss, 16 bit mode124const float counts_to_milliGauss = 1.0e3f / sensitivity;125126uint32_t now = AP_HAL::millis();127if (now - last_sample_ms > 500) {128// seems to be stuck or on first sample, reset state machine129state = STATE_REFILL1;130last_sample_ms = now;131}132133/*134we use the SET/RESET method to remove bridge offset every135measure_count_limit measurements. This involves a fairly complex136state machine, but means we are much less sensitive to137temperature changes138*/139switch (state) {140case STATE_REFILL1:141if (dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {142state = STATE_REFILL1_WAIT;143refill_start_ms = AP_HAL::millis();144}145break;146147case STATE_REFILL1_WAIT: {148uint8_t status;149if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&150dev->read_registers(REG_STATUS, &status, 1) &&151(status & 0x02) == 0) {152if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_SET) ||153!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement154state = STATE_REFILL1;155} else {156state = STATE_MEASURE_WAIT1;157}158}159break;160}161162case STATE_MEASURE_WAIT1: {163uint8_t status;164if (dev->read_registers(REG_STATUS, &status, 1) && (status & 1)) {165if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data0[0], 6)) {166state = STATE_REFILL1;167break;168}169if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_REFILL)) {170state = STATE_REFILL1;171} else {172state = STATE_REFILL2_WAIT;173refill_start_ms = AP_HAL::millis();174}175}176break;177}178179case STATE_REFILL2_WAIT: {180uint8_t status;181if (AP_HAL::millis() - refill_start_ms > MIN_DELAY_SET_RESET &&182dev->read_registers(REG_STATUS, &status, 1) &&183(status & 0x02) == 0) {184if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_RESET) ||185!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement186state = STATE_REFILL1;187} else {188state = STATE_MEASURE_WAIT2;189}190}191break;192}193194case STATE_MEASURE_WAIT2: {195uint8_t status;196if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {197break;198}199uint16_t data1[3];200if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {201state = STATE_REFILL1;202break;203}204Vector3f field;205206/*207calculate field and offset208*/209Vector3f f1(float(data0[0]) - zero_offset,210float(data0[1]) - zero_offset,211float(data0[2]) - zero_offset);212Vector3f f2(float(data1[0]) - zero_offset,213float(data1[1]) - zero_offset,214float(data1[2]) - zero_offset);215field = (f1 - f2) * (counts_to_milliGauss / 2);216Vector3f new_offset = (f1 + f2) * (counts_to_milliGauss / 2);217if (!have_initial_offset) {218offset = new_offset;219have_initial_offset = true;220} else {221// low pass changes to the offset222offset = offset * 0.95f + new_offset * 0.05f;223}224225#if 0226// @LoggerMessage: MMO227// @Description: MMC3416 compass data228// @Field: TimeUS: Time since system startup229// @Field: Nx: new measurement X axis230// @Field: Ny: new measurement Y axis231// @Field: Nz: new measurement Z axis232// @Field: Ox: new offset X axis233// @Field: Oy: new offset Y axis234// @Field: Oz: new offset Z axis235AP::logger().Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",236AP_HAL::micros64(),237(double)new_offset.x,238(double)new_offset.y,239(double)new_offset.z,240(double)offset.x,241(double)offset.y,242(double)offset.z);243printf("F(%.1f %.1f %.1f) O(%.1f %.1f %.1f)\n",244field.x, field.y, field.z,245offset.x, offset.y, offset.z);246#endif247248last_sample_ms = AP_HAL::millis();249250// sensor is not FRD251field.y = -field.y;252253accumulate_sample(field);254255if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) {256state = STATE_REFILL1;257} else {258state = STATE_MEASURE_WAIT3;259}260break;261}262263case STATE_MEASURE_WAIT3: {264uint8_t status;265if (!dev->read_registers(REG_STATUS, &status, 1) || !(status & 1)) {266break;267}268uint16_t data1[3];269if (!dev->read_registers(REG_XOUT_L, (uint8_t *)&data1[0], 6)) {270state = STATE_REFILL1;271break;272}273Vector3f field(float(data1[0]) - zero_offset,274float(data1[1]) - zero_offset,275float(data1[2]) - zero_offset);276field *= -counts_to_milliGauss;277field += offset;278279// sensor is not FRD280field.y = -field.y;281282last_sample_ms = AP_HAL::millis();283accumulate_sample(field);284285// we stay in STATE_MEASURE_WAIT3 for measure_count_limit cycles286if (measure_count++ >= measure_count_limit) {287measure_count = 0;288state = STATE_REFILL1;289} else {290if (!dev->write_register(REG_CONTROL0, REG_CONTROL0_TM)) { // Take Measurement291state = STATE_REFILL1;292}293}294break;295}296}297}298299void AP_Compass_MMC3416::read()300{301drain_accumulated_samples();302}303304#endif // AP_COMPASS_MMC3416_ENABLED305306307