Path: blob/master/libraries/AP_Baro/AP_Baro_ICP101XX.cpp
9660 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_ICP101XX.h"1617#if AP_BARO_ICP101XX_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <AP_HAL/Device.h>2122#include <AP_Common/AP_Common.h>23#include <AP_HAL/AP_HAL.h>24#include <AP_Math/AP_Math.h>25#include <AP_BoardConfig/AP_BoardConfig.h>2627#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 ICP101XX_ID 0x0837#define CMD_READ_ID 0xefc838#define CMD_SET_ADDR 0xc59539#define CMD_READ_OTP 0xc7f740#define CMD_MEAS_LP 0x609c41#define CMD_MEAS_N 0x682542#define CMD_MEAS_LN 0x70df43#define CMD_MEAS_ULN 0x786644#define CMD_SOFT_RESET 0x805d4546/*47constructor48*/49AP_Baro_ICP101XX::AP_Baro_ICP101XX(AP_Baro &baro, AP_HAL::Device &_dev)50: AP_Baro_Backend(baro)51, dev(&_dev)52{53}5455AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro, AP_HAL::Device &dev)56{57AP_Baro_ICP101XX *sensor = NEW_NOTHROW AP_Baro_ICP101XX(baro, dev);58if (!sensor || !sensor->init()) {59delete sensor;60return nullptr;61}62return sensor;63}6465bool AP_Baro_ICP101XX::init()66{67if (!dev) {68return false;69}7071dev->get_semaphore()->take_blocking();7273uint16_t id = 0;74read_response(CMD_READ_ID, (uint8_t *)&id, 2);75uint8_t whoami = (id >> 8) & 0x3f; // Product ID Bits 5:076if (whoami != ICP101XX_ID) {77goto failed;78}7980if (!send_command(CMD_SOFT_RESET)) {81goto failed;82}8384// wait for sensor to settle85hal.scheduler->delay(10);8687if (!read_calibration_data()) {88goto failed;89}9091// start a reading92if (!start_measure(CMD_MEAS_ULN)) {93goto failed;94}9596dev->set_retries(0);9798instance = _frontend.register_sensor();99100dev->set_device_type(DEVTYPE_BARO_ICP101XX);101set_bus_id(instance, dev->get_bus_id());102103dev->get_semaphore()->give();104105dev->register_periodic_callback(measure_interval, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void));106107return true;108109failed:110dev->get_semaphore()->give();111return false;112}113114bool AP_Baro_ICP101XX::read_measure_results(uint8_t *buf, uint8_t len)115{116return dev->transfer(nullptr, 0, buf, len);117}118119bool AP_Baro_ICP101XX::read_response(uint16_t cmd, uint8_t *buf, uint8_t len)120{121uint8_t buff[2];122buff[0] = (cmd >> 8) & 0xff;123buff[1] = cmd & 0xff;124return dev->transfer(&buff[0], 2, buf, len);125}126127bool AP_Baro_ICP101XX::send_command(uint16_t cmd)128{129uint8_t buf[2];130buf[0] = (cmd >> 8) & 0xff;131buf[1] = cmd & 0xff;132return dev->transfer(buf, sizeof(buf), nullptr, 0);133}134135bool AP_Baro_ICP101XX::send_command(uint16_t cmd, uint8_t *data, uint8_t len)136{137uint8_t buf[5];138buf[0] = (cmd >> 8) & 0xff;139buf[1] = cmd & 0xff;140memcpy(&buf[2], data, len);141return dev->transfer(&buf[0], len + 2, nullptr, 0);142}143144int8_t AP_Baro_ICP101XX::cal_crc(uint8_t seed, uint8_t data)145{146int8_t poly = 0x31;147int8_t var2;148uint8_t i;149150for (i = 0; i < 8; i++) {151if ((seed & 0x80) ^ (data & 0x80)) {152var2 = 1;153154} else {155var2 = 0;156}157158seed = (seed & 0x7F) << 1;159data = (data & 0x7F) << 1;160seed = seed ^ (uint8_t)(poly * var2);161}162163return (int8_t)seed;164}165166bool AP_Baro_ICP101XX::read_calibration_data(void)167{168// setup for OTP read169uint8_t cmd[3] = { 0x00, 0x66, 0x9c };170if (!send_command(CMD_SET_ADDR, cmd, 3)) {171return false;172}173for (uint8_t i = 0; i < 4; i++) {174uint8_t d[3];175uint8_t crc = 0xff;176read_response(CMD_READ_OTP, d, 3);177for (int j = 0; j < 2; j++) {178crc = (uint8_t)cal_crc(crc, d[j]);179}180if (crc != d[2]) {181return false;182}183sensor_constants[i] = (d[0] << 8) | d[1];184}185return true;186}187188bool AP_Baro_ICP101XX::start_measure(uint16_t mode)189{190/*191From ds-000186-icp-101xx-v1.0.pdf, page 6, table 1192193Sensor Measurement Max Time194Mode Time (Forced)195Low Power (LP) 1.6 ms 1.8 ms196Normal (N) 5.6 ms 6.3 ms197Low Noise (LN) 20.8 ms 23.8 ms198Ultra Low Noise(ULN) 83.2 ms 94.5 ms199*/200201switch (mode) {202case CMD_MEAS_LP:203measure_interval = 2000;204break;205206case CMD_MEAS_LN:207measure_interval = 24000;208break;209210case CMD_MEAS_ULN:211measure_interval = 95000;212break;213214case CMD_MEAS_N:215default:216measure_interval = 7000;217break;218}219220if (!send_command(mode)) {221return false;222}223224return true;225}226227void AP_Baro_ICP101XX::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],228float &A, float &B, float &C)229{230C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +231p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +232p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /233(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +234p_LUT[0] * (p_Pa[1] - p_Pa[2]) +235p_LUT[1] * (p_Pa[2] - p_Pa[0]));236A = (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]);237B = (p_Pa[0] - A) * (p_LUT[0] + C);238}239240/*241Convert an output from a calibrated sensor to a pressure in Pa.242Arguments:243p_LSB -- Raw pressure data from sensor244T_LSB -- Raw temperature data from sensor245*/246float AP_Baro_ICP101XX::get_pressure(uint32_t p_LSB, uint32_t T_LSB)247{248float t = T_LSB - 32768.0;249float s[3];250s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;251s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;252s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;253float A, B, C;254calculate_conversion_constants(p_Pa_calib, s, A, B, C);255return A + B / (C + p_LSB);256}257258void AP_Baro_ICP101XX::convert_data(uint32_t Praw, uint32_t Traw)259{260// temperature is easy261float T = -45 + (175.0f / (1U<<16)) * Traw;262263// pressure involves a few more calculations264float P = get_pressure(Praw, Traw);265266if (!pressure_ok(P)) {267return;268}269270WITH_SEMAPHORE(_sem);271272accum.psum += P;273accum.tsum += T;274accum.count++;275}276277void AP_Baro_ICP101XX::timer(void)278{279uint8_t d[9] {};280if (read_measure_results(d, 9)) {281// ignore CRC bytes for now282uint32_t Traw = (uint32_t(d[0]) << 8) | d[1];283uint32_t Praw = (uint32_t(d[3]) << 16) | (uint32_t(d[4]) << 8) | d[6];284285convert_data(Praw, Traw);286start_measure(CMD_MEAS_ULN);287last_measure_us = AP_HAL::micros();288} else {289if (AP_HAL::micros() - last_measure_us > measure_interval*3) {290// lost a sample291start_measure(CMD_MEAS_ULN);292last_measure_us = AP_HAL::micros();293}294}295}296297void AP_Baro_ICP101XX::update()298{299WITH_SEMAPHORE(_sem);300301if (accum.count > 0) {302_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);303accum.psum = accum.tsum = 0;304accum.count = 0;305}306}307308#endif // AP_BARO_ICP101XX_ENABLED309310311