APM:Libraries
AP_Airspeed.cpp
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 /*
16  * APM_Airspeed.cpp - airspeed (pitot) driver
17  */
18 
19 #include <AP_ADC/AP_ADC.h>
20 #include <AP_Common/AP_Common.h>
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_HAL/I2CDevice.h>
23 #include <AP_Math/AP_Math.h>
24 #include <GCS_MAVLink/GCS.h>
26 #include <utility>
27 #include "AP_Airspeed.h"
28 #include "AP_Airspeed_MS4525.h"
29 #include "AP_Airspeed_MS5525.h"
30 #include "AP_Airspeed_SDP3X.h"
31 #include "AP_Airspeed_analog.h"
32 #include "AP_Airspeed_Backend.h"
33 
34 extern const AP_HAL::HAL &hal;
35 
36 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
37  #define ARSPD_DEFAULT_TYPE TYPE_ANALOG
38  #define ARSPD_DEFAULT_PIN 1
39 #else
40  #define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
41  #define ARSPD_DEFAULT_PIN 15
42 #endif
43 
44 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
45 #define PSI_RANGE_DEFAULT 0.05
46 #endif
47 
48 #ifndef PSI_RANGE_DEFAULT
49 #define PSI_RANGE_DEFAULT 1.0f
50 #endif
51 
52 // table of user settable parameters
54 
55  // @Param: _TYPE
56  // @DisplayName: Airspeed type
57  // @Description: Type of airspeed sensor
58  // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X
59  // @User: Standard
61 
62  // @Param: _USE
63  // @DisplayName: Airspeed use
64  // @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
65  // @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle
66  // @User: Standard
67  AP_GROUPINFO("_USE", 1, AP_Airspeed, param[0].use, 0),
68 
69  // @Param: _OFFSET
70  // @DisplayName: Airspeed offset
71  // @Description: Airspeed calibration offset
72  // @Increment: 0.1
73  // @User: Advanced
74  AP_GROUPINFO("_OFFSET", 2, AP_Airspeed, param[0].offset, 0),
75 
76  // @Param: _RATIO
77  // @DisplayName: Airspeed ratio
78  // @Description: Airspeed calibration ratio
79  // @Increment: 0.1
80  // @User: Advanced
81  AP_GROUPINFO("_RATIO", 3, AP_Airspeed, param[0].ratio, 1.9936f),
82 
83  // @Param: _PIN
84  // @DisplayName: Airspeed pin
85  // @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
86  // @User: Advanced
87  AP_GROUPINFO("_PIN", 4, AP_Airspeed, param[0].pin, ARSPD_DEFAULT_PIN),
88 
89  // @Param: _AUTOCAL
90  // @DisplayName: Automatic airspeed ratio calibration
91  // @Description: If this is enabled then the APM will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
92  // @User: Advanced
93  AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0),
94 
95  // @Param: _TUBE_ORDER
96  // @DisplayName: Control pitot tube order
97  // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed.
98  // @User: Advanced
99  AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2),
100 
101  // @Param: _SKIP_CAL
102  // @DisplayName: Skip airspeed calibration on startup
103  // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
104  // @Values: 0:Disable,1:Enable
105  // @User: Advanced
106  AP_GROUPINFO("_SKIP_CAL", 7, AP_Airspeed, param[0].skip_cal, 0),
107 
108  // @Param: _PSI_RANGE
109  // @DisplayName: The PSI range of the device
110  // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
111  // @User: Advanced
112  AP_GROUPINFO("_PSI_RANGE", 8, AP_Airspeed, param[0].psi_range, PSI_RANGE_DEFAULT),
113 
114  // @Param: _BUS
115  // @DisplayName: Airspeed I2C bus
116  // @Description: The bus number of the I2C bus to look for the sensor on
117  // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary)
118  // @User: Advanced
119  AP_GROUPINFO("_BUS", 9, AP_Airspeed, param[0].bus, 1),
120 
121  // @Param: _PRIMARY
122  // @DisplayName: Primary airspeed sensor
123  // @Description: This selects which airspeed sensor will be the primary if multiple sensors are found
124  // @Values: 0:FirstSensor,1:2ndSensor
125  // @User: Advanced
126  AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),
127 
128  // @Param: 2_TYPE
129  // @DisplayName: Second Airspeed type
130  // @Description: Type of 2nd airspeed sensor
131  // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X
132  // @User: Standard
133  AP_GROUPINFO_FLAGS("2_TYPE", 11, AP_Airspeed, param[1].type, 0, AP_PARAM_FLAG_ENABLE),
134 
135  // @Param: 2_USE
136  // @DisplayName: Enable use of 2nd airspeed sensor
137  // @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
138  // @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle
139  // @User: Standard
140  AP_GROUPINFO("2_USE", 12, AP_Airspeed, param[1].use, 0),
141 
142  // @Param: 2_OFFSET
143  // @DisplayName: Airspeed offset for 2nd airspeed sensor
144  // @Description: Airspeed calibration offset
145  // @Increment: 0.1
146  // @User: Advanced
147  AP_GROUPINFO("2_OFFSET", 13, AP_Airspeed, param[1].offset, 0),
148 
149  // @Param: 2_RATIO
150  // @DisplayName: Airspeed ratio for 2nd airspeed sensor
151  // @Description: Airspeed calibration ratio
152  // @Increment: 0.1
153  // @User: Advanced
154  AP_GROUPINFO("2_RATIO", 14, AP_Airspeed, param[1].ratio, 2),
155 
156  // @Param: 2_PIN
157  // @DisplayName: Airspeed pin for 2nd airspeed sensor
158  // @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
159  // @User: Advanced
160  AP_GROUPINFO("2_PIN", 15, AP_Airspeed, param[1].pin, 0),
161 
162  // @Param: 2_AUTOCAL
163  // @DisplayName: Automatic airspeed ratio calibration for 2nd airspeed sensor
164  // @Description: If this is enabled then the APM will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
165  // @User: Advanced
166  AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0),
167 
168  // @Param: 2_TUBE_ORDR
169  // @DisplayName: Control pitot tube order of 2nd airspeed sensor
170  // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed.
171  // @User: Advanced
172  AP_GROUPINFO("2_TUBE_ORDR", 17, AP_Airspeed, param[1].tube_order, 2),
173 
174  // @Param: 2_SKIP_CAL
175  // @DisplayName: Skip airspeed calibration on startup for 2nd sensor
176  // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
177  // @Values: 0:Disable,1:Enable
178  // @User: Advanced
179  AP_GROUPINFO("2_SKIP_CAL", 18, AP_Airspeed, param[1].skip_cal, 0),
180 
181  // @Param: 2_PSI_RANGE
182  // @DisplayName: The PSI range of the device for 2nd sensor
183  // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
184  // @User: Advanced
185  AP_GROUPINFO("2_PSI_RANGE", 19, AP_Airspeed, param[1].psi_range, PSI_RANGE_DEFAULT),
186 
187  // @Param: 2_BUS
188  // @DisplayName: Airspeed I2C bus for 2nd sensor
189  // @Description: The bus number of the I2C bus to look for the sensor on
190  // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary)
191  // @User: Advanced
192  AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1),
193 
195 };
196 
197 
199 {
200  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
201  state[i].EAS2TAS = 1;
202  }
204 
205  if (_singleton != nullptr) {
206  AP_HAL::panic("AP_Airspeed must be singleton");
207  }
208  _singleton = this;
209 }
210 
211 
212 /*
213  this scaling factor converts from the old system where we used a
214  0 to 4095 raw ADC value for 0-5V to the new system which gets the
215  voltage in volts directly from the ADC driver
216  */
217 #define SCALING_OLD_CALIBRATION 819 // 4095/5
218 
220 {
221  // cope with upgrade from old system
222  if (param[0].pin.load() && param[0].pin.get() != 65) {
223  param[0].type.set_default(TYPE_ANALOG);
224  }
225 
226  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
228  state[i].last_saved_ratio = param[i].ratio;
229 
230  switch ((enum airspeed_type)param[i].type.get()) {
231  case TYPE_NONE:
232  // nothing to do
233  break;
234  case TYPE_I2C_MS4525:
235  sensor[i] = new AP_Airspeed_MS4525(*this, i);
236  break;
237  case TYPE_ANALOG:
238  sensor[i] = new AP_Airspeed_Analog(*this, i);
239  break;
240  case TYPE_I2C_MS5525:
242  break;
245  break;
248  break;
249  case TYPE_I2C_SDP3X:
250  sensor[i] = new AP_Airspeed_SDP3X(*this, i);
251  break;
252  }
253  if (sensor[i] && !sensor[i]->init()) {
254  gcs().send_text(MAV_SEVERITY_INFO, "Airspeed[%u] init failed", i);
255  delete sensor[i];
256  sensor[i] = nullptr;
257  }
258  }
259 }
260 
261 // read the airspeed sensor
263 {
264  if (!enabled(i)) {
265  return 0;
266  }
267  if (state[i].hil_set) {
268  state[i].healthy = true;
269  return state[i].hil_pressure;
270  }
271  float pressure = 0;
272  if (sensor[i]) {
273  state[i].healthy = sensor[i]->get_differential_pressure(pressure);
274  }
275  return pressure;
276 }
277 
278 // get a temperature reading if possible
280 {
281  if (!enabled(i)) {
282  return false;
283  }
284  if (sensor[i]) {
285  return sensor[i]->get_temperature(temperature);
286  }
287  return false;
288 }
289 
290 // calibrate the zero offset for the airspeed. This must be called at
291 // least once before the get_airspeed() interface can be used
292 void AP_Airspeed::calibrate(bool in_startup)
293 {
294  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
295  if (!enabled(i)) {
296  continue;
297  }
298  if (state[i].use_zero_offset) {
299  param[i].offset.set(0);
300  continue;
301  }
302  if (in_startup && param[i].skip_cal) {
303  continue;
304  }
306  state[i].cal.count = 0;
307  state[i].cal.sum = 0;
308  state[i].cal.read_count = 0;
309  }
310  gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
311 }
312 
313 /*
314  update async airspeed zero offset calibration
315 */
316 void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
317 {
318  if (!enabled(i) || state[i].cal.start_ms == 0) {
319  return;
320  }
321 
322  // consider calibration complete when we have at least 15 samples
323  // over at least 1 second
324  if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&
325  state[i].cal.read_count > 15) {
326  if (state[i].cal.count == 0) {
327  gcs().send_text(MAV_SEVERITY_INFO, "Airspeed[%u] sensor unhealthy", i);
328  } else {
329  gcs().send_text(MAV_SEVERITY_INFO, "Airspeed[%u] sensor calibrated", i);
330  param[i].offset.set_and_save(state[i].cal.sum / state[i].cal.count);
331  }
332  state[i].cal.start_ms = 0;
333  return;
334  }
335  // we discard the first 5 samples
336  if (state[i].healthy && state[i].cal.read_count > 5) {
337  state[i].cal.sum += raw_pressure;
338  state[i].cal.count++;
339  }
340  state[i].cal.read_count++;
341 }
342 
343 // read one airspeed sensor
344 void AP_Airspeed::read(uint8_t i)
345 {
346  float airspeed_pressure;
347  if (!enabled(i) || !sensor[i]) {
348  return;
349  }
350  float raw_pressure = get_pressure(i);
351  if (state[i].cal.start_ms != 0) {
352  update_calibration(i, raw_pressure);
353  }
354 
355  airspeed_pressure = raw_pressure - param[i].offset;
356 
357  // remember raw pressure for logging
358  state[i].corrected_pressure = airspeed_pressure;
359 
360  // filter before clamping positive
361  state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;
362 
363  /*
364  we support different pitot tube setups so user can choose if
365  they want to be able to detect pressure on the static port
366  */
367  switch ((enum pitot_tube_order)param[i].tube_order.get()) {
369  state[i].last_pressure = -airspeed_pressure;
370  state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);
371  state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);
372  break;
374  state[i].last_pressure = airspeed_pressure;
375  state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);
376  state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);
377  if (airspeed_pressure < -32) {
378  // we're reading more than about -8m/s. The user probably has
379  // the ports the wrong way around
380  state[i].healthy = false;
381  }
382  break;
384  default:
385  state[i].last_pressure = fabsf(airspeed_pressure);
386  state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);
387  state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
388  break;
389  }
390 
392 }
393 
394 // read all airspeed sensors
396 {
397  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
398  read(i);
399  }
400 
401 #if 1
402  // debugging until we get MAVLink support for 2nd airspeed sensor
403  if (enabled(1)) {
404  gcs().send_named_float("AS2", get_airspeed(1));
405  }
406 #endif
407 
408  // setup primary
409  if (healthy(primary_sensor.get())) {
410  primary = primary_sensor.get();
411  return;
412  }
413  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
414  if (healthy(i)) {
415  primary = i;
416  break;
417  }
418  }
419 }
420 
421 void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature)
422 {
424  state[0].airspeed = airspeed;
425  state[0].last_pressure = diff_pressure;
427  state[0].hil_pressure = diff_pressure;
428  state[0].hil_set = true;
429  state[0].healthy = true;
430 }
431 
432 bool AP_Airspeed::use(uint8_t i) const
433 {
434  if (!enabled(i) || !param[i].use) {
435  return false;
436  }
438  // special case for gliders with airspeed sensors behind the
439  // propeller. Allow airspeed to be disabled when throttle is
440  // running
441  return false;
442  }
443  return true;
444 }
445 
446 /*
447  return true if all enabled sensors are healthy
448  */
449 bool AP_Airspeed::all_healthy(void) const
450 {
451  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
452  if (enabled(i) && !healthy(i)) {
453  return false;
454  }
455  }
456  return true;
457 }
458 
459 // singleton instance
461 
bool enabled(void) const
Definition: AP_Airspeed.h:91
void setHIL(float pressure)
Definition: AP_Airspeed.h:143
bool use(void) const
Definition: AP_Airspeed.h:82
uint8_t primary
Definition: AP_Airspeed.h:217
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
static int16_t get_output_scaled(SRV_Channel::Aux_servo_function_t function)
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Airspeed.h:151
struct AP_Airspeed::airspeed_state::@6 cal
Airspeed_Calibration calibration
Definition: AP_Airspeed.h:211
AP_Int8 tube_order
Definition: AP_Airspeed.h:186
#define ARSPD_DEFAULT_PIN
Definition: AP_Airspeed.cpp:38
Interface definition for the various Ground Control System.
#define ARSPD_DEFAULT_TYPE
Definition: AP_Airspeed.cpp:37
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define PSI_RANGE_DEFAULT
Definition: AP_Airspeed.cpp:45
virtual bool get_temperature(float &temperature)=0
void init(float initial_ratio)
GCS & gcs()
AP_Int8 skip_cal
Definition: AP_Airspeed.h:187
AP_Int8 type
Definition: AP_Airspeed.h:182
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
AP_Int8 pin
Definition: AP_Airspeed.h:183
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
float temperature
Definition: Airspeed.cpp:32
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
bool all_healthy(void) const
void read(void)
bool healthy(void) const
Definition: AP_Airspeed.h:138
#define f(i)
uint32_t millis()
Definition: system.cpp:157
AP_Float ratio
Definition: AP_Airspeed.h:179
void calibrate(bool in_startup)
void send_named_float(const char *name, float value) const
Definition: GCS.cpp:32
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool get_temperature(uint8_t i, float &temperature)
struct AP_Airspeed::airspeed_state state[AIRSPEED_MAX_SENSORS]
#define AIRSPEED_MAX_SENSORS
Definition: AP_Airspeed.h:11
AP_Int8 primary_sensor
Definition: AP_Airspeed.h:175
AP_Airspeed_Backend * sensor[AIRSPEED_MAX_SENSORS]
Definition: AP_Airspeed.h:226
void init(void)
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
static AP_Airspeed * _singleton
Definition: AP_Airspeed.h:173
float get_pressure(uint8_t i)
virtual bool get_differential_pressure(float &pressure)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static int8_t pin
Definition: AnalogIn.cpp:15
#define AP_GROUPEND
Definition: AP_Param.h:121
struct AP_Airspeed::@5 param[AIRSPEED_MAX_SENSORS]
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214