APM:Libraries
AP_Airspeed_analog.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_Param/AP_Param.h>
5 
6 #include "AP_Airspeed_Backend.h"
7 
9 {
10 public:
11  AP_Airspeed_Analog(AP_Airspeed &frontend, uint8_t _instance);
12 
13  // probe and initialise the sensor
14  bool init(void) override;
15 
16  // return the current differential_pressure in Pascal
17  bool get_differential_pressure(float &pressure) override;
18 
19  // temperature not available via analog backend
20  bool get_temperature(float &temperature) override { return false; }
21 
22 private:
24 };
AP_Airspeed_Analog(AP_Airspeed &frontend, uint8_t _instance)
bool get_temperature(float &temperature) override
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
bool init(void) override
AP_HAL::AnalogSource * _source
bool get_differential_pressure(float &pressure) override