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_IST8310.cpp
Views: 1798
/*1* Copyright (C) 2016 Emlid Ltd. All rights reserved.2*3* This file is free software: you can redistribute it and/or modify it4* under the terms of the GNU General Public License as published by the5* Free Software Foundation, either version 3 of the License, or6* (at your option) any later version.7*8* This file is distributed in the hope that it will be useful, but9* WITHOUT ANY WARRANTY; without even the implied warranty of10* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.11* See the GNU General Public License for more details.12*13* You should have received a copy of the GNU General Public License along14* with this program. If not, see <http://www.gnu.org/licenses/>.15*16* Driver by Georgii Staroselskii, Sep 201617*/18#include "AP_Compass_IST8310.h"1920#if AP_COMPASS_IST8310_ENABLED2122#include <stdio.h>23#include <utility>2425#include <AP_HAL/AP_HAL.h>26#include <AP_HAL/utility/sparse-endian.h>27#include <AP_Math/AP_Math.h>28#include <AP_BoardConfig/AP_BoardConfig.h>2930#define WAI_REG 0x031#define DEVICE_ID 0x103233#define OUTPUT_X_L_REG 0x334#define OUTPUT_X_H_REG 0x435#define OUTPUT_Y_L_REG 0x536#define OUTPUT_Y_H_REG 0x637#define OUTPUT_Z_L_REG 0x738#define OUTPUT_Z_H_REG 0x83940#define CNTL1_REG 0xA41#define CNTL1_VAL_SINGLE_MEASUREMENT_MODE 0x14243#define CNTL2_REG 0xB44#define CNTL2_VAL_SRST 14546#define AVGCNTL_REG 0x4147#define AVGCNTL_VAL_XZ_0 (0)48#define AVGCNTL_VAL_XZ_2 (1)49#define AVGCNTL_VAL_XZ_4 (2)50#define AVGCNTL_VAL_XZ_8 (3)51#define AVGCNTL_VAL_XZ_16 (4)52#define AVGCNTL_VAL_Y_0 (0 << 3)53#define AVGCNTL_VAL_Y_2 (1 << 3)54#define AVGCNTL_VAL_Y_4 (2 << 3)55#define AVGCNTL_VAL_Y_8 (3 << 3)56#define AVGCNTL_VAL_Y_16 (4 << 3)5758#define PDCNTL_REG 0x4259#define PDCNTL_VAL_PULSE_DURATION_NORMAL 0xC06061#define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC)6263/*64* FSR:65* x, y: +- 1600 µT66* z: +- 2500 µT67*68* Resolution according to datasheet is 0.3µT/LSB69*/70#define IST8310_RESOLUTION 0.37172static const int16_t IST8310_MAX_VAL_XY = (1600 / IST8310_RESOLUTION) + 1;73static const int16_t IST8310_MIN_VAL_XY = -IST8310_MAX_VAL_XY;74static const int16_t IST8310_MAX_VAL_Z = (2500 / IST8310_RESOLUTION) + 1;75static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;767778extern const AP_HAL::HAL &hal;7980AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,81bool force_external,82enum Rotation rotation)83{84if (!dev) {85return nullptr;86}8788AP_Compass_IST8310 *sensor = NEW_NOTHROW AP_Compass_IST8310(std::move(dev), force_external, rotation);89if (!sensor || !sensor->init()) {90delete sensor;91return nullptr;92}9394return sensor;95}9697AP_Compass_IST8310::AP_Compass_IST8310(AP_HAL::OwnPtr<AP_HAL::Device> dev,98bool force_external,99enum Rotation rotation)100: _dev(std::move(dev))101, _rotation(rotation)102, _force_external(force_external)103{104}105106bool AP_Compass_IST8310::init()107{108uint8_t reset_count = 0;109110_dev->get_semaphore()->take_blocking();111112// high retries for init113_dev->set_retries(10);114115/*116unfortunately the IST8310 employs the novel concept of a117writeable WHOAMI register. The register can become corrupt due118to bus noise, and what is worse it persists the corruption even119across a power cycle. If you power it off for 30s or more then120it will reset to the default of 0x10, but for less than that the121value of WAI is unreliable.122123To avoid this issue we do a reset of the device before we probe124the WAI register. This is nasty as we don't yet know we've found125a real IST8310, but it is the best we can do given the bad126hardware design of the sensor127*/128_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST);129hal.scheduler->delay(10);130131uint8_t whoami;132if (!_dev->read_registers(WAI_REG, &whoami, 1) ||133whoami != DEVICE_ID) {134// not an IST8310135goto fail;136}137138for (; reset_count < 5; reset_count++) {139if (!_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST)) {140hal.scheduler->delay(10);141continue;142}143144hal.scheduler->delay(10);145146uint8_t cntl2 = 0xFF;147if (_dev->read_registers(CNTL2_REG, &cntl2, 1) &&148(cntl2 & 0x01) == 0) {149break;150}151}152153if (reset_count == 5) {154printf("IST8310: failed to reset device\n");155goto fail;156}157158if (!_dev->write_register(AVGCNTL_REG, AVGCNTL_VAL_Y_16 | AVGCNTL_VAL_XZ_16) ||159!_dev->write_register(PDCNTL_REG, PDCNTL_VAL_PULSE_DURATION_NORMAL)) {160printf("IST8310: found device but could not set it up\n");161goto fail;162}163164// lower retries for run165_dev->set_retries(3);166167// start state machine: request a sample168start_conversion();169170_dev->get_semaphore()->give();171172// register compass instance173_dev->set_device_type(DEVTYPE_IST8310);174if (!register_compass(_dev->get_bus_id(), _instance)) {175return false;176}177set_dev_id(_instance, _dev->get_bus_id());178179printf("%s found on bus %u id %u address 0x%02x\n", name,180_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());181182set_rotation(_instance, _rotation);183184if (_force_external) {185set_external(_instance, true);186}187188_periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC,189FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void));190191return true;192193fail:194_dev->get_semaphore()->give();195return false;196}197198void AP_Compass_IST8310::start_conversion()199{200if (!_dev->write_register(CNTL1_REG, CNTL1_VAL_SINGLE_MEASUREMENT_MODE)) {201_ignore_next_sample = true;202}203}204205void AP_Compass_IST8310::timer()206{207if (_ignore_next_sample) {208_ignore_next_sample = false;209start_conversion();210return;211}212213struct PACKED {214le16_t rx;215le16_t ry;216le16_t rz;217} buffer;218219bool ret = _dev->read_registers(OUTPUT_X_L_REG, (uint8_t *) &buffer, sizeof(buffer));220if (!ret) {221return;222}223224start_conversion();225226/* same period, but start counting from now */227_dev->adjust_periodic_callback(_periodic_handle, SAMPLING_PERIOD_USEC);228229auto x = static_cast<int16_t>(le16toh(buffer.rx));230auto y = static_cast<int16_t>(le16toh(buffer.ry));231auto z = static_cast<int16_t>(le16toh(buffer.rz));232233/*234* Check if value makes sense according to the FSR and Resolution of235* this sensor, discarding outliers236*/237if (x > IST8310_MAX_VAL_XY || x < IST8310_MIN_VAL_XY ||238y > IST8310_MAX_VAL_XY || y < IST8310_MIN_VAL_XY ||239z > IST8310_MAX_VAL_Z || z < IST8310_MIN_VAL_Z) {240return;241}242243// flip Z to conform to right-hand rule convention244z = -z;245246/* Resolution: 0.3 µT/LSB - already convert to milligauss */247Vector3f field = Vector3f{x * 3.0f, y * 3.0f, z * 3.0f};248249accumulate_sample(field, _instance);250}251252void AP_Compass_IST8310::read()253{254drain_accumulated_samples(_instance);255}256257#endif // AP_COMPASS_IST8310_ENABLED258259260