Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_AUAV.h
4183 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*/14#pragma once1516#include "AP_Airspeed_config.h"1718#if AP_AIRSPEED_AUAV_ENABLED1920/*21backend driver for airspeed from I2C22*/2324#include <AP_HAL/AP_HAL.h>25#include <AP_HAL/I2CDevice.h>26#include <utility>2728#include "AP_Airspeed_Backend.h"2930class AUAV_Pressure_sensor31{32public:33enum class Type {34Differential,35Absolute,36};3738AUAV_Pressure_sensor(AP_HAL::I2CDevice *&_dev, Type _type);3940// start a measurement41// Return true if successful42bool measure() WARN_IF_UNUSED;4344enum class Status {45Normal, // Happy, valid reading46Busy, // Busy, try reading again later47Fault, // Something bad has happened48};4950// read the values from the sensor51// Return status52// pressure corrected but not scaled to the correct units53// temperature in degrees centigrade54Status collect(float &PComp, float &temperature) WARN_IF_UNUSED;5556// Read coefficients in stages57enum class CoefficientStage {58A_high,59A_low,60B_high,61B_low,62C_high,63C_low,64D_high,65D_low,66E_high,67E_low,68Done,69} stage;7071// Read extended compensation coefficients from sensor72void read_coefficients();7374// Read 4 bytes compensation coefficient75bool read_register(uint8_t cmd, uint16_t &result);7677private:78AP_HAL::I2CDevice *&dev;7980Type type;8182// Extended compensation coefficients83// Theses are read from the sensor in read_coefficients84float LIN_A;85float LIN_B;86float LIN_C;87float LIN_D;88float Es;89float TC50H;90float TC50L;9192// Step of reading coefficients, request must be made before read.93enum class CoefficientStep {94request,95read,96} coefficient_step;9798};99100class AP_Airspeed_AUAV : public AP_Airspeed_Backend101{102public:103AP_Airspeed_AUAV(AP_Airspeed &frontend, uint8_t _instance, const float _range_inH2O);104~AP_Airspeed_AUAV(void) {105delete _dev;106}107108// probe and initialise the sensor109bool init() override;110111// return the current differential_pressure in Pascal112bool get_differential_pressure(float &pressure) override;113114// return the current temperature in degrees C, if available115bool get_temperature(float &temperature) override;116117private:118bool probe(uint8_t bus, uint8_t address);119void _timer();120121uint32_t last_sample_time_ms;122bool measurement_requested;123AP_HAL::I2CDevice *_dev;124125AUAV_Pressure_sensor sensor { _dev, AUAV_Pressure_sensor::Type::Differential };126127float pressure;128float temp_C;129const float range_inH2O;130};131132#endif // AP_Airspeed_AUAV_ENABLED133134135