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_DPS280.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*/14/*15DPS280 barometer driver16*/1718#include "AP_Baro_DPS280.h"1920#if AP_BARO_DPS280_ENABLED2122#include <utility>23#include <stdio.h>24#include <AP_Math/definitions.h>2526extern const AP_HAL::HAL &hal;2728#define DPS280_REG_PRESS 0x0029#define DPS280_REG_TEMP 0x0330#define DPS280_REG_PCONF 0x0631#define DPS280_REG_TCONF 0x0732#define DPS280_REG_MCONF 0x0833#define DPS280_REG_CREG 0x0934#define DPS280_REG_ISTS 0x0A35#define DPS280_REG_FSTS 0x0B36#define DPS280_REG_RESET 0x0C37#define DPS280_REG_PID 0x0D38#define DPS280_REG_COEF 0x1039#define DPS280_REG_CSRC 0x284041#define DPS280_WHOAMI 0x104243#define TEMPERATURE_LIMIT_C 1204445AP_Baro_DPS280::AP_Baro_DPS280(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev)46: AP_Baro_Backend(baro)47, dev(std::move(_dev))48{49}5051AP_Baro_Backend *AP_Baro_DPS280::probe(AP_Baro &baro,52AP_HAL::OwnPtr<AP_HAL::Device> _dev, bool _is_dps310)53{54if (!_dev) {55return nullptr;56}5758AP_Baro_DPS280 *sensor = NEW_NOTHROW AP_Baro_DPS280(baro, std::move(_dev));59if (sensor) {60sensor->is_dps310 = _is_dps310;61}62if (!sensor || !sensor->init(_is_dps310)) {63delete sensor;64return nullptr;65}66return sensor;67}6869AP_Baro_Backend *AP_Baro_DPS310::probe(AP_Baro &baro,70AP_HAL::OwnPtr<AP_HAL::Device> _dev)71{72// same as DPS280 but with is_dps310 set for temperature fix73return AP_Baro_DPS280::probe(baro, std::move(_dev), true);74}7576/*77handle bit width for 16 bit config registers78*/79void AP_Baro_DPS280::fix_config_bits16(int16_t &v, uint8_t bits) const80{81if (v > int16_t((1U<<(bits-1))-1)) {82v = v - (1U<<bits);83}84}8586/*87handle bit width for 32 bit config registers88*/89void AP_Baro_DPS280::fix_config_bits32(int32_t &v, uint8_t bits) const90{91if (v > int32_t((1U<<(bits-1))-1)) {92v = v - (1U<<bits);93}94}9596/*97read calibration data98*/99bool AP_Baro_DPS280::read_calibration(void)100{101uint8_t buf[18];102103if (!dev->read_registers(DPS280_REG_COEF, buf, 18)) {104return false;105}106107calibration.C0 = (buf[0] << 4) + ((buf[1] >>4) & 0x0F);108calibration.C1 = (buf[2] + ((buf[1] & 0x0F)<<8));109calibration.C00 = ((buf[4]<<4) + (buf[3]<<12)) + ((buf[5]>>4) & 0x0F);110calibration.C10 = ((buf[5] & 0x0F)<<16) + buf[7] + (buf[6]<<8);111calibration.C01 = (buf[9] + (buf[8]<<8));112calibration.C11 = (buf[11] + (buf[10]<<8));113calibration.C20 = (buf[13] + (buf[12]<<8));114calibration.C21 = (buf[15] + (buf[14]<<8));115calibration.C30 = (buf[17] + (buf[16]<<8));116117fix_config_bits16(calibration.C0, 12);118fix_config_bits16(calibration.C1, 12);119fix_config_bits32(calibration.C00, 20);120fix_config_bits32(calibration.C10, 20);121fix_config_bits16(calibration.C01, 16);122fix_config_bits16(calibration.C11, 16);123fix_config_bits16(calibration.C20, 16);124fix_config_bits16(calibration.C21, 16);125fix_config_bits16(calibration.C30, 16);126127/* get calibration source */128if (!dev->read_registers(DPS280_REG_CSRC, &calibration.temp_source, 1)) {129return false;130}131calibration.temp_source &= 0x80;132133return true;134}135136void AP_Baro_DPS280::set_config_registers(void)137{138dev->write_register(DPS280_REG_CREG, 0x0C, true); // shift for 16x oversampling139dev->write_register(DPS280_REG_PCONF, 0x54, true); // 32 Hz, 16x oversample140dev->write_register(DPS280_REG_TCONF, 0x54 | calibration.temp_source, true); // 32 Hz, 16x oversample141dev->write_register(DPS280_REG_MCONF, 0x07); // continuous temp and pressure.142143if (is_dps310) {144// work around broken temperature handling on some sensors145// using undocumented register writes146// see https://github.com/infineon/DPS310-Pressure-Sensor/blob/dps310/src/DpsClass.cpp#L442147dev->write_register(0x0E, 0xA5);148dev->write_register(0x0F, 0x96);149dev->write_register(0x62, 0x02);150dev->write_register(0x0E, 0x00);151dev->write_register(0x0F, 0x00);152}153}154155bool AP_Baro_DPS280::init(bool _is_dps310)156{157if (!dev) {158return false;159}160dev->get_semaphore()->take_blocking();161162// setup to allow reads on SPI163if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {164dev->set_read_flag(0x80);165}166167dev->set_speed(AP_HAL::Device::SPEED_HIGH);168169// the DPS310 can get into a state on boot where the whoami is not170// read correctly at startup. Toggling the CS line gets its out of171// this state172dev->set_chip_select(true);173dev->set_chip_select(false);174175uint8_t whoami=0;176if (!dev->read_registers(DPS280_REG_PID, &whoami, 1) ||177whoami != DPS280_WHOAMI) {178dev->get_semaphore()->give();179return false;180}181182if (!read_calibration()) {183dev->get_semaphore()->give();184return false;185}186187dev->setup_checked_registers(4, 20);188189set_config_registers();190191instance = _frontend.register_sensor();192if(_is_dps310) {193dev->set_device_type(DEVTYPE_BARO_DPS310);194} else {195dev->set_device_type(DEVTYPE_BARO_DPS280);196}197set_bus_id(instance, dev->get_bus_id());198199dev->get_semaphore()->give();200201// request 64Hz update. New data will be available at 32Hz202dev->register_periodic_callback((1000 / 64) * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_DPS280::timer, void));203204return true;205}206207/*208calculate corrected pressure and temperature209*/210void AP_Baro_DPS280::calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature)211{212const struct dps280_cal &cal = calibration;213// scaling for 16x oversampling214const float scaling_16 = 1.0f/253952;215216float temp_scaled;217float press_scaled;218219temp_scaled = float(UT) * scaling_16;220temperature = cal.C0 * 0.5f + cal.C1 * temp_scaled;221222press_scaled = float(UP) * scaling_16;223224pressure = cal.C00;225pressure += press_scaled * (cal.C10 + press_scaled * (cal.C20 + press_scaled * cal.C30));226pressure += temp_scaled * cal.C01;227pressure += temp_scaled * press_scaled * (cal.C11 + press_scaled * cal.C21);228}229230/*231check health and possibly reset232*/233void AP_Baro_DPS280::check_health(void)234{235dev->check_next_register();236237if (fabsf(last_temperature) > TEMPERATURE_LIMIT_C) {238err_count++;239}240if (err_count > 16) {241err_count = 0;242dev->write_register(DPS280_REG_RESET, 0x09);243set_config_registers();244pending_reset = true;245}246}247248// accumulate a new sensor reading249void AP_Baro_DPS280::timer(void)250{251uint8_t buf[6];252uint8_t ready;253254if (pending_reset) {255// reset registers after software reset from check_health()256pending_reset = false;257set_config_registers();258return;259}260261if (!dev->read_registers(DPS280_REG_MCONF, &ready, 1) ||262!(ready & (1U<<4)) ||263!dev->read_registers(DPS280_REG_PRESS, buf, 3) ||264!dev->read_registers(DPS280_REG_TEMP, &buf[3], 3)) {265// data not ready266err_count++;267check_health();268return;269}270271int32_t press = (buf[2]) + (buf[1]<<8) + (buf[0]<<16);272int32_t temp = (buf[5]) + (buf[4]<<8) + (buf[3]<<16);273fix_config_bits32(press, 24);274fix_config_bits32(temp, 24);275276float pressure, temperature;277278calculate_PT(temp, press, pressure, temperature);279280last_temperature = temperature;281282if (!pressure_ok(pressure)) {283return;284}285286check_health();287288if (fabsf(last_temperature) <= TEMPERATURE_LIMIT_C) {289err_count = 0;290}291292WITH_SEMAPHORE(_sem);293294pressure_sum += pressure;295temperature_sum += temperature;296count++;297}298299// transfer data to the frontend300void AP_Baro_DPS280::update(void)301{302if (count == 0) {303return;304}305306WITH_SEMAPHORE(_sem);307308_copy_to_frontend(instance, pressure_sum/count, temperature_sum/count);309pressure_sum = 0;310temperature_sum = 0;311count=0;312}313314#endif // AP_BARO_DPS280_ENABLED315316317