Path: blob/master/libraries/AP_Baro/AP_Baro_KellerLD.cpp
9649 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_KellerLD.h"1617#if AP_BARO_KELLERLD_ENABLED1819#include <stdio.h>2021#include <AP_Math/AP_Math.h>2223#define KELLER_DEBUG 02425#if KELLER_DEBUG26# define Debug(fmt, args ...) do {printf(fmt "\n", ## args);} while(0)27#else28# define Debug(fmt, args ...)29#endif3031extern const AP_HAL::HAL &hal;3233// sensor metadata register34static const uint8_t CMD_METADATA_PMODE = 0x12;35// Measurement range registers36static const uint8_t CMD_PRANGE_MIN_MSB = 0x13;37static const uint8_t CMD_PRANGE_MIN_LSB = 0x14;38static const uint8_t CMD_PRANGE_MAX_MSB = 0x15;39static const uint8_t CMD_PRANGE_MAX_LSB = 0x16;4041// write to this address to start pressure measurement42static const uint8_t CMD_REQUEST_MEASUREMENT = 0xAC;4344AP_Baro_KellerLD::AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::Device &dev)45: AP_Baro_Backend(baro)46, _dev(&dev)47{48}4950// Look for the device on the bus and see if it responds appropriately51AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::Device &dev)52{53AP_Baro_KellerLD *sensor = NEW_NOTHROW AP_Baro_KellerLD(baro, dev);54if (!sensor || !sensor->_init()) {55delete sensor;56return nullptr;57}58return sensor;59}606162// convenience function to work around device transfer oddities63bool AP_Baro_KellerLD::transfer_with_delays(uint8_t *send, uint8_t sendlen, uint8_t *recv, uint8_t recvlen)64{65if (!_dev->transfer(send, sendlen, nullptr, 0)) {66return false;67}68hal.scheduler->delay(1);6970if(!_dev->transfer(nullptr, 0, recv, recvlen)) {71return false;72}73hal.scheduler->delay(1);74return true;75}7677// This device has some undocumented finicky quirks and requires78// delays when reading out the measurement range, but for some reason79// this isn't an issue when requesting measurements. This is why we80// need to split the transfers with delays like this. (Using81// AP_HAL::I2CDevice::set_split_transfers will not work with these82// sensors)83bool AP_Baro_KellerLD::read_measurement_limit(float *limit, uint8_t msb_addr, uint8_t lsb_addr)84{85uint8_t data[3];8687if (!transfer_with_delays(&msb_addr, 1, data, ARRAY_SIZE(data))) {88return false;89}9091const uint16_t ms_word = (data[1] << 8) | data[2];92Debug("0x%02x: %d [%d, %d, %d]", msb_addr, ms_word, data[0], data[1], data[2]);9394if (!transfer_with_delays(&lsb_addr, 1, data, ARRAY_SIZE(data))) {95return false;96}9798const uint16_t ls_word = (data[1] << 8) | data[2];99Debug("0x%02x: %d [%d, %d, %d]", lsb_addr, ls_word, data[0], data[1], data[2]);100101const uint32_t cal_data = (ms_word << 16) | ls_word;102memcpy(limit, &cal_data, sizeof(*limit));103104if (isinf(*limit) || isnan(*limit)) {105return false;106}107108Debug("data: %d, float: %.2f", cal_data, _p_min);109return true;110}111112bool AP_Baro_KellerLD::read_cal()113{114// Read out pressure measurement range115if (!read_measurement_limit(&_p_min, CMD_PRANGE_MIN_MSB, CMD_PRANGE_MIN_LSB)) {116return false;117}118119if (!read_measurement_limit(&_p_max, CMD_PRANGE_MAX_MSB, CMD_PRANGE_MAX_LSB)) {120return false;121}122123if (_p_max <= _p_min) {124return false;125}126127return true;128}129130// Read sensor P-Mode type and set pressure reference offset131// This determines the pressure offset based on the type of sensor132// vented to atmosphere, gauged to vacuum, or gauged to standard sea-level pressure133bool AP_Baro_KellerLD::read_mode_type()134{135uint8_t cmd = CMD_METADATA_PMODE;136uint8_t data[3];137if (!transfer_with_delays(&cmd, 1, data, ARRAY_SIZE(data))) {138return false;139}140141// Byte 3, Bit 0 & 1: Represents P-Mode142// "Communication Protocol 4 LD…9 LD", Version 2.6 pg 12 of 25143// https://keller-druck.com/?d=VeMYAQBxgoSNjUSHbdnBTU144_p_mode = (SensorMode)(data[2] & 0b11);145146// update pressure offset based on P-Mode147switch (_p_mode) {148case SensorMode::PR_MODE:149// PR-Mode vented gauge sensor150// pressure reads zero when the pressure outside is equal to the pressure inside the enclosure151_p_mode_offset = _frontend.get_pressure(0);152break;153case SensorMode::PA_MODE:154// PA-Mode sealed gauge sensor155// pressure reads zero when the pressure outside is equal to 1.0 bar156// i.e., the pressure at which the vent is sealed157_p_mode_offset = 1.0;158break;159case SensorMode::PAA_MODE:160// PAA-mode Absolute sensor (zero at vacuum)161_p_mode_offset = 0.0;162break;163case SensorMode::UNDEFINED:164// we should give an error here165printf("KellerLD Device Mode UNDEFINED\n");166return false;167}168169return true;170}171172// We read out the measurement range to be used in raw value conversions173bool AP_Baro_KellerLD::_init()174{175if (!_dev) {176return false;177}178179WITH_SEMAPHORE(_dev->get_semaphore());180181// high retries for init182_dev->set_retries(10);183184if (!read_cal()) {185printf("Cal read bad!\n");186return false;187}188189if (!read_mode_type()) {190printf("Mode_Type read bad!\n");191return false;192}193194printf("Keller LD found on bus %u address 0x%02x\n", _dev->bus_num(), _dev->get_bus_address());195196// Send a command to take a measurement197_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);198199memset(&_accum, 0, sizeof(_accum));200201_instance = _frontend.register_sensor();202203_dev->set_device_type(DEVTYPE_BARO_KELLERLD);204set_bus_id(_instance, _dev->get_bus_id());205206_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);207208// lower retries for run209_dev->set_retries(3);210211// The sensor needs time to take a deep breath after reading out the calibration...212hal.scheduler->delay(150);213214// Request 50Hz update215// The sensor really struggles with any jitter in timing at 100Hz, and will sometimes start reading out all zeros216_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC,217FUNCTOR_BIND_MEMBER(&AP_Baro_KellerLD::_timer, void));218return true;219}220221// Read out most recent measurement from sensor hw222bool AP_Baro_KellerLD::_read()223{224uint8_t data[5];225if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {226Debug("Keller LD read failed!");227return false;228}229230//uint8_t status = data[0];231uint16_t pressure_raw = (data[1] << 8) | data[2];232uint16_t temperature_raw = (data[3] << 8) | data[4];233234#if KELLER_DEBUG235static uint8_t samples = 0;236if (samples < 3) {237samples++;238Debug("data: [%d, %d, %d, %d, %d]", data[0], data[1], data[2], data[3], data[4]);239Debug("pressure_raw: %d\ttemperature_raw: %d", pressure_raw, temperature_raw);240}241#endif242243if (pressure_raw == 0 || temperature_raw == 0) {244Debug("Keller: bad read");245return false;246}247248if (!pressure_ok(pressure_raw)) {249return false;250}251252WITH_SEMAPHORE(_sem);253254_update_and_wrap_accumulator(pressure_raw, temperature_raw, 128);255256return true;257}258259// Periodic callback, regular update at 50Hz260// Read out most recent measurement, and request another261// Max conversion time according to datasheet is ~8ms, so262// max update rate is ~125Hz, yet we struggle to get consistent263// performance/data at 100Hz264void AP_Baro_KellerLD::_timer(void)265{266_read();267_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);268}269270// Accumulate a reading, shrink if necessary to prevent overflow271void AP_Baro_KellerLD::_update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)272{273_accum.sum_pressure += pressure;274_accum.sum_temperature += temperature;275_accum.num_samples += 1;276277if (_accum.num_samples == max_count) {278_accum.sum_pressure /= 2;279_accum.sum_temperature /= 2;280_accum.num_samples /= 2;281}282}283284// Take the average of accumulated values and push to frontend285void AP_Baro_KellerLD::update()286{287float sum_pressure, sum_temperature;288float num_samples;289290// update _p_mode_offset if vented guage291if (_p_mode == SensorMode::PR_MODE) {292// we need to get the pressure from on-board barometer293_p_mode_offset = _frontend.get_pressure(0);294}295296{297WITH_SEMAPHORE(_sem);298299if (_accum.num_samples == 0) {300return;301}302303sum_pressure = _accum.sum_pressure;304sum_temperature = _accum.sum_temperature;305num_samples = _accum.num_samples;306memset(&_accum, 0, sizeof(_accum));307}308309uint16_t raw_pressure_avg = sum_pressure / num_samples;310uint16_t raw_temperature_avg = sum_temperature / num_samples;311312// per datasheet313float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min + _p_mode_offset;314pressure *= 100000; // bar -> Pascal315float temperature = ((raw_temperature_avg >> 4) - 24) * 0.05f - 50;316317_copy_to_frontend(_instance, pressure, temperature);318}319320#endif // AP_BARO_KELLERLD_ENABLED321322323