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_ICP101XX.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_ICP101XX.h"1617#if AP_BARO_ICP101XX_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_HAL/AP_HAL.h>25#include <AP_Math/AP_Math.h>26#include <AP_BoardConfig/AP_BoardConfig.h>2728#include <utility>29#include <stdio.h>3031#include <AP_Math/AP_Math.h>32#include <AP_Logger/AP_Logger.h>3334#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>3536extern const AP_HAL::HAL &hal;3738#define ICP101XX_ID 0x0839#define CMD_READ_ID 0xefc840#define CMD_SET_ADDR 0xc59541#define CMD_READ_OTP 0xc7f742#define CMD_MEAS_LP 0x609c43#define CMD_MEAS_N 0x682544#define CMD_MEAS_LN 0x70df45#define CMD_MEAS_ULN 0x786646#define CMD_SOFT_RESET 0x805d4748/*49constructor50*/51AP_Baro_ICP101XX::AP_Baro_ICP101XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)52: AP_Baro_Backend(baro)53, dev(std::move(_dev))54{55}5657AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro,58AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)59{60if (!dev) {61return nullptr;62}63AP_Baro_ICP101XX *sensor = NEW_NOTHROW AP_Baro_ICP101XX(baro, std::move(dev));64if (!sensor || !sensor->init()) {65delete sensor;66return nullptr;67}68return sensor;69}7071bool AP_Baro_ICP101XX::init()72{73if (!dev) {74return false;75}7677dev->get_semaphore()->take_blocking();7879uint16_t id = 0;80read_response(CMD_READ_ID, (uint8_t *)&id, 2);81uint8_t whoami = (id >> 8) & 0x3f; // Product ID Bits 5:082if (whoami != ICP101XX_ID) {83goto failed;84}8586if (!send_command(CMD_SOFT_RESET)) {87goto failed;88}8990// wait for sensor to settle91hal.scheduler->delay(10);9293if (!read_calibration_data()) {94goto failed;95}9697// start a reading98if (!start_measure(CMD_MEAS_ULN)) {99goto failed;100}101102dev->set_retries(0);103104instance = _frontend.register_sensor();105106dev->set_device_type(DEVTYPE_BARO_ICP101XX);107set_bus_id(instance, dev->get_bus_id());108109dev->get_semaphore()->give();110111dev->register_periodic_callback(measure_interval, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void));112113return true;114115failed:116dev->get_semaphore()->give();117return false;118}119120bool AP_Baro_ICP101XX::read_measure_results(uint8_t *buf, uint8_t len)121{122return dev->transfer(nullptr, 0, buf, len);123}124125bool AP_Baro_ICP101XX::read_response(uint16_t cmd, uint8_t *buf, uint8_t len)126{127uint8_t buff[2];128buff[0] = (cmd >> 8) & 0xff;129buff[1] = cmd & 0xff;130return dev->transfer(&buff[0], 2, buf, len);131}132133bool AP_Baro_ICP101XX::send_command(uint16_t cmd)134{135uint8_t buf[2];136buf[0] = (cmd >> 8) & 0xff;137buf[1] = cmd & 0xff;138return dev->transfer(buf, sizeof(buf), nullptr, 0);139}140141bool AP_Baro_ICP101XX::send_command(uint16_t cmd, uint8_t *data, uint8_t len)142{143uint8_t buf[5];144buf[0] = (cmd >> 8) & 0xff;145buf[1] = cmd & 0xff;146memcpy(&buf[2], data, len);147return dev->transfer(&buf[0], len + 2, nullptr, 0);148}149150int8_t AP_Baro_ICP101XX::cal_crc(uint8_t seed, uint8_t data)151{152int8_t poly = 0x31;153int8_t var2;154uint8_t i;155156for (i = 0; i < 8; i++) {157if ((seed & 0x80) ^ (data & 0x80)) {158var2 = 1;159160} else {161var2 = 0;162}163164seed = (seed & 0x7F) << 1;165data = (data & 0x7F) << 1;166seed = seed ^ (uint8_t)(poly * var2);167}168169return (int8_t)seed;170}171172bool AP_Baro_ICP101XX::read_calibration_data(void)173{174// setup for OTP read175uint8_t cmd[3] = { 0x00, 0x66, 0x9c };176if (!send_command(CMD_SET_ADDR, cmd, 3)) {177return false;178}179for (uint8_t i = 0; i < 4; i++) {180uint8_t d[3];181uint8_t crc = 0xff;182read_response(CMD_READ_OTP, d, 3);183for (int j = 0; j < 2; j++) {184crc = (uint8_t)cal_crc(crc, d[j]);185}186if (crc != d[2]) {187return false;188}189sensor_constants[i] = (d[0] << 8) | d[1];190}191return true;192}193194bool AP_Baro_ICP101XX::start_measure(uint16_t mode)195{196/*197From ds-000186-icp-101xx-v1.0.pdf, page 6, table 1198199Sensor Measurement Max Time200Mode Time (Forced)201Low Power (LP) 1.6 ms 1.8 ms202Normal (N) 5.6 ms 6.3 ms203Low Noise (LN) 20.8 ms 23.8 ms204Ultra Low Noise(ULN) 83.2 ms 94.5 ms205*/206207switch (mode) {208case CMD_MEAS_LP:209measure_interval = 2000;210break;211212case CMD_MEAS_LN:213measure_interval = 24000;214break;215216case CMD_MEAS_ULN:217measure_interval = 95000;218break;219220case CMD_MEAS_N:221default:222measure_interval = 7000;223break;224}225226if (!send_command(mode)) {227return false;228}229230return true;231}232233void AP_Baro_ICP101XX::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],234float &A, float &B, float &C)235{236C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +237p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +238p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /239(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +240p_LUT[0] * (p_Pa[1] - p_Pa[2]) +241p_LUT[1] * (p_Pa[2] - p_Pa[0]));242A = (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]);243B = (p_Pa[0] - A) * (p_LUT[0] + C);244}245246/*247Convert an output from a calibrated sensor to a pressure in Pa.248Arguments:249p_LSB -- Raw pressure data from sensor250T_LSB -- Raw temperature data from sensor251*/252float AP_Baro_ICP101XX::get_pressure(uint32_t p_LSB, uint32_t T_LSB)253{254float t = T_LSB - 32768.0;255float s[3];256s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;257s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;258s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;259float A, B, C;260calculate_conversion_constants(p_Pa_calib, s, A, B, C);261return A + B / (C + p_LSB);262}263264void AP_Baro_ICP101XX::convert_data(uint32_t Praw, uint32_t Traw)265{266// temperature is easy267float T = -45 + (175.0f / (1U<<16)) * Traw;268269// pressure involves a few more calculations270float P = get_pressure(Praw, Traw);271272if (!pressure_ok(P)) {273return;274}275276WITH_SEMAPHORE(_sem);277278accum.psum += P;279accum.tsum += T;280accum.count++;281}282283void AP_Baro_ICP101XX::timer(void)284{285uint8_t d[9] {};286if (read_measure_results(d, 9)) {287// ignore CRC bytes for now288uint32_t Traw = (uint32_t(d[0]) << 8) | d[1];289uint32_t Praw = (uint32_t(d[3]) << 16) | (uint32_t(d[4]) << 8) | d[6];290291convert_data(Praw, Traw);292start_measure(CMD_MEAS_ULN);293last_measure_us = AP_HAL::micros();294} else {295if (AP_HAL::micros() - last_measure_us > measure_interval*3) {296// lost a sample297start_measure(CMD_MEAS_ULN);298last_measure_us = AP_HAL::micros();299}300}301}302303void AP_Baro_ICP101XX::update()304{305WITH_SEMAPHORE(_sem);306307if (accum.count > 0) {308_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);309accum.psum = accum.tsum = 0;310accum.count = 0;311}312}313314#endif // AP_BARO_ICP101XX_ENABLED315316317