APM:Libraries
AP_Airspeed.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <AP_Param/AP_Param.h>
7 #include <AP_Baro/AP_Baro.h>
8 
10 
11 #define AIRSPEED_MAX_SENSORS 2
12 
14 public:
15  friend class AP_Airspeed;
16  // constructor
18 
19  // initialise the calibration
20  void init(float initial_ratio);
21 
22  // take current airspeed in m/s and ground speed vector and return
23  // new scaling factor
24  float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal);
25 
26 private:
27  // state of kalman filter for airspeed ratio estimation
28  Matrix3f P; // covarience matrix
29  const float Q0; // process noise matrix top left and middle element
30  const float Q1; // process noise matrix bottom right element
31  Vector3f state; // state vector
32  const float DT; // time delta
33 };
34 
36 {
37 public:
38  friend class AP_Airspeed_Backend;
39 
40  // constructor
41  AP_Airspeed();
42 
43  void init(void);
44 
45  // read the analog source and update airspeed
46  void read(void);
47 
48  // calibrate the airspeed. This must be called on startup if the
49  // altitude/climb_rate/acceleration interfaces are ever used
50  void calibrate(bool in_startup);
51 
52  // return the current airspeed in m/s
53  float get_airspeed(uint8_t i) const {
54  return state[i].airspeed;
55  }
56  float get_airspeed(void) const { return get_airspeed(primary); }
57 
58  // return the unfiltered airspeed in m/s
59  float get_raw_airspeed(uint8_t i) const {
60  return state[i].raw_airspeed;
61  }
62  float get_raw_airspeed(void) const { return get_raw_airspeed(primary); }
63 
64  // return the current airspeed ratio (dimensionless)
65  float get_airspeed_ratio(uint8_t i) const {
66  return param[i].ratio;
67  }
68  float get_airspeed_ratio(void) const { return get_airspeed_ratio(primary); }
69 
70  // get temperature if available
71  bool get_temperature(uint8_t i, float &temperature);
72  bool get_temperature(float &temperature) { return get_temperature(primary, temperature); }
73 
74  // set the airspeed ratio (dimensionless)
75  void set_airspeed_ratio(uint8_t i, float ratio) {
76  param[i].ratio.set(ratio);
77  }
78  void set_airspeed_ratio(float ratio) { set_airspeed_ratio(primary, ratio); }
79 
80  // return true if airspeed is enabled, and airspeed use is set
81  bool use(uint8_t i) const;
82  bool use(void) const { return use(primary); }
83 
84  // return true if airspeed is enabled
85  bool enabled(uint8_t i) const {
86  if (i < AIRSPEED_MAX_SENSORS) {
87  return param[i].type.get() != TYPE_NONE;
88  }
89  return false;
90  }
91  bool enabled(void) const { return enabled(primary); }
92 
93  // used by HIL to set the airspeed
94  void set_HIL(float airspeed) {
95  state[primary].airspeed = airspeed;
96  }
97 
98  // return the differential pressure in Pascal for the last airspeed reading
99  float get_differential_pressure(uint8_t i) const {
100  return state[i].last_pressure;
101  }
102  float get_differential_pressure(void) const { return get_differential_pressure(primary); }
103 
104  // return the current calibration offset
105  float get_offset(uint8_t i) const {
106  return param[i].offset;
107  }
108  float get_offset(void) const { return get_offset(primary); }
109 
110  // return the current corrected pressure
111  float get_corrected_pressure(uint8_t i) const {
112  return state[i].corrected_pressure;
113  }
114  float get_corrected_pressure(void) const { return get_corrected_pressure(primary); }
115 
116  // set the apparent to true airspeed ratio
117  void set_EAS2TAS(uint8_t i, float v) {
118  state[i].EAS2TAS = v;
119  }
120  void set_EAS2TAS(float v) { set_EAS2TAS(primary, v); }
121 
122  // get the apparent to true airspeed ratio
123  float get_EAS2TAS(uint8_t i) const {
124  return state[i].EAS2TAS;
125  }
126  float get_EAS2TAS(void) const { return get_EAS2TAS(primary); }
127 
128  // update airspeed ratio calibration
129  void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
130 
131  // log data to MAVLink
132  void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground);
133 
134  // return health status of sensor
135  bool healthy(uint8_t i) const {
136  return state[i].healthy && (fabsf(param[i].offset) > 0 || state[i].use_zero_offset) && enabled(i);
137  }
138  bool healthy(void) const { return healthy(primary); }
139 
140  // return true if all enabled sensors are healthy
141  bool all_healthy(void) const;
142 
143  void setHIL(float pressure) { state[0].healthy=state[0].hil_set=true; state[0].hil_pressure=pressure; }
144 
145  // return time in ms of last update
146  uint32_t last_update_ms(uint8_t i) const { return state[i].last_update_ms; }
147  uint32_t last_update_ms(void) const { return last_update_ms(primary); }
148 
149  void setHIL(float airspeed, float diff_pressure, float temperature);
150 
151  static const struct AP_Param::GroupInfo var_info[];
152 
153  enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0,
154  PITOT_TUBE_ORDER_NEGATIVE = 1,
155  PITOT_TUBE_ORDER_AUTO = 2 };
156 
158  TYPE_NONE=0,
159  TYPE_I2C_MS4525=1,
160  TYPE_ANALOG=2,
161  TYPE_I2C_MS5525=3,
162  TYPE_I2C_MS5525_ADDRESS_1=4,
163  TYPE_I2C_MS5525_ADDRESS_2=5,
164  TYPE_I2C_SDP3X=6,
165  };
166 
167  // get current primary sensor
168  uint8_t get_primary(void) const { return primary; }
169 
170  static AP_Airspeed *get_singleton() { return _singleton; }
171 
172 private:
174 
175  AP_Int8 primary_sensor;
176 
177  struct {
178  AP_Float offset;
179  AP_Float ratio;
180  AP_Float psi_range;
181  AP_Int8 use;
182  AP_Int8 type;
183  AP_Int8 pin;
184  AP_Int8 bus;
185  AP_Int8 autocal;
186  AP_Int8 tube_order;
187  AP_Int8 skip_cal;
188  } param[AIRSPEED_MAX_SENSORS];
189 
190  struct airspeed_state {
192  float airspeed;
196  float EAS2TAS;
197  bool healthy:1;
198  bool hil_set:1;
200  uint32_t last_update_ms;
202 
203  // state of runtime calibration
204  struct {
205  uint32_t start_ms;
206  uint16_t count;
207  float sum;
208  uint16_t read_count;
209  } cal;
210 
213  uint8_t counter;
215 
216  // current primary sensor
217  uint8_t primary;
218 
219  void read(uint8_t i);
220  // return the differential pressure in Pascal for the last airspeed reading for the requested instance
221  // returns 0 if the sensor is not enabled
222  float get_pressure(uint8_t i);
223  void update_calibration(uint8_t i, float raw_pressure);
224  void update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
225 
227 };
void set_HIL(float airspeed)
Definition: AP_Airspeed.h:94
uint32_t last_update_ms(uint8_t i) const
Definition: AP_Airspeed.h:146
float get_corrected_pressure(void) const
Definition: AP_Airspeed.h:114
bool enabled(void) const
Definition: AP_Airspeed.h:91
uint8_t get_primary(void) const
Definition: AP_Airspeed.h:168
void setHIL(float pressure)
Definition: AP_Airspeed.h:143
bool enabled(uint8_t i) const
Definition: AP_Airspeed.h:85
bool use(void) const
Definition: AP_Airspeed.h:82
uint8_t primary
Definition: AP_Airspeed.h:217
void set_EAS2TAS(uint8_t i, float v)
Definition: AP_Airspeed.h:117
float get_airspeed_ratio(uint8_t i) const
Definition: AP_Airspeed.h:65
Airspeed_Calibration calibration
Definition: AP_Airspeed.h:211
AP_Int8 tube_order
Definition: AP_Airspeed.h:186
float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
AP_Float psi_range
Definition: AP_Airspeed.h:180
float get_differential_pressure(void) const
Definition: AP_Airspeed.h:102
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
float get_offset(uint8_t i) const
Definition: AP_Airspeed.h:105
float get_raw_airspeed(void) const
Definition: AP_Airspeed.h:62
virtual bool get_temperature(float &temperature)=0
void init(float initial_ratio)
void set_airspeed_ratio(uint8_t i, float ratio)
Definition: AP_Airspeed.h:75
float get_EAS2TAS(void) const
Definition: AP_Airspeed.h:126
AP_Int8 skip_cal
Definition: AP_Airspeed.h:187
AP_Int8 type
Definition: AP_Airspeed.h:182
AP_Int8 pin
Definition: AP_Airspeed.h:183
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
bool healthy(void) const
Definition: AP_Airspeed.h:138
float get_offset(void) const
Definition: AP_Airspeed.h:108
uint32_t last_update_ms(void) const
Definition: AP_Airspeed.h:147
AP_Float offset
Definition: AP_Airspeed.h:178
void set_airspeed_ratio(float ratio)
Definition: AP_Airspeed.h:78
float get_airspeed_ratio(void) const
Definition: AP_Airspeed.h:68
float get_raw_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:59
AP_Float ratio
Definition: AP_Airspeed.h:179
float get_corrected_pressure(uint8_t i) const
Definition: AP_Airspeed.h:111
bool get_temperature(float &temperature)
Definition: AP_Airspeed.h:72
float v
Definition: Printf.cpp:15
AP_Int8 autocal
Definition: AP_Airspeed.h:185
float get_differential_pressure(uint8_t i) const
Definition: AP_Airspeed.h:99
#define AIRSPEED_MAX_SENSORS
Definition: AP_Airspeed.h:11
AP_Int8 primary_sensor
Definition: AP_Airspeed.h:175
static AP_Airspeed * get_singleton()
Definition: AP_Airspeed.h:170
Common definitions and utility routines for the ArduPilot libraries.
float get_airspeed(void) const
Definition: AP_Airspeed.h:56
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float get_EAS2TAS(uint8_t i) const
Definition: AP_Airspeed.h:123
static AP_Airspeed * _singleton
Definition: AP_Airspeed.h:173
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
friend class AP_Airspeed
Definition: AP_Airspeed.h:15
AP_Int8 bus
Definition: AP_Airspeed.h:184
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
void set_EAS2TAS(float v)
Definition: AP_Airspeed.h:120
AP_Int8 use
Definition: AP_Airspeed.h:181