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_Airspeed/AP_Airspeed_Backend.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/>.13*/14#pragma once1516/*17backend driver class for airspeed18*/1920#include "AP_Airspeed_config.h"2122#if AP_AIRSPEED_ENABLED2324#include <AP_Common/AP_Common.h>25#include <AP_HAL/AP_HAL_Boards.h>26#include <AP_HAL/Semaphores.h>27#include "AP_Airspeed.h"28#include <AP_MSP/msp_sensors.h>2930class AP_Airspeed_Backend {31public:32AP_Airspeed_Backend(AP_Airspeed &frontend, uint8_t instance);33virtual ~AP_Airspeed_Backend();3435// probe and initialise the sensor36virtual bool init(void) = 0;3738// return the current differential_pressure in Pascal39virtual bool get_differential_pressure(float &pressure) {return false;}4041// return the current temperature in degrees C, if available42virtual bool get_temperature(float &temperature) = 0;4344// true if sensor reads airspeed directly, not via pressure45virtual bool has_airspeed() {return false;}4647// return airspeed in m/s if available48virtual bool get_airspeed(float& airspeed) {return false;}4950virtual void handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}51#if AP_AIRSPEED_EXTERNAL_ENABLED52virtual void handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt) {}53#endif5455#if AP_AIRSPEED_HYGROMETER_ENABLE56// optional hygrometer support57virtual bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) { return false; }58#endif5960protected:61int8_t get_pin(void) const;62float get_psi_range(void) const;63uint8_t get_bus(void) const;64bool bus_is_configured(void) const;65uint8_t get_instance(void) const {66return instance;67}6869// see if voltage correction should be disabled70bool disable_voltage_correction(void) const {71return (frontend._options.get() & AP_Airspeed::OptionsMask::DISABLE_VOLTAGE_CORRECTION) != 0;72}7374AP_Airspeed::pitot_tube_order get_tube_order(void) const {75#ifndef HAL_BUILD_AP_PERIPH76return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());77#else78return AP_Airspeed::pitot_tube_order::PITOT_TUBE_ORDER_AUTO;79#endif80}8182// semaphore for access to shared frontend data83HAL_Semaphore sem;8485float get_airspeed_ratio(void) const {86return frontend.get_airspeed_ratio(instance);87}8889// some sensors use zero offsets90void set_use_zero_offset(void) {91frontend.state[instance].use_zero_offset = true;92}9394// set to no zero cal, which makes sense for some sensors95void set_skip_cal(void) {96#ifndef HAL_BUILD_AP_PERIPH97frontend.param[instance].skip_cal.set(1);98#endif99}100101// set zero offset102void set_offset(float ofs) {103#ifndef HAL_BUILD_AP_PERIPH104frontend.param[instance].offset.set(ofs);105#endif106}107108// set use109void set_use(int8_t use) {110#ifndef HAL_BUILD_AP_PERIPH111frontend.param[instance].use.set(use);112#endif113}114115// set bus ID of this instance, for ARSPD_DEVID parameters116void set_bus_id(uint32_t id);117118enum class DevType {119SITL = 0x01,120MS4525 = 0x02,121MS5525 = 0x03,122DLVR = 0x04,123MSP = 0x05,124SDP3X = 0x06,125UAVCAN = 0x07,126ANALOG = 0x08,127NMEA = 0x09,128ASP5033 = 0x0A,129};130131private:132AP_Airspeed &frontend;133uint8_t instance;134};135136#endif // AP_AIRSPEED_ENABLED137138139