Path: blob/master/libraries/AP_Compass/AP_Compass_LIS3MDL.cpp
9448 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 20161617thanks to Robert Dickenson and the PX4 team for register definitions18*/19#include "AP_Compass_LIS3MDL.h"2021#if AP_COMPASS_LIS3MDL_ENABLED2223#include <AP_HAL/AP_HAL.h>24#include <utility>25#include <AP_Math/AP_Math.h>26#include <stdio.h>2728#define ADDR_CTRL_REG1 0x2029#define ADDR_CTRL_REG2 0x2130#define ADDR_CTRL_REG3 0x2231#define ADDR_CTRL_REG4 0x2332#define ADDR_CTRL_REG5 0x243334#define ADDR_STATUS_REG 0x2735#define ADDR_OUT_X_L 0x2836#define ADDR_OUT_X_H 0x2937#define ADDR_OUT_Y_L 0x2a38#define ADDR_OUT_Y_H 0x2b39#define ADDR_OUT_Z_L 0x2c40#define ADDR_OUT_Z_H 0x2d41#define ADDR_OUT_T_L 0x2e42#define ADDR_OUT_T_H 0x2f4344#define MODE_REG_CONTINOUS_MODE (0 << 0)45#define MODE_REG_SINGLE_MODE (1 << 0)4647#define ADDR_WHO_AM_I 0x0f48#define ID_WHO_AM_I 0x3d4950AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,51bool force_external,52enum Rotation rotation)53{54if (!dev) {55return nullptr;56}57AP_Compass_LIS3MDL *sensor = NEW_NOTHROW AP_Compass_LIS3MDL(std::move(dev), force_external, rotation);58if (!sensor || !sensor->init()) {59delete sensor;60return nullptr;61}6263return sensor;64}6566AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,67bool _force_external,68enum Rotation _rotation)69: dev(std::move(_dev))70, force_external(_force_external)71, rotation(_rotation)72{73}7475bool AP_Compass_LIS3MDL::init()76{77dev->get_semaphore()->take_blocking();7879if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {80dev->set_read_flag(0xC0);81}8283// high retries for init84dev->set_retries(10);8586uint8_t whoami;87if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||88whoami != ID_WHO_AM_I) {89// not a 3MDL90goto fail;91}9293dev->setup_checked_registers(5);9495dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP96dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range97dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous98dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf99dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update100101// lower retries for run102dev->set_retries(3);103104dev->get_semaphore()->give();105106/* register the compass instance in the frontend */107dev->set_device_type(DEVTYPE_LIS3MDL);108if (!register_compass(dev->get_bus_id())) {109return false;110}111112printf("Found a LIS3MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), instance);113114set_rotation(rotation);115116if (force_external) {117set_external(true);118}119120// call timer() at 80Hz121dev->register_periodic_callback(1000000U/80U,122FUNCTOR_BIND_MEMBER(&AP_Compass_LIS3MDL::timer, void));123124return true;125126fail:127dev->get_semaphore()->give();128return false;129}130131void AP_Compass_LIS3MDL::timer()132{133struct PACKED {134int16_t magx;135int16_t magy;136int16_t magz;137} data;138const float range_scale = 1000.0f / 6842.0f;139140// check data ready141uint8_t status;142if (!dev->read_registers(ADDR_STATUS_REG, (uint8_t *)&status, 1)) {143goto check_registers;144}145if (!(status & 0x08)) {146// data not available yet147goto check_registers;148}149150if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {151goto check_registers;152}153154{155Vector3f field{156data.magx * range_scale,157data.magy * range_scale,158data.magz * range_scale,159};160161accumulate_sample(field);162}163164check_registers:165dev->check_next_register();166}167168void AP_Compass_LIS3MDL::read()169{170drain_accumulated_samples();171}172173#endif // AP_COMPASS_LIS3MDL_ENABLED174175176