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_ICP201XX.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.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/1213#include "AP_Baro_ICP201XX.h"1415#if AP_BARO_ICP201XX_ENABLED1617#include <AP_HAL/AP_HAL.h>18#include <AP_HAL/I2CDevice.h>19#include <utility>2021#include <AP_Common/AP_Common.h>22#include <AP_HAL/AP_HAL.h>23#include <AP_Math/AP_Math.h>24#include <AP_BoardConfig/AP_BoardConfig.h>2526#include <utility>27#include <stdio.h>2829#include <AP_Math/AP_Math.h>30#include <AP_Logger/AP_Logger.h>3132#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>3334extern const AP_HAL::HAL &hal;3536#define ICP201XX_ID 0x633738#define CONVERSION_INTERVAL 250003940#define REG_EMPTY 0x0041#define REG_TRIM1_MSB 0x0542#define REG_TRIM2_LSB 0x0643#define REG_TRIM2_MSB 0x0744#define REG_DEVICE_ID 0x0C45#define REG_OTP_MTP_OTP_CFG1 0xAC46#define REG_OTP_MTP_MR_LSB 0xAD47#define REG_OTP_MTP_MR_MSB 0xAE48#define REG_OTP_MTP_MRA_LSB 0xAF49#define REG_OTP_MTP_MRA_MSB 0xB050#define REG_OTP_MTP_MRB_LSB 0xB151#define REG_OTP_MTP_MRB_MSB 0xB252#define REG_OTP_MTP_OTP_ADDR 0xB553#define REG_OTP_MTP_OTP_CMD 0xB654#define REG_OTP_MTP_RD_DATA 0xB855#define REG_OTP_MTP_OTP_STATUS 0xB956#define REG_OTP_DEBUG2 0xBC57#define REG_MASTER_LOCK 0xBE58#define REG_OTP_MTP_OTP_STATUS2 0xBF59#define REG_MODE_SELECT 0xC060#define REG_INTERRUPT_STATUS 0xC161#define REG_INTERRUPT_MASK 0xC262#define REG_FIFO_CONFIG 0xC363#define REG_FIFO_FILL 0xC464#define REG_SPI_MODE 0xC565#define REG_PRESS_ABS_LSB 0xC766#define REG_PRESS_ABS_MSB 0xC867#define REG_PRESS_DELTA_LSB 0xC968#define REG_PRESS_DELTA_MSB 0xCA69#define REG_DEVICE_STATUS 0xCD70#define REG_I3C_INFO 0xCE71#define REG_VERSION 0xD372#define REG_FIFO_BASE 0xFA7374/*75constructor76*/77AP_Baro_ICP201XX::AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)78: AP_Baro_Backend(baro)79, dev(std::move(_dev))80{81}8283AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro,84AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)85{86if (!dev) {87return nullptr;88}89AP_Baro_ICP201XX *sensor = NEW_NOTHROW AP_Baro_ICP201XX(baro, std::move(dev));90if (!sensor || !sensor->init()) {91delete sensor;92return nullptr;93}94return sensor;95}9697bool AP_Baro_ICP201XX::init()98{99if (!dev) {100return false;101}102103dev->get_semaphore()->take_blocking();104105uint8_t id = 0xFF;106uint8_t ver = 0xFF;107read_reg(REG_DEVICE_ID, &id);108read_reg(REG_DEVICE_ID, &id);109read_reg(REG_VERSION, &ver);110111if (id != ICP201XX_ID) {112goto failed;113}114115if (ver != 0x00 && ver != 0xB2) {116goto failed;117}118119hal.scheduler->delay(10);120121soft_reset();122123if (!boot_sequence()) {124goto failed;125}126127if (!configure()) {128goto failed;129}130131wait_read();132133dev->set_retries(0);134135instance = _frontend.register_sensor();136137dev->set_device_type(DEVTYPE_BARO_ICP201XX);138set_bus_id(instance, dev->get_bus_id());139140dev->get_semaphore()->give();141142dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP201XX::timer, void));143return true;144145failed:146dev->get_semaphore()->give();147return false;148}149150151void AP_Baro_ICP201XX::dummy_reg()152{153do {154uint8_t reg = REG_EMPTY;155uint8_t val = 0;156dev->transfer(®, 1, &val, 1);157} while (0);158}159160bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *buf, uint8_t len)161{162bool ret;163ret = dev->transfer(®, 1, buf, len);164dummy_reg();165return ret;166}167168bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *val)169{170return read_reg(reg, val, 1);171}172173bool AP_Baro_ICP201XX::write_reg(uint8_t reg, uint8_t val)174{175bool ret;176uint8_t data[2] = { reg, val };177ret = dev->transfer(data, sizeof(data), nullptr, 0);178dummy_reg();179return ret;180}181182void AP_Baro_ICP201XX::soft_reset()183{184/* Stop the measurement */185mode_select(0x00);186187hal.scheduler->delay(2);188189/* Flush FIFO */190flush_fifo();191192/* Mask all interrupts */193write_reg(REG_FIFO_CONFIG, 0x00);194write_reg(REG_INTERRUPT_MASK, 0xFF);195}196197bool AP_Baro_ICP201XX::mode_select(uint8_t mode)198{199uint8_t mode_sync_status = 0;200201do {202read_reg(REG_DEVICE_STATUS, &mode_sync_status, 1);203204if (mode_sync_status & 0x01) {205break;206}207208hal.scheduler->delay(1);209} while (1);210211return write_reg(REG_MODE_SELECT, mode);212}213214bool AP_Baro_ICP201XX::read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val)215{216uint8_t otp_status = 0xFF;217218/* Write the address content and read command */219if (!write_reg(REG_OTP_MTP_OTP_ADDR, addr)) {220return false;221}222223if (!write_reg(REG_OTP_MTP_OTP_CMD, cmd)) {224return false;225}226227/* Wait for the OTP read to finish Monitor otp_status */228do {229read_reg(REG_OTP_MTP_OTP_STATUS, &otp_status);230231if (otp_status == 0) {232break;233}234235hal.scheduler->delay_microseconds(1);236} while (1);237238/* Read the data from register */239if (!read_reg(REG_OTP_MTP_RD_DATA, val)) {240return false;241}242243return true;244}245246bool AP_Baro_ICP201XX::get_sensor_data(float *pressure, float *temperature)247{248uint8_t fifo_data[96] {0};249uint8_t fifo_packets = 0;250int32_t data_temp = 0;251int32_t data_press = 0;252*pressure = 0;253*temperature = 0;254255if (read_reg(REG_FIFO_FILL, &fifo_packets)) {256fifo_packets = (uint8_t)(fifo_packets & 0x1F);257if (fifo_packets > 16) {258flush_fifo();259return false;260}261if (fifo_packets > 0 && fifo_packets <= 16 && read_reg(REG_FIFO_BASE, fifo_data, fifo_packets * 2 * 3)) {262uint8_t offset = 0;263264for (uint8_t i = 0; i < fifo_packets; i++) {265data_press = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);266if (data_press & 0x080000) {267data_press |= 0xFFF00000;268}269/* P = (POUT/2^17)*40kPa + 70kPa */270*pressure += ((float)(data_press) * 40 / 131072) + 70;271offset += 3;272273data_temp = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);274if (data_temp & 0x080000) {275data_temp |= 0xFFF00000;276}277/* T = (TOUT/2^18)*65C + 25C */278*temperature += ((float)(data_temp) * 65 / 262144) + 25;279offset += 3;280}281282*pressure = *pressure * 1000 / fifo_packets;283*temperature = *temperature / fifo_packets;284return true;285}286}287288return false;289}290291bool AP_Baro_ICP201XX::boot_sequence()292{293uint8_t reg_value = 0;294uint8_t offset = 0, gain = 0, Hfosc = 0;295uint8_t version = 0;296uint8_t bootup_status = 0;297int ret = 1;298299/* read version register */300if (!read_reg(REG_VERSION, &version)) {301return false;302}303304if (version == 0xB2) {305/* B2 version Asic is detected. Boot up sequence is not required for B2 Asic, so returning */306return true;307}308309/* Read boot up status and avoid re running boot up sequence if it is already done */310if (!read_reg(REG_OTP_MTP_OTP_STATUS2, &bootup_status)) {311return false;312}313314if (bootup_status & 0x01) {315/* Boot up sequence is already done, not required to repeat boot up sequence */316return true;317}318319/* Bring the ASIC in power mode to activate the OTP power domain and get access to the main registers */320mode_select(0x04);321hal.scheduler->delay(4);322323/* Unlock the main registers */324write_reg(REG_MASTER_LOCK, 0x1F);325326/* Enable the OTP and the write switch */327read_reg(REG_OTP_MTP_OTP_CFG1, ®_value);328reg_value |= 0x03;329write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);330hal.scheduler->delay_microseconds(10);331332/* Toggle the OTP reset pin */333read_reg(REG_OTP_DEBUG2, ®_value);334reg_value |= 1 << 7;335write_reg(REG_OTP_DEBUG2, reg_value);336hal.scheduler->delay_microseconds(10);337338read_reg(REG_OTP_DEBUG2, ®_value);339reg_value &= ~(1 << 7);340write_reg(REG_OTP_DEBUG2, reg_value);341hal.scheduler->delay_microseconds(10);342343/* Program redundant read */344write_reg(REG_OTP_MTP_MRA_LSB, 0x04);345write_reg(REG_OTP_MTP_MRA_MSB, 0x04);346write_reg(REG_OTP_MTP_MRB_LSB, 0x21);347write_reg(REG_OTP_MTP_MRB_MSB, 0x20);348write_reg(REG_OTP_MTP_MR_LSB, 0x10);349write_reg(REG_OTP_MTP_MR_MSB, 0x80);350351/* Read the data from register */352ret &= read_otp_data(0xF8, 0x10, &offset);353ret &= read_otp_data(0xF9, 0x10, &gain);354ret &= read_otp_data(0xFA, 0x10, &Hfosc);355hal.scheduler->delay_microseconds(10);356357/* Write OTP values to main registers */358ret &= read_reg(REG_TRIM1_MSB, ®_value);359if (ret) {360reg_value = (reg_value & (~0x3F)) | (offset & 0x3F);361ret &= write_reg(REG_TRIM1_MSB, reg_value);362}363364ret &= read_reg(REG_TRIM2_MSB, ®_value);365if (ret) {366reg_value = (reg_value & (~0x70)) | ((gain & 0x07) << 4);367ret &= write_reg(REG_TRIM2_MSB, reg_value);368}369370ret &= read_reg(REG_TRIM2_LSB, ®_value);371if (ret) {372reg_value = (reg_value & (~0x7F)) | (Hfosc & 0x7F);373ret &= write_reg(REG_TRIM2_LSB, reg_value);374}375376hal.scheduler->delay_microseconds(10);377378/* Update boot up status to 1 */379if (ret) {380ret &= read_reg(REG_OTP_MTP_OTP_STATUS2, ®_value);381if (!ret) {382reg_value |= 0x01;383ret &= write_reg(REG_OTP_MTP_OTP_STATUS2, reg_value);384}385}386387/* Disable OTP and write switch */388read_reg(REG_OTP_MTP_OTP_CFG1, ®_value);389reg_value &= ~0x03;390write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);391392/* Lock the main register */393write_reg(REG_MASTER_LOCK, 0x00);394395/* Move to standby */396mode_select(0x00);397398return ret;399}400401bool AP_Baro_ICP201XX::configure()402{403uint8_t reg_value = 0;404405/* Initiate Triggered Operation: Stay in Standby mode */406reg_value |= (reg_value & (~0x10)) | ((uint8_t)_forced_meas_trigger << 4);407408/* Power Mode Selection: Normal Mode */409reg_value |= (reg_value & (~0x04)) | ((uint8_t)_power_mode << 2);410411/* FIFO Readout Mode Selection: Pressure first. */412reg_value |= (reg_value & (~0x03)) | ((uint8_t)(_fifo_readout_mode));413414/* Measurement Configuration: Mode2*/415reg_value |= (reg_value & (~0xE0)) | (((uint8_t)_op_mode) << 5);416417/* Measurement Mode Selection: Continuous Measurements (duty cycled) */418reg_value |= (reg_value & (~0x08)) | ((uint8_t)_meas_mode << 3);419420return mode_select(reg_value);421}422423void AP_Baro_ICP201XX::wait_read()424{425/*426* If FIR filter is enabled, it will cause a settling effect on the first 14 pressure values.427* Therefore the first 14 pressure output values are discarded.428**/429uint8_t fifo_packets = 0;430uint8_t fifo_packets_to_skip = 14;431432do {433hal.scheduler->delay(10);434read_reg(REG_FIFO_FILL, &fifo_packets);435fifo_packets = (uint8_t)(fifo_packets & 0x1F);436} while (fifo_packets >= fifo_packets_to_skip);437438flush_fifo();439fifo_packets = 0;440441do {442hal.scheduler->delay(10);443read_reg(REG_FIFO_FILL, &fifo_packets);444fifo_packets = (uint8_t)(fifo_packets & 0x1F);445} while (fifo_packets == 0);446}447448bool AP_Baro_ICP201XX::flush_fifo()449{450uint8_t reg_value;451452if (!read_reg(REG_FIFO_FILL, ®_value)) {453return false;454}455456reg_value |= 0x80;457458if (!write_reg(REG_FIFO_FILL, reg_value)) {459return false;460}461462return true;463}464465void AP_Baro_ICP201XX::timer()466{467float p = 0;468float t = 0;469470if (get_sensor_data(&p, &t)) {471WITH_SEMAPHORE(_sem);472473accum.psum += p;474accum.tsum += t;475accum.count++;476last_measure_us = AP_HAL::micros();477} else {478if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {479flush_fifo();480last_measure_us = AP_HAL::micros();481}482}483}484485void AP_Baro_ICP201XX::update()486{487WITH_SEMAPHORE(_sem);488489if (accum.count > 0) {490_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);491accum.psum = accum.tsum = 0;492accum.count = 0;493}494}495496#endif // AP_BARO_ICP201XX_ENABLED497498499