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_RM3100.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 Thomas Schumacher, Jan 201916Structure based on LIS3MDL driver1718*/19#include "AP_Compass_RM3100.h"2021#if AP_COMPASS_RM3100_ENABLED2223#include <AP_HAL/AP_HAL.h>24#include <utility>25#include <AP_Math/AP_Math.h>26#include <stdio.h>2728#define RM3100_POLL_REG 0x002930#define RM3100_CMM_REG 0x013132#define RM3100_CCX1_REG 0x0433#define RM3100_CCX0_REG 0x0534#define RM3100_CCY1_REG 0x0635#define RM3100_CCY0_REG 0x0736#define RM3100_CCZ1_REG 0x0837#define RM3100_CCZ0_REG 0x093839#define RM3100_TMRC_REG 0x0B4041#define RM3100_MX2_REG 0x2442#define RM3100_MX1_REG 0x2543#define RM3100_MX0_REG 0x2644#define RM3100_MY2_REG 0x2745#define RM3100_MY1_REG 0x2846#define RM3100_MY0_REG 0x2947#define RM3100_MZ2_REG 0x2A48#define RM3100_MZ1_REG 0x2B49#define RM3100_MZ0_REG 0x2C5051#define RM3100_BIST_REG 0x3352#define RM3100_STATUS_REG 0x3453#define RM3100_HSHAKE_REG 0x3454#define RM3100_REVID_REG 0x365556#define CCP0 0xC8 // Cycle Count values57#define CCP1 0x0058#define CCP0_DEFAULT 0xC8 // Default Cycle Count values (used as a whoami check)59#define CCP1_DEFAULT 0x0060#define GAIN_CC50 20.0f // LSB/uT61#define GAIN_CC100 38.0f62#define GAIN_CC200 75.0f6364#define TMRC 0x94 // Update rate 150Hz65#define CMM 0x71 // read 3 axes and set data ready if 3 axes are ready6667extern const AP_HAL::HAL &hal;6869AP_Compass_Backend *AP_Compass_RM3100::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,70bool force_external,71enum Rotation rotation)72{73if (!dev) {74return nullptr;75}76AP_Compass_RM3100 *sensor = NEW_NOTHROW AP_Compass_RM3100(std::move(dev), force_external, rotation);77if (!sensor || !sensor->init()) {78delete sensor;79return nullptr;80}8182return sensor;83}8485AP_Compass_RM3100::AP_Compass_RM3100(AP_HAL::OwnPtr<AP_HAL::Device> _dev,86bool _force_external,87enum Rotation _rotation)88: dev(std::move(_dev))89, force_external(_force_external)90, rotation(_rotation)91{92}9394bool AP_Compass_RM3100::init()95{96dev->get_semaphore()->take_blocking();9798if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {99// read has high bit set for SPI100dev->set_read_flag(0x80);101}102103// high retries for init104dev->set_retries(10);105106// use default cycle count values as a whoami test107uint8_t ccx0;108uint8_t ccx1;109uint8_t ccy0;110uint8_t ccy1;111uint8_t ccz0;112uint8_t ccz1;113if (!dev->read_registers(RM3100_CCX1_REG, &ccx1, 1) ||114!dev->read_registers(RM3100_CCX0_REG, &ccx0, 1) ||115!dev->read_registers(RM3100_CCY1_REG, &ccy1, 1) ||116!dev->read_registers(RM3100_CCY0_REG, &ccy0, 1) ||117!dev->read_registers(RM3100_CCZ1_REG, &ccz1, 1) ||118!dev->read_registers(RM3100_CCZ0_REG, &ccz0, 1) ||119ccx1 != CCP1_DEFAULT || ccx0 != CCP0_DEFAULT ||120ccy1 != CCP1_DEFAULT || ccy0 != CCP0_DEFAULT ||121ccz1 != CCP1_DEFAULT || ccz0 != CCP0_DEFAULT) {122// couldn't read one of the cycle count registers or didn't recognize the default cycle count values123dev->get_semaphore()->give();124return false;125}126127dev->setup_checked_registers(8);128129dev->write_register(RM3100_TMRC_REG, TMRC, true); // CMM data rate130dev->write_register(RM3100_CMM_REG, CMM, true); // CMM configuration131dev->write_register(RM3100_CCX1_REG, CCP1, true); // cycle count x132dev->write_register(RM3100_CCX0_REG, CCP0, true); // cycle count x133dev->write_register(RM3100_CCY1_REG, CCP1, true); // cycle count y134dev->write_register(RM3100_CCY0_REG, CCP0, true); // cycle count y135dev->write_register(RM3100_CCZ1_REG, CCP1, true); // cycle count z136dev->write_register(RM3100_CCZ0_REG, CCP0, true); // cycle count z137138_scaler = (1 / GAIN_CC200) * UTESLA_TO_MGAUSS; // has to be changed if using a different cycle count139140// lower retries for run141dev->set_retries(3);142143dev->get_semaphore()->give();144145/* register the compass instance in the frontend */146dev->set_device_type(DEVTYPE_RM3100);147if (!register_compass(dev->get_bus_id(), compass_instance)) {148return false;149}150set_dev_id(compass_instance, dev->get_bus_id());151152DEV_PRINTF("RM3100: Found at address 0x%x as compass %u\n", dev->get_bus_address(), compass_instance);153154set_rotation(compass_instance, rotation);155156if (force_external) {157set_external(compass_instance, true);158}159160// call timer() at 80Hz161dev->register_periodic_callback(1000000U/80U,162FUNCTOR_BIND_MEMBER(&AP_Compass_RM3100::timer, void));163164return true;165}166167void AP_Compass_RM3100::timer()168{169struct PACKED {170uint8_t magx_2;171uint8_t magx_1;172uint8_t magx_0;173uint8_t magy_2;174uint8_t magy_1;175uint8_t magy_0;176uint8_t magz_2;177uint8_t magz_1;178uint8_t magz_0;179} data;180181int32_t magx = 0;182int32_t magy = 0;183int32_t magz = 0;184185// check data ready on 3 axis186uint8_t status;187if (!dev->read_registers(RM3100_STATUS_REG, (uint8_t *)&status, 1)) {188goto check_registers;189}190191if (!(status & 0x80)) {192// data not available yet193goto check_registers;194}195196if (!dev->read_registers(RM3100_MX2_REG, (uint8_t *)&data, sizeof(data))) {197goto check_registers;198}199200// the 24 bits of data for each axis are in 2s complement representation201// each byte is shifted to its position in a 24-bit unsigned integer and from 8 more bits to be left-aligned in a 32-bit integer202magx = ((uint32_t)data.magx_2 << 24) | ((uint32_t)data.magx_1 << 16) | ((uint32_t)data.magx_0 << 8);203magy = ((uint32_t)data.magy_2 << 24) | ((uint32_t)data.magy_1 << 16) | ((uint32_t)data.magy_0 << 8);204magz = ((uint32_t)data.magz_2 << 24) | ((uint32_t)data.magz_1 << 16) | ((uint32_t)data.magz_0 << 8);205206// right-shift signed integer back to get correct measurement value207magx >>= 8;208magy >>= 8;209magz >>= 8;210211#ifdef AP_RM3100_REVERSAL_MASK212// some RM3100 builds get the polarity wrong on one or more of the213// elements. By setting AP_RM3100_REVERSAL_MASK in hwdef.dat you214// can fix it without modifying the hardware215if (AP_RM3100_REVERSAL_MASK & 1U) {216magx = -magx;217}218if (AP_RM3100_REVERSAL_MASK & 2U) {219magy = -magy;220}221if (AP_RM3100_REVERSAL_MASK & 4U) {222magz = -magz;223}224#endif225226{227// apply scaler and store in field vector228Vector3f field{229magx * _scaler,230magy * _scaler,231magz * _scaler232};233234accumulate_sample(field, compass_instance);235}236237check_registers:238dev->check_next_register();239}240241void AP_Compass_RM3100::read()242{243drain_accumulated_samples(compass_instance);244}245246#endif // AP_COMPASS_RM3100_ENABLED247248249