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_KellerLD.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_KellerLD.h"1617#if AP_BARO_KELLERLD_ENABLED1819#include <utility>20#include <stdio.h>2122#include <AP_Math/AP_Math.h>2324#define KELLER_DEBUG 02526#if KELLER_DEBUG27# define Debug(fmt, args ...) do {printf(fmt "\n", ## args);} while(0)28#else29# define Debug(fmt, args ...)30#endif3132extern const AP_HAL::HAL &hal;3334// sensor metadata register35static const uint8_t CMD_METADATA_PMODE = 0x12;36// Measurement range registers37static const uint8_t CMD_PRANGE_MIN_MSB = 0x13;38static const uint8_t CMD_PRANGE_MIN_LSB = 0x14;39static const uint8_t CMD_PRANGE_MAX_MSB = 0x15;40static const uint8_t CMD_PRANGE_MAX_LSB = 0x16;4142// write to this address to start pressure measurement43static const uint8_t CMD_REQUEST_MEASUREMENT = 0xAC;4445AP_Baro_KellerLD::AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)46: AP_Baro_Backend(baro)47, _dev(std::move(dev))48{49}5051// Look for the device on the bus and see if it responds appropriately52AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)53{54if (!dev) {55return nullptr;56}57AP_Baro_KellerLD *sensor = NEW_NOTHROW AP_Baro_KellerLD(baro, std::move(dev));58if (!sensor || !sensor->_init()) {59delete sensor;60return nullptr;61}62return sensor;63}646566// convenience function to work around device transfer oddities67bool AP_Baro_KellerLD::transfer_with_delays(uint8_t *send, uint8_t sendlen, uint8_t *recv, uint8_t recvlen)68{69if (!_dev->transfer(send, sendlen, nullptr, 0)) {70return false;71}72hal.scheduler->delay(1);7374if(!_dev->transfer(nullptr, 0, recv, recvlen)) {75return false;76}77hal.scheduler->delay(1);78return true;79}8081// This device has some undocumented finicky quirks and requires82// delays when reading out the measurement range, but for some reason83// this isn't an issue when requesting measurements. This is why we84// need to split the transfers with delays like this. (Using85// AP_HAL::I2CDevice::set_split_transfers will not work with these86// sensors)87bool AP_Baro_KellerLD::read_measurement_limit(float *limit, uint8_t msb_addr, uint8_t lsb_addr)88{89uint8_t data[3];9091if (!transfer_with_delays(&msb_addr, 1, data, ARRAY_SIZE(data))) {92return false;93}9495const uint16_t ms_word = (data[1] << 8) | data[2];96Debug("0x%02x: %d [%d, %d, %d]", msb_addr, ms_word, data[0], data[1], data[2]);9798if (!transfer_with_delays(&lsb_addr, 1, data, ARRAY_SIZE(data))) {99return false;100}101102const uint16_t ls_word = (data[1] << 8) | data[2];103Debug("0x%02x: %d [%d, %d, %d]", lsb_addr, ls_word, data[0], data[1], data[2]);104105const uint32_t cal_data = (ms_word << 16) | ls_word;106memcpy(limit, &cal_data, sizeof(*limit));107108if (isinf(*limit) || isnan(*limit)) {109return false;110}111112Debug("data: %d, float: %.2f", cal_data, _p_min);113return true;114}115116bool AP_Baro_KellerLD::read_cal()117{118// Read out pressure measurement range119if (!read_measurement_limit(&_p_min, CMD_PRANGE_MIN_MSB, CMD_PRANGE_MIN_LSB)) {120return false;121}122123if (!read_measurement_limit(&_p_max, CMD_PRANGE_MAX_MSB, CMD_PRANGE_MAX_LSB)) {124return false;125}126127if (_p_max <= _p_min) {128return false;129}130131return true;132}133134// Read sensor P-Mode type and set pressure reference offset135// This determines the pressure offset based on the type of sensor136// vented to atmosphere, gauged to vacuum, or gauged to standard sea-level pressure137bool AP_Baro_KellerLD::read_mode_type()138{139uint8_t cmd = CMD_METADATA_PMODE;140uint8_t data[3];141if (!transfer_with_delays(&cmd, 1, data, ARRAY_SIZE(data))) {142return false;143}144145// Byte 3, Bit 0 & 1: Represents P-Mode146// "Communication Protocol 4 LD…9 LD", Version 2.6 pg 12 of 25147// https://keller-druck.com/?d=VeMYAQBxgoSNjUSHbdnBTU148_p_mode = (SensorMode)(data[2] & 0b11);149150// update pressure offset based on P-Mode151switch (_p_mode) {152case SensorMode::PR_MODE:153// PR-Mode vented gauge sensor154// pressure reads zero when the pressure outside is equal to the pressure inside the enclosure155_p_mode_offset = _frontend.get_pressure(0);156break;157case SensorMode::PA_MODE:158// PA-Mode sealed gauge sensor159// pressure reads zero when the pressure outside is equal to 1.0 bar160// i.e., the pressure at which the vent is sealed161_p_mode_offset = 1.0;162break;163case SensorMode::PAA_MODE:164// PAA-mode Absolute sensor (zero at vacuum)165_p_mode_offset = 0.0;166break;167case SensorMode::UNDEFINED:168// we should give an error here169printf("KellerLD Device Mode UNDEFINED\n");170return false;171}172173return true;174}175176// We read out the measurement range to be used in raw value conversions177bool AP_Baro_KellerLD::_init()178{179if (!_dev) {180return false;181}182183WITH_SEMAPHORE(_dev->get_semaphore());184185// high retries for init186_dev->set_retries(10);187188if (!read_cal()) {189printf("Cal read bad!\n");190return false;191}192193if (!read_mode_type()) {194printf("Mode_Type read bad!\n");195return false;196}197198printf("Keller LD found on bus %u address 0x%02x\n", _dev->bus_num(), _dev->get_bus_address());199200// Send a command to take a measurement201_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);202203memset(&_accum, 0, sizeof(_accum));204205_instance = _frontend.register_sensor();206207_dev->set_device_type(DEVTYPE_BARO_KELLERLD);208set_bus_id(_instance, _dev->get_bus_id());209210_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);211212// lower retries for run213_dev->set_retries(3);214215// The sensor needs time to take a deep breath after reading out the calibration...216hal.scheduler->delay(150);217218// Request 50Hz update219// The sensor really struggles with any jitter in timing at 100Hz, and will sometimes start reading out all zeros220_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC,221FUNCTOR_BIND_MEMBER(&AP_Baro_KellerLD::_timer, void));222return true;223}224225// Read out most recent measurement from sensor hw226bool AP_Baro_KellerLD::_read()227{228uint8_t data[5];229if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {230Debug("Keller LD read failed!");231return false;232}233234//uint8_t status = data[0];235uint16_t pressure_raw = (data[1] << 8) | data[2];236uint16_t temperature_raw = (data[3] << 8) | data[4];237238#if KELLER_DEBUG239static uint8_t samples = 0;240if (samples < 3) {241samples++;242Debug("data: [%d, %d, %d, %d, %d]", data[0], data[1], data[2], data[3], data[4]);243Debug("pressure_raw: %d\ttemperature_raw: %d", pressure_raw, temperature_raw);244}245#endif246247if (pressure_raw == 0 || temperature_raw == 0) {248Debug("Keller: bad read");249return false;250}251252if (!pressure_ok(pressure_raw)) {253return false;254}255256WITH_SEMAPHORE(_sem);257258_update_and_wrap_accumulator(pressure_raw, temperature_raw, 128);259260return true;261}262263// Periodic callback, regular update at 50Hz264// Read out most recent measurement, and request another265// Max conversion time according to datasheet is ~8ms, so266// max update rate is ~125Hz, yet we struggle to get consistent267// performance/data at 100Hz268void AP_Baro_KellerLD::_timer(void)269{270_read();271_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);272}273274// Accumulate a reading, shrink if necessary to prevent overflow275void AP_Baro_KellerLD::_update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)276{277_accum.sum_pressure += pressure;278_accum.sum_temperature += temperature;279_accum.num_samples += 1;280281if (_accum.num_samples == max_count) {282_accum.sum_pressure /= 2;283_accum.sum_temperature /= 2;284_accum.num_samples /= 2;285}286}287288// Take the average of accumulated values and push to frontend289void AP_Baro_KellerLD::update()290{291float sum_pressure, sum_temperature;292float num_samples;293294// update _p_mode_offset if vented guage295if (_p_mode == SensorMode::PR_MODE) {296// we need to get the pressure from on-board barometer297_p_mode_offset = _frontend.get_pressure(0);298}299300{301WITH_SEMAPHORE(_sem);302303if (_accum.num_samples == 0) {304return;305}306307sum_pressure = _accum.sum_pressure;308sum_temperature = _accum.sum_temperature;309num_samples = _accum.num_samples;310memset(&_accum, 0, sizeof(_accum));311}312313uint16_t raw_pressure_avg = sum_pressure / num_samples;314uint16_t raw_temperature_avg = sum_temperature / num_samples;315316// per datasheet317float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min + _p_mode_offset;318pressure *= 100000; // bar -> Pascal319float temperature = ((raw_temperature_avg >> 4) - 24) * 0.05f - 50;320321_copy_to_frontend(_instance, pressure, temperature);322}323324#endif // AP_BARO_KELLERLD_ENABLED325326327