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.h
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/>.131415* Driver for 4 LD ... 9 LD line of pressure transducers from Keller:16* http://www.keller-druck.com/home_e/paprod_e/4ld_e.asp17*18* These sensors operate on I2C and come in a variety of form factors.19* The measurement range is between 0-200 bar depbending on the model.20* They are definitely not the worlds smallest pressure transmitter.21*22* Default address is 0x40.23*/2425#pragma once2627#include "AP_Baro_Backend.h"2829#if AP_BARO_KELLERLD_ENABLED3031#include <AP_HAL/AP_HAL.h>32#include <AP_HAL/Semaphores.h>33#include <AP_HAL/Device.h>3435#ifndef HAL_BARO_KELLERLD_I2C_ADDR36#define HAL_BARO_KELLERLD_I2C_ADDR 0x4037#endif3839class AP_Baro_KellerLD : public AP_Baro_Backend40{41public:42void update() override;4344static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);4546private:47AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);4849bool _init();5051void _timer();5253bool _read();5455void _update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count);5657AP_HAL::OwnPtr<AP_HAL::Device> _dev;5859/* Shared values between thread sampling the HW and main thread */60/* These are raw outputs, not calculated values */61struct {62uint32_t sum_pressure;63uint32_t sum_temperature;64uint8_t num_samples;65} _accum;6667uint8_t _instance;6869enum class SensorMode {70PR_MODE = 0, // Vented gauge71PA_MODE = 1, // Sealed gauge72PAA_MODE = 2, // Absolute73UNDEFINED = 3,74};7576// to store sensor mode77SensorMode _p_mode;78// Model-specific offset/calibration values stored in device ROM79// pressure offset used in pressure calculation80float _p_mode_offset;81// measurement range parameters used in pressure calculation82float _p_min;83float _p_max;8485// helpers for reading out calibration information:86bool transfer_with_delays(uint8_t *send, uint8_t sendlen, uint8_t *recv, uint8_t recvlen);87bool read_measurement_limit(float *limit, uint8_t msb_addr, uint8_t lsb_addr);88bool read_cal();89bool read_mode_type();90};919293#endif // AP_BARO_KELLERLD_ENABLED949596