Path: blob/master/libraries/AP_Baro/AP_Baro_ICP201XX.cpp
9685 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.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/Device.h>1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>22#include <AP_Math/AP_Math.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#define ICP201XX_ID 0x633536#define CONVERSION_INTERVAL 250003738#define REG_EMPTY 0x0039#define REG_TRIM1_MSB 0x0540#define REG_TRIM2_LSB 0x0641#define REG_TRIM2_MSB 0x0742#define REG_DEVICE_ID 0x0C43#define REG_OTP_MTP_OTP_CFG1 0xAC44#define REG_OTP_MTP_MR_LSB 0xAD45#define REG_OTP_MTP_MR_MSB 0xAE46#define REG_OTP_MTP_MRA_LSB 0xAF47#define REG_OTP_MTP_MRA_MSB 0xB048#define REG_OTP_MTP_MRB_LSB 0xB149#define REG_OTP_MTP_MRB_MSB 0xB250#define REG_OTP_MTP_OTP_ADDR 0xB551#define REG_OTP_MTP_OTP_CMD 0xB652#define REG_OTP_MTP_RD_DATA 0xB853#define REG_OTP_MTP_OTP_STATUS 0xB954#define REG_OTP_DEBUG2 0xBC55#define REG_MASTER_LOCK 0xBE56#define REG_OTP_MTP_OTP_STATUS2 0xBF57#define REG_MODE_SELECT 0xC058#define REG_INTERRUPT_STATUS 0xC159#define REG_INTERRUPT_MASK 0xC260#define REG_FIFO_CONFIG 0xC361#define REG_FIFO_FILL 0xC462#define REG_SPI_MODE 0xC563#define REG_PRESS_ABS_LSB 0xC764#define REG_PRESS_ABS_MSB 0xC865#define REG_PRESS_DELTA_LSB 0xC966#define REG_PRESS_DELTA_MSB 0xCA67#define REG_DEVICE_STATUS 0xCD68#define REG_I3C_INFO 0xCE69#define REG_VERSION 0xD370#define REG_FIFO_BASE 0xFA7172/*73constructor74*/75AP_Baro_ICP201XX::AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::Device &_dev)76: AP_Baro_Backend(baro)77, dev(&_dev)78{79}8081AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro, AP_HAL::Device &dev)82{83AP_Baro_ICP201XX *sensor = NEW_NOTHROW AP_Baro_ICP201XX(baro, dev);84if (!sensor || !sensor->init()) {85delete sensor;86return nullptr;87}88return sensor;89}9091bool AP_Baro_ICP201XX::init()92{93if (!dev) {94return false;95}9697dev->get_semaphore()->take_blocking();9899uint8_t id = 0xFF;100uint8_t ver = 0xFF;101read_reg(REG_DEVICE_ID, &id);102read_reg(REG_DEVICE_ID, &id);103read_reg(REG_VERSION, &ver);104105if (id != ICP201XX_ID) {106goto failed;107}108109if (ver != 0x00 && ver != 0xB2) {110goto failed;111}112113hal.scheduler->delay(10);114115soft_reset();116117if (!boot_sequence()) {118goto failed;119}120121if (!configure()) {122goto failed;123}124125wait_read();126127dev->set_retries(0);128129instance = _frontend.register_sensor();130131dev->set_device_type(DEVTYPE_BARO_ICP201XX);132set_bus_id(instance, dev->get_bus_id());133134dev->get_semaphore()->give();135136dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP201XX::timer, void));137return true;138139failed:140dev->get_semaphore()->give();141return false;142}143144145void AP_Baro_ICP201XX::dummy_reg()146{147do {148uint8_t reg = REG_EMPTY;149uint8_t val = 0;150dev->transfer(®, 1, &val, 1);151} while (0);152}153154bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *buf, uint8_t len)155{156bool ret;157ret = dev->transfer(®, 1, buf, len);158dummy_reg();159return ret;160}161162bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *val)163{164return read_reg(reg, val, 1);165}166167bool AP_Baro_ICP201XX::write_reg(uint8_t reg, uint8_t val)168{169bool ret;170uint8_t data[2] = { reg, val };171ret = dev->transfer(data, sizeof(data), nullptr, 0);172dummy_reg();173return ret;174}175176void AP_Baro_ICP201XX::soft_reset()177{178/* Stop the measurement */179mode_select(0x00);180181hal.scheduler->delay(2);182183/* Flush FIFO */184flush_fifo();185186/* Mask all interrupts */187write_reg(REG_FIFO_CONFIG, 0x00);188write_reg(REG_INTERRUPT_MASK, 0xFF);189}190191bool AP_Baro_ICP201XX::mode_select(uint8_t mode)192{193uint8_t mode_sync_status = 0;194195do {196read_reg(REG_DEVICE_STATUS, &mode_sync_status, 1);197198if (mode_sync_status & 0x01) {199break;200}201202hal.scheduler->delay(1);203} while (1);204205return write_reg(REG_MODE_SELECT, mode);206}207208bool AP_Baro_ICP201XX::read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val)209{210uint8_t otp_status = 0xFF;211212/* Write the address content and read command */213if (!write_reg(REG_OTP_MTP_OTP_ADDR, addr)) {214return false;215}216217if (!write_reg(REG_OTP_MTP_OTP_CMD, cmd)) {218return false;219}220221/* Wait for the OTP read to finish Monitor otp_status */222do {223read_reg(REG_OTP_MTP_OTP_STATUS, &otp_status);224225if (otp_status == 0) {226break;227}228229hal.scheduler->delay_microseconds(1);230} while (1);231232/* Read the data from register */233if (!read_reg(REG_OTP_MTP_RD_DATA, val)) {234return false;235}236237return true;238}239240bool AP_Baro_ICP201XX::get_sensor_data(float *pressure, float *temperature)241{242uint8_t fifo_data[96] {0};243uint8_t fifo_packets = 0;244int32_t data_temp = 0;245int32_t data_press = 0;246*pressure = 0;247*temperature = 0;248249if (read_reg(REG_FIFO_FILL, &fifo_packets)) {250fifo_packets = (uint8_t)(fifo_packets & 0x1F);251if (fifo_packets > 16) {252flush_fifo();253return false;254}255if (fifo_packets > 0 && fifo_packets <= 16 && read_reg(REG_FIFO_BASE, fifo_data, fifo_packets * 2 * 3)) {256uint8_t offset = 0;257258for (uint8_t i = 0; i < fifo_packets; i++) {259data_press = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);260if (data_press & 0x080000) {261data_press |= 0xFFF00000;262}263/* P = (POUT/2^17)*40kPa + 70kPa */264*pressure += ((float)(data_press) * 40 / 131072) + 70;265offset += 3;266267data_temp = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);268if (data_temp & 0x080000) {269data_temp |= 0xFFF00000;270}271/* T = (TOUT/2^18)*65C + 25C */272*temperature += ((float)(data_temp) * 65 / 262144) + 25;273offset += 3;274}275276*pressure = *pressure * 1000 / fifo_packets;277*temperature = *temperature / fifo_packets;278return true;279}280}281282return false;283}284285bool AP_Baro_ICP201XX::boot_sequence()286{287uint8_t reg_value = 0;288uint8_t offset = 0, gain = 0, Hfosc = 0;289uint8_t version = 0;290uint8_t bootup_status = 0;291int ret = 1;292293/* read version register */294if (!read_reg(REG_VERSION, &version)) {295return false;296}297298if (version == 0xB2) {299/* B2 version Asic is detected. Boot up sequence is not required for B2 Asic, so returning */300return true;301}302303/* Read boot up status and avoid re running boot up sequence if it is already done */304if (!read_reg(REG_OTP_MTP_OTP_STATUS2, &bootup_status)) {305return false;306}307308if (bootup_status & 0x01) {309/* Boot up sequence is already done, not required to repeat boot up sequence */310return true;311}312313/* Bring the ASIC in power mode to activate the OTP power domain and get access to the main registers */314mode_select(0x04);315hal.scheduler->delay(4);316317/* Unlock the main registers */318write_reg(REG_MASTER_LOCK, 0x1F);319320/* Enable the OTP and the write switch */321read_reg(REG_OTP_MTP_OTP_CFG1, ®_value);322reg_value |= 0x03;323write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);324hal.scheduler->delay_microseconds(10);325326/* Toggle the OTP reset pin */327read_reg(REG_OTP_DEBUG2, ®_value);328reg_value |= 1 << 7;329write_reg(REG_OTP_DEBUG2, reg_value);330hal.scheduler->delay_microseconds(10);331332read_reg(REG_OTP_DEBUG2, ®_value);333reg_value &= ~(1 << 7);334write_reg(REG_OTP_DEBUG2, reg_value);335hal.scheduler->delay_microseconds(10);336337/* Program redundant read */338write_reg(REG_OTP_MTP_MRA_LSB, 0x04);339write_reg(REG_OTP_MTP_MRA_MSB, 0x04);340write_reg(REG_OTP_MTP_MRB_LSB, 0x21);341write_reg(REG_OTP_MTP_MRB_MSB, 0x20);342write_reg(REG_OTP_MTP_MR_LSB, 0x10);343write_reg(REG_OTP_MTP_MR_MSB, 0x80);344345/* Read the data from register */346ret &= read_otp_data(0xF8, 0x10, &offset);347ret &= read_otp_data(0xF9, 0x10, &gain);348ret &= read_otp_data(0xFA, 0x10, &Hfosc);349hal.scheduler->delay_microseconds(10);350351/* Write OTP values to main registers */352ret &= read_reg(REG_TRIM1_MSB, ®_value);353if (ret) {354reg_value = (reg_value & (~0x3F)) | (offset & 0x3F);355ret &= write_reg(REG_TRIM1_MSB, reg_value);356}357358ret &= read_reg(REG_TRIM2_MSB, ®_value);359if (ret) {360reg_value = (reg_value & (~0x70)) | ((gain & 0x07) << 4);361ret &= write_reg(REG_TRIM2_MSB, reg_value);362}363364ret &= read_reg(REG_TRIM2_LSB, ®_value);365if (ret) {366reg_value = (reg_value & (~0x7F)) | (Hfosc & 0x7F);367ret &= write_reg(REG_TRIM2_LSB, reg_value);368}369370hal.scheduler->delay_microseconds(10);371372/* Update boot up status to 1 */373if (ret) {374ret &= read_reg(REG_OTP_MTP_OTP_STATUS2, ®_value);375if (!ret) {376reg_value |= 0x01;377ret &= write_reg(REG_OTP_MTP_OTP_STATUS2, reg_value);378}379}380381/* Disable OTP and write switch */382read_reg(REG_OTP_MTP_OTP_CFG1, ®_value);383reg_value &= ~0x03;384write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);385386/* Lock the main register */387write_reg(REG_MASTER_LOCK, 0x00);388389/* Move to standby */390mode_select(0x00);391392return ret;393}394395bool AP_Baro_ICP201XX::configure()396{397uint8_t reg_value = 0;398399/* Initiate Triggered Operation: Stay in Standby mode */400reg_value |= (reg_value & (~0x10)) | ((uint8_t)_forced_meas_trigger << 4);401402/* Power Mode Selection: Normal Mode */403reg_value |= (reg_value & (~0x04)) | ((uint8_t)_power_mode << 2);404405/* FIFO Readout Mode Selection: Pressure first. */406reg_value |= (reg_value & (~0x03)) | ((uint8_t)(_fifo_readout_mode));407408/* Measurement Configuration: Mode2*/409reg_value |= (reg_value & (~0xE0)) | (((uint8_t)_op_mode) << 5);410411/* Measurement Mode Selection: Continuous Measurements (duty cycled) */412reg_value |= (reg_value & (~0x08)) | ((uint8_t)_meas_mode << 3);413414return mode_select(reg_value);415}416417void AP_Baro_ICP201XX::wait_read()418{419/*420* If FIR filter is enabled, it will cause a settling effect on the first 14 pressure values.421* Therefore the first 14 pressure output values are discarded.422**/423uint8_t fifo_packets = 0;424uint8_t fifo_packets_to_skip = 14;425426do {427hal.scheduler->delay(10);428read_reg(REG_FIFO_FILL, &fifo_packets);429fifo_packets = (uint8_t)(fifo_packets & 0x1F);430} while (fifo_packets >= fifo_packets_to_skip);431432flush_fifo();433fifo_packets = 0;434435do {436hal.scheduler->delay(10);437read_reg(REG_FIFO_FILL, &fifo_packets);438fifo_packets = (uint8_t)(fifo_packets & 0x1F);439} while (fifo_packets == 0);440}441442bool AP_Baro_ICP201XX::flush_fifo()443{444uint8_t reg_value;445446if (!read_reg(REG_FIFO_FILL, ®_value)) {447return false;448}449450reg_value |= 0x80;451452if (!write_reg(REG_FIFO_FILL, reg_value)) {453return false;454}455456return true;457}458459void AP_Baro_ICP201XX::timer()460{461float p = 0;462float t = 0;463464if (get_sensor_data(&p, &t)) {465WITH_SEMAPHORE(_sem);466467accum.psum += p;468accum.tsum += t;469accum.count++;470last_measure_us = AP_HAL::micros();471} else {472if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {473flush_fifo();474last_measure_us = AP_HAL::micros();475}476}477}478479void AP_Baro_ICP201XX::update()480{481WITH_SEMAPHORE(_sem);482483if (accum.count > 0) {484_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);485accum.psum = accum.tsum = 0;486accum.count = 0;487}488}489490#endif // AP_BARO_ICP201XX_ENABLED491492493