APM:Libraries
AP_Airspeed_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  backend driver class for airspeed
19  */
20 
21 #include <AP_Common/AP_Common.h>
22 #include <AP_HAL/AP_HAL.h>
23 #include "AP_Airspeed.h"
24 
26 public:
28  virtual ~AP_Airspeed_Backend();
29 
30  // probe and initialise the sensor
31  virtual bool init(void) = 0;
32 
33  // return the current differential_pressure in Pascal
34  virtual bool get_differential_pressure(float &pressure) = 0;
35 
36  // return the current temperature in degrees C, if available
37  virtual bool get_temperature(float &temperature) = 0;
38 
39 protected:
40  int8_t get_pin(void) const;
41  float get_psi_range(void) const;
42  uint8_t get_bus(void) const;
43 
45  return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());
46  }
47 
48  // semaphore for access to shared frontend data
50 
51  float get_airspeed_ratio(void) const {
52  return frontend.get_airspeed_ratio(instance);
53  }
54 
55  // some sensors use zero offsets
56  void set_use_zero_offset(void) {
57  frontend.state[instance].use_zero_offset = true;
58  }
59 
60  // set to no zero cal, which makes sense for some sensors
61  void set_skip_cal(void) {
62  frontend.param[instance].skip_cal.set(1);
63  }
64 
65  // set zero offset
66  void set_offset(float ofs) {
67  frontend.param[instance].offset.set(ofs);
68  }
69 
70 private:
72  uint8_t instance;
73 };
float get_psi_range(void) const
int8_t get_pin(void) const
float get_airspeed_ratio(uint8_t i) const
Definition: AP_Airspeed.h:65
AP_Int8 tube_order
Definition: AP_Airspeed.h:186
float get_airspeed_ratio(void) const
virtual bool get_temperature(float &temperature)=0
AP_Int8 skip_cal
Definition: AP_Airspeed.h:187
AP_HAL::Semaphore * sem
float temperature
Definition: Airspeed.cpp:32
AP_Airspeed_Backend(AP_Airspeed &frontend, uint8_t instance)
void set_offset(float ofs)
virtual bool init(void)=0
AP_Float offset
Definition: AP_Airspeed.h:178
struct AP_Airspeed::airspeed_state state[AIRSPEED_MAX_SENSORS]
Common definitions and utility routines for the ArduPilot libraries.
uint8_t get_bus(void) const
virtual bool get_differential_pressure(float &pressure)=0
AP_Airspeed::pitot_tube_order get_tube_order(void) const
struct AP_Airspeed::@5 param[AIRSPEED_MAX_SENSORS]