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_Baro/AP_Baro_ICM20789.cpp
Views: 1798
/*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/I2CDevice.h>21#include <utility>2223#include <AP_Common/AP_Common.h>24#include <AP_BoardConfig/AP_BoardConfig.h>2526#include <stdio.h>2728#include <AP_Math/AP_Math.h>29#include <AP_Logger/AP_Logger.h>3031#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>3233extern const AP_HAL::HAL &hal;3435/*36CMD_READ options. The draft datasheet doesn't specify, but it seems37Mode_1 has a conversion interval of 2ms. Mode_3 has a conversion38interval of 20ms. Both seem to produce equally as smooth results, so39presumably Mode_3 is doing internal averaging40*/41#define CMD_READ_PT_MODE_1 0x401A42#define CMD_READ_PT_MODE_3 0x505943#define CMD_READ_TP_MODE_1 0x609C44#define CMD_READ_TP_MODE_3 0x70DF4546#define CONVERSION_INTERVAL_MODE_1 200047#define CONVERSION_INTERVAL_MODE_3 200004849// setup for Mode_350#define CMD_READ_PT CMD_READ_PT_MODE_351#define CONVERSION_INTERVAL CONVERSION_INTERVAL_MODE_35253#define CMD_SOFT_RESET 0x805D54#define CMD_READ_ID 0xEFC85556#define BARO_ICM20789_DEBUG 05758#if BARO_ICM20789_DEBUG59#define debug(fmt, args...) hal.console->printf(fmt, ##args)60#else61#define debug(fmt, args...)62#endif6364/*65constructor66*/67AP_Baro_ICM20789::AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev, AP_HAL::OwnPtr<AP_HAL::Device> _dev_imu)68: AP_Baro_Backend(baro)69, dev(std::move(_dev))70, dev_imu(std::move(_dev_imu))71{72}7374AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro,75AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,76AP_HAL::OwnPtr<AP_HAL::Device> dev_imu)77{78debug("Probing for ICM20789 baro\n");79if (!dev || !dev_imu) {80return nullptr;81}82AP_Baro_ICM20789 *sensor = NEW_NOTHROW AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu));83if (!sensor || !sensor->init()) {84delete sensor;85return nullptr;86}87return sensor;88}899091/*92setup ICM20789 to enable barometer, assuming IMU is on SPI and baro is on I2C93*/94bool AP_Baro_ICM20789::imu_spi_init(void)95{96dev_imu->get_semaphore()->take_blocking();9798dev_imu->set_read_flag(0x80);99100dev_imu->set_speed(AP_HAL::Device::SPEED_LOW);101uint8_t whoami = 0;102uint8_t v;103104dev_imu->read_registers(MPUREG_USER_CTRL, &v, 1);105dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);106107hal.scheduler->delay(1);108dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);109dev_imu->write_register(MPUREG_PWR_MGMT_1,110BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);111112hal.scheduler->delay(1);113dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);114115hal.scheduler->delay(1);116dev_imu->write_register(MPUREG_FIFO_EN, 0x00);117dev_imu->write_register(MPUREG_PWR_MGMT_1,118BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);119120dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);121122// wait for sensor to settle123hal.scheduler->delay(100);124125dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);126127dev_imu->write_register(MPUREG_INT_PIN_CFG, 0x00);128dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);129130dev_imu->get_semaphore()->give();131132return true;133}134135/*136setup ICM20789 to enable barometer, assuming both IMU and baro on the same i2c bus137*/138bool AP_Baro_ICM20789::imu_i2c_init(void)139{140// as the baro device is already locked we need to re-use it,141// changing its address to match the IMU address142uint8_t old_address = dev->get_bus_address();143dev->set_address(dev_imu->get_bus_address());144145dev->set_retries(4);146147uint8_t whoami=0;148dev->read_registers(MPUREG_WHOAMI, &whoami, 1);149debug("ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);150151dev->write_register(MPUREG_FIFO_EN, 0x00);152dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);153154// wait for sensor to settle155hal.scheduler->delay(10);156157dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);158159dev->set_address(old_address);160161return true;162}163164bool AP_Baro_ICM20789::init()165{166if (!dev) {167return false;168}169170debug("Looking for 20789 baro\n");171172dev->get_semaphore()->take_blocking();173174debug("Setting up IMU\n");175if (dev_imu->bus_type() != AP_HAL::Device::BUS_TYPE_I2C) {176if (!imu_spi_init()) {177debug("ICM20789: failed to initialise IMU SPI device\n");178return false;179}180} else if (!imu_i2c_init()) {181debug("ICM20789: failed to initialise IMU I2C device\n");182return false;183}184185if (!send_cmd16(CMD_SOFT_RESET)) {186debug("ICM20789: reset failed\n");187goto failed;188}189190// wait for sensor to settle191hal.scheduler->delay(10);192193if (!read_calibration_data()) {194debug("ICM20789: read_calibration_data failed\n");195goto failed;196}197198// start a reading199if (!send_cmd16(CMD_READ_PT)) {200debug("ICM20789: start read failed\n");201goto failed;202}203204dev->set_retries(0);205206instance = _frontend.register_sensor();207208dev->set_device_type(DEVTYPE_BARO_ICM20789);209set_bus_id(instance, dev->get_bus_id());210211dev->get_semaphore()->give();212213debug("ICM20789: startup OK\n");214215// use 10ms to ensure we don't lose samples, with max lag of 10ms216dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICM20789::timer, void));217218return true;219220failed:221dev->get_semaphore()->give();222return false;223}224225bool AP_Baro_ICM20789::send_cmd16(uint16_t cmd)226{227uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };228return dev->transfer(cmd_b, 2, nullptr, 0);229}230231bool AP_Baro_ICM20789::read_calibration_data(void)232{233// setup for OTP read234const uint8_t cmd[5] = { 0xC5, 0x95, 0x00, 0x66, 0x9C };235if (!dev->transfer(cmd, sizeof(cmd), nullptr, 0)) {236debug("ICM20789: read cal1 failed\n");237return false;238}239for (uint8_t i=0; i<4; i++) {240if (!send_cmd16(0xC7F7)) {241debug("ICM20789: read cal2[%u] failed\n", i);242return false;243}244uint8_t d[3];245if (!dev->transfer(nullptr, 0, d, sizeof(d))) {246debug("ICM20789: read cal3[%u] failed\n", i);247return false;248}249sensor_constants[i] = int16_t((d[0]<<8) | d[1]);250debug("sensor_constants[%u]=%d\n", i, sensor_constants[i]);251}252return true;253}254255void AP_Baro_ICM20789::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],256float &A, float &B, float &C)257{258C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +259p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +260p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /261(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +262p_LUT[0] * (p_Pa[1] - p_Pa[2]) +263p_LUT[1] * (p_Pa[2] - p_Pa[0]));264A = (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]);265B = (p_Pa[0] - A) * (p_LUT[0] + C);266}267268/*269Convert an output from a calibrated sensor to a pressure in Pa.270Arguments:271p_LSB -- Raw pressure data from sensor272T_LSB -- Raw temperature data from sensor273*/274float AP_Baro_ICM20789::get_pressure(uint32_t p_LSB, uint32_t T_LSB)275{276float t = T_LSB - 32768.0;277float s[3];278s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;279s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;280s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;281float A, B, C;282calculate_conversion_constants(p_Pa_calib, s, A, B, C);283return A + B / (C + p_LSB);284}285286287#if BARO_ICM20789_DEBUG288static struct {289uint32_t Praw, Traw;290float T, P;291} dd;292#endif293294void AP_Baro_ICM20789::convert_data(uint32_t Praw, uint32_t Traw)295{296// temperature is easy297float T = -45 + (175.0f / (1U<<16)) * Traw;298299// pressure involves a few more calculations300float P = get_pressure(Praw, Traw);301302if (!pressure_ok(P)) {303return;304}305306WITH_SEMAPHORE(_sem);307308#if BARO_ICM20789_DEBUG309dd.Praw = Praw;310dd.Traw = Traw;311dd.P = P;312dd.T = T;313#endif314315accum.psum += P;316accum.tsum += T;317accum.count++;318}319320void AP_Baro_ICM20789::timer(void)321{322uint8_t d[9] {};323if (dev->transfer(nullptr, 0, d, sizeof(d))) {324// ignore CRC bytes for now325uint32_t Praw = (uint32_t(d[0]) << 16) | (uint32_t(d[1]) << 8) | d[3];326uint32_t Traw = (uint32_t(d[6]) << 8) | d[7];327328convert_data(Praw, Traw);329send_cmd16(CMD_READ_PT);330last_measure_us = AP_HAL::micros();331} else {332if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {333// lost a sample334send_cmd16(CMD_READ_PT);335last_measure_us = AP_HAL::micros();336}337}338}339340void AP_Baro_ICM20789::update()341{342#if BARO_ICM20789_DEBUG343// useful for debugging344// @LoggerMessage: ICMB345// @Description: ICM20789 diagnostics346// @Field: TimeUS: Time since system startup347// @Field: Traw: raw temperature from sensor348// @Field: Praw: raw pressure from sensor349// @Field: P: pressure350// @Field: T: temperature351AP::logger().WriteStreaming("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",352AP_HAL::micros64(),353dd.Traw, dd.Praw, dd.P, dd.T);354#endif355356WITH_SEMAPHORE(_sem);357358if (accum.count > 0) {359_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);360accum.psum = accum.tsum = 0;361accum.count = 0;362}363}364365#endif // AP_BARO_ICM20789_ENABLED366367368