Path: blob/master/libraries/AP_Compass/AP_Compass_LIS2MDL.cpp
6351 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 for the LIS2MDL magnetometer.16*/17#include "AP_Compass_config.h"1819#if AP_COMPASS_LIS2MDL_ENABLED2021#include "AP_Compass_LIS2MDL.h"2223#include <AP_HAL/AP_HAL.h>24#include <utility>25#include <AP_Math/AP_Math.h>26#include <stdio.h>2728// Register addresses29#define ADDR_WHO_AM_I 0x4F30#define ADDR_CFG_REG_A 0x6031#define ADDR_CFG_REG_B 0x6132#define ADDR_CFG_REG_C 0x6233#define ADDR_STATUS_REG 0x6734#define ADDR_OUT_X_L 0x683536// WHO_AM_I device ID37#define ID_WHO_AM_I 0x403839AP_Compass_Backend *AP_Compass_LIS2MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,40bool force_external,41enum Rotation rotation)42{43if (!dev) {44return nullptr;45}46AP_Compass_LIS2MDL *sensor = NEW_NOTHROW AP_Compass_LIS2MDL(std::move(dev), force_external, rotation);47if (!sensor || !sensor->init()) {48delete sensor;49return nullptr;50}5152return sensor;53}5455AP_Compass_LIS2MDL::AP_Compass_LIS2MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,56bool _force_external,57enum Rotation _rotation)58: dev(std::move(_dev))59, force_external(_force_external)60, rotation(_rotation)61{62}6364// @brief Initialize the sensor65bool AP_Compass_LIS2MDL::init()66{67WITH_SEMAPHORE(dev->get_semaphore());6869if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {70// LIS2MDL SPI reads are MSb=1, autoincrement.71dev->set_read_flag(0xC0);72}7374// high retries for init75dev->set_retries(10);7677uint8_t whoami;78if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||79whoami != ID_WHO_AM_I) {80// not a LIS2MDL81return false;82}8384dev->setup_checked_registers(3);8586// Configure for 100Hz continuous mode, with temperature compensation.87dev->write_register(ADDR_CFG_REG_A, 0b10001100, true); // ODR=100Hz, continuous mode, temp comp on8889// Default settings for CFG_REG_B are fine.90dev->write_register(ADDR_CFG_REG_B, 0x00, true);9192// Enable Block Data Update (BDU)93dev->write_register(ADDR_CFG_REG_C, 0b00010000, true);9495// lower retries for run96dev->set_retries(3);9798/* register the compass instance in the frontend */99dev->set_device_type(DEVTYPE_LIS2MDL);100if (!register_compass(dev->get_bus_id())) {101return false;102}103104printf("Found a LIS2MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), instance);105106set_rotation(rotation);107108if (force_external) {109set_external(force_external);110}111112// call timer() at 100Hz113dev->register_periodic_callback(1000000U/100U,114FUNCTOR_BIND_MEMBER(&AP_Compass_LIS2MDL::timer, void));115116return true;117}118119// @brief Read data from the sensor and accumulate it120void AP_Compass_LIS2MDL::timer()121{122struct PACKED {123int16_t magx;124int16_t magy;125int16_t magz;126} data;127128// Sensitivity is 1.5 mgauss/LSB129const float range_scale = 1.5f;130131// check data ready132uint8_t status;133if (!dev->read_registers(ADDR_STATUS_REG, &status, 1)) {134goto check_registers;135}136if (!(status & 0x08)) { // ZYXDA bit137// data not available yet138goto check_registers;139}140141if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {142goto check_registers;143}144145{146Vector3f field{147(float)data.magx * range_scale,148(float)data.magy * range_scale,149(float)-data.magz * range_scale, // for unknown reasons the Z axis appears to be reversed, without this it is impossible to orient correctly150};151152accumulate_sample(field, instance);153}154155check_registers:156dev->check_next_register();157}158159// @brief Publish accumulated data to the frontend160void AP_Compass_LIS2MDL::read()161{162drain_accumulated_samples();163}164165#endif // AP_COMPASS_LIS2MDL_ENABLED166167168