Path: blob/master/libraries/AP_Baro/AP_Baro_ICM20789.cpp
9316 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Baro_ICM20789.h"1617#if AP_BARO_ICM20789_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <AP_HAL/Device.h>2122#include <AP_Common/AP_Common.h>23#include <AP_BoardConfig/AP_BoardConfig.h>2425#include <stdio.h>2627#include <AP_Math/AP_Math.h>28#include <AP_Logger/AP_Logger.h>2930#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>3132extern const AP_HAL::HAL &hal;3334/*35CMD_READ options. The draft datasheet doesn't specify, but it seems36Mode_1 has a conversion interval of 2ms. Mode_3 has a conversion37interval of 20ms. Both seem to produce equally as smooth results, so38presumably Mode_3 is doing internal averaging39*/40#define CMD_READ_PT_MODE_1 0x401A41#define CMD_READ_PT_MODE_3 0x505942#define CMD_READ_TP_MODE_1 0x609C43#define CMD_READ_TP_MODE_3 0x70DF4445#define CONVERSION_INTERVAL_MODE_1 200046#define CONVERSION_INTERVAL_MODE_3 200004748// setup for Mode_349#define CMD_READ_PT CMD_READ_PT_MODE_350#define CONVERSION_INTERVAL CONVERSION_INTERVAL_MODE_35152#define CMD_SOFT_RESET 0x805D53#define CMD_READ_ID 0xEFC85455#define BARO_ICM20789_DEBUG 05657#if BARO_ICM20789_DEBUG58#define debug(fmt, args...) hal.console->printf(fmt, ##args)59#else60#define debug(fmt, args...)61#endif6263/*64constructor65*/66AP_Baro_ICM20789::AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::Device &_dev, AP_HAL::Device &_dev_imu)67: AP_Baro_Backend(baro)68, dev(&_dev)69, dev_imu(&_dev_imu)70{71}7273AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro,74AP_HAL::Device &dev,75AP_HAL::Device &dev_imu)76{77debug("Probing for ICM20789 baro\n");78AP_Baro_ICM20789 *sensor = NEW_NOTHROW AP_Baro_ICM20789(baro, dev, dev_imu);79if (!sensor || !sensor->init()) {80delete sensor;81return nullptr;82}83return sensor;84}858687/*88setup ICM20789 to enable barometer, assuming IMU is on SPI and baro is on I2C89*/90bool AP_Baro_ICM20789::imu_spi_init(void)91{92dev_imu->get_semaphore()->take_blocking();9394dev_imu->set_read_flag(0x80);9596dev_imu->set_speed(AP_HAL::Device::SPEED_LOW);97uint8_t whoami = 0;98uint8_t v;99100dev_imu->read_registers(MPUREG_USER_CTRL, &v, 1);101dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);102103hal.scheduler->delay(1);104dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);105dev_imu->write_register(MPUREG_PWR_MGMT_1,106BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);107108hal.scheduler->delay(1);109dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);110111hal.scheduler->delay(1);112dev_imu->write_register(MPUREG_FIFO_EN, 0x00);113dev_imu->write_register(MPUREG_PWR_MGMT_1,114BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);115116dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);117118// wait for sensor to settle119hal.scheduler->delay(100);120121dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);122123dev_imu->write_register(MPUREG_INT_PIN_CFG, 0x00);124dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);125126dev_imu->get_semaphore()->give();127128return true;129}130131/*132setup ICM20789 to enable barometer, assuming both IMU and baro on the same i2c bus133*/134bool AP_Baro_ICM20789::imu_i2c_init(void)135{136// as the baro device is already locked we need to re-use it,137// changing its address to match the IMU address138uint8_t old_address = dev->get_bus_address();139dev->set_address(dev_imu->get_bus_address());140141dev->set_retries(4);142143uint8_t whoami=0;144dev->read_registers(MPUREG_WHOAMI, &whoami, 1);145debug("ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);146147dev->write_register(MPUREG_FIFO_EN, 0x00);148dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);149150// wait for sensor to settle151hal.scheduler->delay(10);152153dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);154155dev->set_address(old_address);156157return true;158}159160bool AP_Baro_ICM20789::init()161{162if (!dev) {163return false;164}165166debug("Looking for 20789 baro\n");167168dev->get_semaphore()->take_blocking();169170debug("Setting up IMU\n");171if (dev_imu->bus_type() != AP_HAL::Device::BUS_TYPE_I2C) {172if (!imu_spi_init()) {173debug("ICM20789: failed to initialise IMU SPI device\n");174return false;175}176} else if (!imu_i2c_init()) {177debug("ICM20789: failed to initialise IMU I2C device\n");178return false;179}180181if (!send_cmd16(CMD_SOFT_RESET)) {182debug("ICM20789: reset failed\n");183goto failed;184}185186// wait for sensor to settle187hal.scheduler->delay(10);188189if (!read_calibration_data()) {190debug("ICM20789: read_calibration_data failed\n");191goto failed;192}193194// start a reading195if (!send_cmd16(CMD_READ_PT)) {196debug("ICM20789: start read failed\n");197goto failed;198}199200dev->set_retries(0);201202instance = _frontend.register_sensor();203204dev->set_device_type(DEVTYPE_BARO_ICM20789);205set_bus_id(instance, dev->get_bus_id());206207dev->get_semaphore()->give();208209debug("ICM20789: startup OK\n");210211// use 10ms to ensure we don't lose samples, with max lag of 10ms212dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICM20789::timer, void));213214return true;215216failed:217dev->get_semaphore()->give();218return false;219}220221bool AP_Baro_ICM20789::send_cmd16(uint16_t cmd)222{223uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };224return dev->transfer(cmd_b, 2, nullptr, 0);225}226227bool AP_Baro_ICM20789::read_calibration_data(void)228{229// setup for OTP read230const uint8_t cmd[5] = { 0xC5, 0x95, 0x00, 0x66, 0x9C };231if (!dev->transfer(cmd, sizeof(cmd), nullptr, 0)) {232debug("ICM20789: read cal1 failed\n");233return false;234}235for (uint8_t i=0; i<4; i++) {236if (!send_cmd16(0xC7F7)) {237debug("ICM20789: read cal2[%u] failed\n", i);238return false;239}240uint8_t d[3];241if (!dev->transfer(nullptr, 0, d, sizeof(d))) {242debug("ICM20789: read cal3[%u] failed\n", i);243return false;244}245sensor_constants[i] = int16_t((d[0]<<8) | d[1]);246debug("sensor_constants[%u]=%d\n", i, sensor_constants[i]);247}248return true;249}250251void AP_Baro_ICM20789::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],252float &A, float &B, float &C)253{254C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +255p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +256p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /257(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +258p_LUT[0] * (p_Pa[1] - p_Pa[2]) +259p_LUT[1] * (p_Pa[2] - p_Pa[0]));260A = (p_Pa[0] * p_LUT[0] - p_Pa[1] * p_LUT[1] - (p_Pa[1] - p_Pa[0]) * C) / (p_LUT[0] - p_LUT[1]);261B = (p_Pa[0] - A) * (p_LUT[0] + C);262}263264/*265Convert an output from a calibrated sensor to a pressure in Pa.266Arguments:267p_LSB -- Raw pressure data from sensor268T_LSB -- Raw temperature data from sensor269*/270float AP_Baro_ICM20789::get_pressure(uint32_t p_LSB, uint32_t T_LSB)271{272float t = T_LSB - 32768.0;273float s[3];274s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;275s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;276s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;277float A, B, C;278calculate_conversion_constants(p_Pa_calib, s, A, B, C);279return A + B / (C + p_LSB);280}281282283#if BARO_ICM20789_DEBUG284static struct {285uint32_t Praw, Traw;286float T, P;287} dd;288#endif289290void AP_Baro_ICM20789::convert_data(uint32_t Praw, uint32_t Traw)291{292// temperature is easy293float T = -45 + (175.0f / (1U<<16)) * Traw;294295// pressure involves a few more calculations296float P = get_pressure(Praw, Traw);297298if (!pressure_ok(P)) {299return;300}301302WITH_SEMAPHORE(_sem);303304#if BARO_ICM20789_DEBUG305dd.Praw = Praw;306dd.Traw = Traw;307dd.P = P;308dd.T = T;309#endif310311accum.psum += P;312accum.tsum += T;313accum.count++;314}315316void AP_Baro_ICM20789::timer(void)317{318uint8_t d[9] {};319if (dev->transfer(nullptr, 0, d, sizeof(d))) {320// ignore CRC bytes for now321uint32_t Praw = (uint32_t(d[0]) << 16) | (uint32_t(d[1]) << 8) | d[3];322uint32_t Traw = (uint32_t(d[6]) << 8) | d[7];323324convert_data(Praw, Traw);325send_cmd16(CMD_READ_PT);326last_measure_us = AP_HAL::micros();327} else {328if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {329// lost a sample330send_cmd16(CMD_READ_PT);331last_measure_us = AP_HAL::micros();332}333}334}335336void AP_Baro_ICM20789::update()337{338#if BARO_ICM20789_DEBUG339// useful for debugging340// @LoggerMessage: ICMB341// @Description: ICM20789 diagnostics342// @Field: TimeUS: Time since system startup343// @Field: Traw: raw temperature from sensor344// @Field: Praw: raw pressure from sensor345// @Field: P: pressure346// @Field: T: temperature347AP::logger().WriteStreaming("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",348AP_HAL::micros64(),349dd.Traw, dd.Praw, dd.P, dd.T);350#endif351352WITH_SEMAPHORE(_sem);353354if (accum.count > 0) {355_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);356accum.psum = accum.tsum = 0;357accum.count = 0;358}359}360361#endif // AP_BARO_ICM20789_ENABLED362363364