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_LIS3MDL.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 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 0x3d4950extern const AP_HAL::HAL &hal;5152AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,53bool force_external,54enum Rotation rotation)55{56if (!dev) {57return nullptr;58}59AP_Compass_LIS3MDL *sensor = NEW_NOTHROW AP_Compass_LIS3MDL(std::move(dev), force_external, rotation);60if (!sensor || !sensor->init()) {61delete sensor;62return nullptr;63}6465return sensor;66}6768AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,69bool _force_external,70enum Rotation _rotation)71: dev(std::move(_dev))72, force_external(_force_external)73, rotation(_rotation)74{75}7677bool AP_Compass_LIS3MDL::init()78{79dev->get_semaphore()->take_blocking();8081if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {82dev->set_read_flag(0xC0);83}8485// high retries for init86dev->set_retries(10);8788uint8_t whoami;89if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||90whoami != ID_WHO_AM_I) {91// not a 3MDL92goto fail;93}9495dev->setup_checked_registers(5);9697dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP98dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range99dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous100dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf101dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update102103// lower retries for run104dev->set_retries(3);105106dev->get_semaphore()->give();107108/* register the compass instance in the frontend */109dev->set_device_type(DEVTYPE_LIS3MDL);110if (!register_compass(dev->get_bus_id(), compass_instance)) {111return false;112}113set_dev_id(compass_instance, dev->get_bus_id());114115printf("Found a LIS3MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance);116117set_rotation(compass_instance, rotation);118119if (force_external) {120set_external(compass_instance, true);121}122123// call timer() at 80Hz124dev->register_periodic_callback(1000000U/80U,125FUNCTOR_BIND_MEMBER(&AP_Compass_LIS3MDL::timer, void));126127return true;128129fail:130dev->get_semaphore()->give();131return false;132}133134void AP_Compass_LIS3MDL::timer()135{136struct PACKED {137int16_t magx;138int16_t magy;139int16_t magz;140} data;141const float range_scale = 1000.0f / 6842.0f;142143// check data ready144uint8_t status;145if (!dev->read_registers(ADDR_STATUS_REG, (uint8_t *)&status, 1)) {146goto check_registers;147}148if (!(status & 0x08)) {149// data not available yet150goto check_registers;151}152153if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {154goto check_registers;155}156157{158Vector3f field{159data.magx * range_scale,160data.magy * range_scale,161data.magz * range_scale,162};163164accumulate_sample(field, compass_instance);165}166167check_registers:168dev->check_next_register();169}170171void AP_Compass_LIS3MDL::read()172{173drain_accumulated_samples(compass_instance);174}175176#endif // AP_COMPASS_LIS3MDL_ENABLED177178179