Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed.cpp
9623 views
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
* AP_Airspeed.cpp - airspeed (pitot) driver
17
*/
18
19
#include "AP_Airspeed_config.h"
20
21
#if AP_AIRSPEED_ENABLED
22
23
#include "AP_Airspeed.h"
24
25
#include <AP_Vehicle/AP_Vehicle_Type.h>
26
27
// Dummy the AP_Airspeed class to allow building Airspeed only for plane, rover, sub, and copter & heli 2MB boards
28
// This could be removed once the build system allows for APM_BUILD_TYPE in header files
29
// Note that this is also defined in AP_Airspeed_Params.cpp
30
#ifndef AP_AIRSPEED_DUMMY_METHODS_ENABLED
31
#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && HAL_PROGRAM_SIZE_LIMIT_KB <= 1024) || \
32
APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Blimp))
33
#endif
34
35
#if !AP_AIRSPEED_DUMMY_METHODS_ENABLED
36
37
#include <AP_Common/AP_Common.h>
38
#include <AP_HAL/AP_HAL.h>
39
#include <AP_HAL/I2CDevice.h>
40
#include <AP_Math/AP_Math.h>
41
#include <GCS_MAVLink/GCS.h>
42
#include <SRV_Channel/SRV_Channel.h>
43
#include <AP_Logger/AP_Logger.h>
44
#include <utility>
45
#include "AP_Airspeed_MS4525.h"
46
#include "AP_Airspeed_MS5525.h"
47
#include "AP_Airspeed_SDP3X.h"
48
#include "AP_Airspeed_DLVR.h"
49
#include "AP_Airspeed_analog.h"
50
#include "AP_Airspeed_ASP5033.h"
51
#include "AP_Airspeed_Backend.h"
52
#include "AP_Airspeed_DroneCAN.h"
53
#include "AP_Airspeed_NMEA.h"
54
#include "AP_Airspeed_MSP.h"
55
#include "AP_Airspeed_AUAV.h"
56
#include "AP_Airspeed_External.h"
57
#include "AP_Airspeed_SITL.h"
58
extern const AP_HAL::HAL &hal;
59
60
#include <AP_Vehicle/AP_FixedWing.h>
61
62
#ifdef HAL_AIRSPEED_TYPE_DEFAULT
63
#define ARSPD_DEFAULT_TYPE HAL_AIRSPEED_TYPE_DEFAULT
64
#ifndef ARSPD_DEFAULT_PIN
65
#define ARSPD_DEFAULT_PIN 1
66
#endif
67
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
68
// The HAL_BOARD_SITL setting is required because of current probe process for MS4525 will
69
// connect and find the SIM_DLVR sensors & fault as there is no way to tell them apart
70
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
71
#define ARSPD_DEFAULT_TYPE TYPE_ANALOG
72
#define ARSPD_DEFAULT_PIN 1
73
#elif AP_AIRSPEED_MS4525_ENABLED
74
#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
75
#ifdef HAL_DEFAULT_AIRSPEED_PIN
76
#define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN
77
#else
78
#define ARSPD_DEFAULT_PIN 15
79
#endif
80
#else
81
#define ARSPD_DEFAULT_TYPE TYPE_NONE
82
#define ARSPD_DEFAULT_PIN 15
83
#endif //CONFIG_HAL_BOARD
84
#else // All Other Vehicle Types
85
#define ARSPD_DEFAULT_TYPE TYPE_NONE
86
#define ARSPD_DEFAULT_PIN 15
87
#endif
88
89
#ifndef HAL_AIRSPEED_BUS_DEFAULT
90
#define HAL_AIRSPEED_BUS_DEFAULT 1
91
#endif
92
93
#define OPTIONS_DEFAULT AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE | AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE | AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY
94
95
#define ENABLE_PARAMETER !(APM_BUILD_TYPE(APM_BUILD_ArduPlane) || defined(HAL_BUILD_AP_PERIPH))
96
97
// table of user settable parameters
98
const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
99
100
#if ENABLE_PARAMETER
101
// @Param: _ENABLE
102
// @DisplayName: Airspeed Enable
103
// @Description: Enable airspeed sensor support
104
// @Values: 0:Disable, 1:Enable
105
// @User: Standard
106
AP_GROUPINFO_FLAGS("_ENABLE", 30, AP_Airspeed, _enable, 0, AP_PARAM_FLAG_ENABLE),
107
#endif
108
// slots 0-9 (and 63) were previously used by params before being refactored into AP_Airspeed_Params
109
110
// @Param: _TUBE_ORDER
111
// @DisplayName: Control pitot tube order
112
// @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 first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation 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 is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.
113
// @User: Advanced
114
// @Values: 0:Normal,1:Swapped,2:Auto Detect
115
116
// tube order param had to be shortened so is not preserved in per group descriptions
117
118
#if AIRSPEED_MAX_SENSORS > 1
119
// @Param: _PRIMARY
120
// @DisplayName: Primary airspeed sensor
121
// @Description: This selects which airspeed sensor will be the primary if multiple sensors are found
122
// @Values: 0:FirstSensor, 1:2nd Sensor, 2:3rd Sensor, 3:4th Sensor, 4:5th Sensor, 5:6th Sensor
123
// @User: Advanced
124
AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),
125
#endif
126
127
// 11-20 were previously used by second sensor params before being refactored into AP_Airspeed_Params
128
129
#ifndef HAL_BUILD_AP_PERIPH
130
// @Param: _OPTIONS
131
// @DisplayName: Airspeed options bitmask
132
// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3), 4:Report cal offset to GCS
133
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
134
// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency, 4:ReportOffset
135
// @User: Advanced
136
AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),
137
138
// @Param: _WIND_MAX
139
// @DisplayName: Maximum airspeed and ground speed difference
140
// @Description: If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTIONS this health value can be used to disable the sensor.
141
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
142
// @Units: m/s
143
// @User: Advanced
144
AP_GROUPINFO("_WIND_MAX", 22, AP_Airspeed, _wind_max, 0),
145
146
// @Param: _WIND_WARN
147
// @DisplayName: Airspeed and GPS speed difference that gives a warning
148
// @Description: If the difference between airspeed and GPS speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used.
149
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
150
// @Units: m/s
151
// @User: Advanced
152
AP_GROUPINFO("_WIND_WARN", 23, AP_Airspeed, _wind_warn, 0),
153
154
// @Param: _WIND_GATE
155
// @DisplayName: Re-enable Consistency Check Gate Size
156
// @Description: Number of standard deviations applied to the re-enable EKF consistency check that is used when ARSPD_OPTIONS bit position 3 is set. Larger values will make the re-enabling of the airspeed sensor faster, but increase the likelihood of re-enabling a degraded sensor. The value can be tuned by using the ARSP.TR log message by setting ARSPD_WIND_GATE to a value that is higher than the value for ARSP.TR observed with a healthy airspeed sensor. Occasional transients in ARSP.TR above the value set by ARSPD_WIND_GATE can be tolerated provided they are less than 5 seconds in duration and less than 10% duty cycle.
157
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle.
158
// @Range: 0.0 10.0
159
// @User: Advanced
160
AP_GROUPINFO("_WIND_GATE", 26, AP_Airspeed, _wind_gate, 5.0f),
161
162
// @Param{Plane}: _OFF_PCNT
163
// @DisplayName: Maximum offset cal speed error
164
// @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered.
165
// @Range: 0.0 10.0
166
// @Units: %
167
// @User: Advanced
168
AP_GROUPINFO_FRAME("_OFF_PCNT", 27, AP_Airspeed, max_speed_pcnt, 0, AP_PARAM_FRAME_PLANE),
169
170
#endif
171
172
// @Group: _
173
// @Path: AP_Airspeed_Params.cpp
174
AP_SUBGROUPINFO(param[0], "_", 28, AP_Airspeed, AP_Airspeed_Params),
175
176
#if AIRSPEED_MAX_SENSORS > 1
177
// @Group: 2_
178
// @Path: AP_Airspeed_Params.cpp
179
AP_SUBGROUPINFO(param[1], "2_", 29, AP_Airspeed, AP_Airspeed_Params),
180
#endif
181
182
// index 30 is used by enable at the top of the table
183
184
#if AIRSPEED_MAX_SENSORS > 2
185
// @Group: 3_
186
// @Path: AP_Airspeed_Params.cpp
187
AP_SUBGROUPINFO(param[2], "3_", 31, AP_Airspeed, AP_Airspeed_Params),
188
#endif
189
190
#if AIRSPEED_MAX_SENSORS > 3
191
// @Group: 4_
192
// @Path: AP_Airspeed_Params.cpp
193
AP_SUBGROUPINFO(param[3], "4_", 32, AP_Airspeed, AP_Airspeed_Params),
194
#endif
195
196
#if AIRSPEED_MAX_SENSORS > 4
197
// @Group: 5_
198
// @Path: AP_Airspeed_Params.cpp
199
AP_SUBGROUPINFO(param[4], "5_", 33, AP_Airspeed, AP_Airspeed_Params),
200
#endif
201
202
#if AIRSPEED_MAX_SENSORS > 5
203
// @Group: 6_
204
// @Path: AP_Airspeed_Params.cpp
205
AP_SUBGROUPINFO(param[5], "6_", 34, AP_Airspeed, AP_Airspeed_Params),
206
#endif
207
208
AP_GROUPEND
209
};
210
211
/*
212
this scaling factor converts from the old system where we used a
213
0 to 4095 raw ADC value for 0-5V to the new system which gets the
214
voltage in volts directly from the ADC driver
215
*/
216
#define SCALING_OLD_CALIBRATION 819 // 4095/5
217
218
AP_Airspeed::AP_Airspeed()
219
{
220
AP_Param::setup_object_defaults(this, var_info);
221
222
// Setup defaults that only apply to first sensor
223
param[0].type.set_default(ARSPD_DEFAULT_TYPE);
224
#ifndef HAL_BUILD_AP_PERIPH
225
param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT);
226
param[0].pin.set_default(ARSPD_DEFAULT_PIN);
227
#endif
228
229
if (_singleton != nullptr) {
230
AP_HAL::panic("AP_Airspeed must be singleton");
231
}
232
_singleton = this;
233
}
234
235
void AP_Airspeed::set_fixedwing_parameters(const AP_FixedWing *_fixed_wing_parameters)
236
{
237
fixed_wing_parameters = _fixed_wing_parameters;
238
}
239
240
// macro for use by HAL_INS_PROBE_LIST
241
#define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device_ptr(bus, address)
242
243
bool AP_Airspeed::add_backend(AP_Airspeed_Backend *backend)
244
{
245
if (!backend) {
246
return false;
247
}
248
if (num_sensors >= AIRSPEED_MAX_SENSORS) {
249
AP_HAL::panic("Too many airspeed drivers");
250
}
251
const uint8_t i = num_sensors;
252
sensor[num_sensors++] = backend;
253
if (!sensor[i]->init()) {
254
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i+1);
255
delete sensor[i];
256
sensor[i] = nullptr;
257
}
258
return true;
259
}
260
261
/*
262
macro to add a backend with check for too many sensors
263
We don't try to start more than the maximum allowed
264
*/
265
#define ADD_BACKEND(backend) \
266
do { add_backend(backend); \
267
if (num_sensors == AIRSPEED_MAX_SENSORS) { return; } \
268
} while (0)
269
270
271
// convert params to per instance param table
272
// PARAMETER_CONVERSION - Added: Dec-2022
273
void AP_Airspeed::convert_per_instance()
274
{
275
AP_Param::ConversionInfo info;
276
#ifndef HAL_BUILD_AP_PERIPH
277
// Vehicle conversion
278
if (!AP_Param::find_key_by_pointer(this, info.old_key)) {
279
return;
280
}
281
282
static const struct convert_table {
283
uint32_t element[2];
284
ap_var_type type;
285
const char* name;
286
} conversion_table[] = {
287
{ {4042, 714}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE
288
{ {74, 778}, AP_PARAM_INT8, "USE" }, // ARSPD_USE, ARSPD2_USE
289
{ {138, 842}, AP_PARAM_FLOAT, "OFFSET" }, // ARSPD_OFFSET, ARSPD2_OFFSET
290
{ {202, 906}, AP_PARAM_FLOAT, "RATIO" }, // ARSPD_RATIO, ARSPD2_RATIO
291
{ {266, 970}, AP_PARAM_INT8, "PIN" }, // ARSPD_PIN, ARSPD2_PIN
292
#if AP_AIRSPEED_AUTOCAL_ENABLE
293
{ {330, 1034}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL
294
#endif
295
{ {394, 1098}, AP_PARAM_INT8, "TUBE_ORDR" }, // ARSPD_TUBE_ORDER, ARSPD2_TUBE_ORDR
296
{ {458, 1162}, AP_PARAM_INT8, "SKIP_CAL" }, // ARSPD_SKIP_CAL, ARSPD2_SKIP_CAL
297
{ {522, 1226}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE
298
{ {586, 1290}, AP_PARAM_INT8, "BUS" }, // ARSPD_BUS, ARSPD2_BUS
299
{ {1546, 1610}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID
300
};
301
302
#else
303
// Periph conversion
304
if (!AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {
305
return;
306
}
307
const struct convert_table {
308
uint32_t element[2];
309
ap_var_type type;
310
const char* name;
311
} conversion_table[] = {
312
{ {0, 11}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE
313
#if AP_AIRSPEED_AUTOCAL_ENABLE
314
{ {5, 16}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL
315
#endif
316
{ {8, 19}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE
317
{ {24, 25}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID
318
};
319
#endif
320
321
char param_name[17] {};
322
info.new_name = param_name;
323
324
for (const auto & elem : conversion_table) {
325
info.type = elem.type;
326
for (uint8_t i=0; i < MIN(AIRSPEED_MAX_SENSORS,2); i++) {
327
info.old_group_element = elem.element[i];
328
if (i == 0) {
329
hal.util->snprintf(param_name, sizeof(param_name), "ARSPD_%s", elem.name);
330
} else {
331
hal.util->snprintf(param_name, sizeof(param_name), "ARSPD%i_%s", i+1, elem.name);
332
}
333
AP_Param::convert_old_parameter(&info, 1.0, 0);
334
}
335
}
336
}
337
338
void AP_Airspeed::init()
339
{
340
341
convert_per_instance();
342
343
// Set primary from parameter to avoid primary changed message at boot
344
primary = primary_sensor.get();
345
346
#if ENABLE_PARAMETER
347
// if either type is set then enable if not manually set
348
if (!_enable.configured() && ((param[0].type.get() != TYPE_NONE) || (param[1].type.get() != TYPE_NONE))) {
349
_enable.set_and_save(1);
350
}
351
352
// Check if enabled
353
if (!lib_enabled()) {
354
return;
355
}
356
#endif
357
358
if (enabled(0)) {
359
allocate();
360
}
361
}
362
363
void AP_Airspeed::allocate()
364
{
365
if (sensor[0] != nullptr) {
366
// already initialised, periph may call allocate several times to allow CAN detection
367
return;
368
}
369
370
#ifdef HAL_AIRSPEED_PROBE_LIST
371
// load sensors via a list from hwdef.dat
372
HAL_AIRSPEED_PROBE_LIST;
373
#else
374
// look for sensors based on type parameters
375
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
376
#if AP_AIRSPEED_AUTOCAL_ENABLE
377
state[i].calibration.init(param[i].ratio);
378
state[i].last_saved_ratio = param[i].ratio;
379
#endif
380
381
// Set the enable automatically to false and set the probability that the airspeed is healhy to start with
382
state[i].failures.health_probability = 1.0f;
383
384
switch ((enum airspeed_type)param[i].type.get()) {
385
case TYPE_NONE:
386
// nothing to do
387
break;
388
#if AP_AIRSPEED_MS4525_ENABLED
389
case TYPE_I2C_MS4525:
390
sensor[i] = NEW_NOTHROW AP_Airspeed_MS4525(*this, i);
391
break;
392
#endif // AP_AIRSPEED_MS4525_ENABLED
393
#if AP_AIRSPEED_SITL_ENABLED
394
case TYPE_SITL:
395
sensor[i] = NEW_NOTHROW AP_Airspeed_SITL(*this, i);
396
break;
397
#endif // AP_AIRSPEED_SITL_ENABLED
398
#if AP_AIRSPEED_ANALOG_ENABLED
399
case TYPE_ANALOG:
400
sensor[i] = NEW_NOTHROW AP_Airspeed_Analog(*this, i);
401
break;
402
#endif // AP_AIRSPEED_ANALOG_ENABLED
403
#if AP_AIRSPEED_MS5525_ENABLED
404
case TYPE_I2C_MS5525:
405
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
406
break;
407
#endif // AP_AIRSPEED_MS5525_ENABLED
408
#if AP_AIRSPEED_MS5525_ENABLED
409
case TYPE_I2C_MS5525_ADDRESS_1:
410
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);
411
break;
412
#endif // AP_AIRSPEED_MS5525_ENABLED
413
#if AP_AIRSPEED_MS5525_ENABLED
414
case TYPE_I2C_MS5525_ADDRESS_2:
415
sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);
416
break;
417
#endif // AP_AIRSPEED_MS5525_ENABLED
418
#if AP_AIRSPEED_SDP3X_ENABLED
419
case TYPE_I2C_SDP3X:
420
sensor[i] = NEW_NOTHROW AP_Airspeed_SDP3X(*this, i);
421
break;
422
#endif // AP_AIRSPEED_SDP3X_ENABLED
423
#if AP_AIRSPEED_DLVR_ENABLED
424
case TYPE_I2C_DLVR_5IN:
425
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 5);
426
break;
427
case TYPE_I2C_DLVR_10IN:
428
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 10);
429
break;
430
case TYPE_I2C_DLVR_20IN:
431
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 20);
432
break;
433
case TYPE_I2C_DLVR_30IN:
434
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 30);
435
break;
436
case TYPE_I2C_DLVR_60IN:
437
sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 60);
438
break;
439
#endif // AP_AIRSPEED_DLVR_ENABLED
440
#if AP_AIRSPEED_ASP5033_ENABLED
441
case TYPE_I2C_ASP5033:
442
sensor[i] = NEW_NOTHROW AP_Airspeed_ASP5033(*this, i);
443
break;
444
#endif // AP_AIRSPEED_ASP5033_ENABLED
445
#if AP_AIRSPEED_DRONECAN_ENABLED
446
case TYPE_UAVCAN:
447
sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));
448
break;
449
#endif // AP_AIRSPEED_DRONECAN_ENABLED
450
#if AP_AIRSPEED_NMEA_ENABLED
451
case TYPE_NMEA_WATER:
452
#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
453
sensor[i] = NEW_NOTHROW AP_Airspeed_NMEA(*this, i);
454
#endif
455
break;
456
#endif // AP_AIRSPEED_NMEA_ENABLED
457
#if AP_AIRSPEED_MSP_ENABLED
458
case TYPE_MSP:
459
sensor[i] = NEW_NOTHROW AP_Airspeed_MSP(*this, i, 0);
460
break;
461
#endif // AP_AIRSPEED_MSP_ENABLED
462
#if AP_AIRSPEED_EXTERNAL_ENABLED
463
case TYPE_EXTERNAL:
464
sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i);
465
break;
466
#endif // AP_AIRSPEED_EXTERNAL_ENABLED
467
#if AP_AIRSPEED_AUAV_ENABLED
468
case TYPE_AUAV_5IN:
469
sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 5);
470
break;
471
case TYPE_AUAV_10IN:
472
sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 10);
473
break;
474
case TYPE_AUAV_30IN:
475
sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 30);
476
break;
477
#endif // AP_AIRSPEED_AUAV_ENABLED
478
}
479
if (sensor[i] && !sensor[i]->init()) {
480
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i + 1);
481
delete sensor[i];
482
sensor[i] = nullptr;
483
}
484
if (sensor[i] != nullptr) {
485
num_sensors = i+1;
486
}
487
}
488
489
#if AP_AIRSPEED_DRONECAN_ENABLED
490
// we need a 2nd pass for DroneCAN sensors so we can match order by DEVID
491
// the 2nd pass accepts any devid
492
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
493
if (sensor[i] == nullptr && (enum airspeed_type)param[i].type.get() == TYPE_UAVCAN) {
494
sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, 0);
495
if (sensor[i] != nullptr) {
496
num_sensors = i+1;
497
}
498
}
499
}
500
#endif // AP_AIRSPEED_DRONECAN_ENABLED
501
#endif // HAL_AIRSPEED_PROBE_LIST
502
503
// set DEVID to zero for any sensors not found. This allows backends to order
504
// based on previous value of DEVID. This allows for swapping out sensors
505
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
506
if (sensor[i] == nullptr) {
507
// note we use set() not set_and_save() to allow a sensor to be temporarily
508
// removed for one boot without losing its slot
509
param[i].bus_id.set(0);
510
}
511
}
512
}
513
514
// get a temperature reading if possible
515
bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) const
516
{
517
if (!enabled(i)) {
518
return false;
519
}
520
if (sensor[i]) {
521
return sensor[i]->get_temperature(temperature);
522
}
523
return false;
524
}
525
526
// calibrate the zero offset for the airspeed. This must be called at
527
// least once before the get_airspeed() interface can be used
528
void AP_Airspeed::calibrate(bool in_startup)
529
{
530
#ifndef HAL_BUILD_AP_PERIPH
531
if (!lib_enabled()) {
532
return;
533
}
534
if (hal.util->was_watchdog_reset()) {
535
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed: skipping cal");
536
return;
537
}
538
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
539
if (!enabled(i)) {
540
continue;
541
}
542
if (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) {
543
continue;
544
}
545
if (in_startup) {
546
switch ((AP_Airspeed_Params::SkipCalType)param[i].skip_cal.get()) {
547
case AP_Airspeed_Params::SkipCalType::None:
548
break;
549
550
case AP_Airspeed_Params::SkipCalType::NoCalRequired:
551
// Skip startup calibration, use saved value.
552
state[i].cal.state = CalibrationState::SUCCESS;
553
continue;
554
555
case AP_Airspeed_Params::SkipCalType::SkipBootCal:
556
// Skip startup calibration, calibration state remains NOT_STARTED.
557
continue;
558
}
559
}
560
if (sensor[i] == nullptr) {
561
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u not initialized, cannot cal", i+1);
562
continue;
563
}
564
state[i].cal.start_ms = AP_HAL::millis();
565
state[i].cal.count = 0;
566
state[i].cal.sum = 0;
567
state[i].cal.read_count = 0;
568
state[i].cal.state = CalibrationState::IN_PROGRESS;
569
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u calibration started", i+1);
570
}
571
#endif // HAL_BUILD_AP_PERIPH
572
}
573
574
/*
575
update async airspeed zero offset calibration
576
*/
577
void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
578
{
579
#ifndef HAL_BUILD_AP_PERIPH
580
if (!enabled(i) || state[i].cal.start_ms == 0) {
581
return;
582
}
583
584
// consider calibration complete when we have at least 15 samples
585
// over at least 1 second
586
if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&
587
state[i].cal.read_count > 15) {
588
if (state[i].cal.count == 0) {
589
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1);
590
state[i].cal.state = CalibrationState::FAILED;
591
} else {
592
float calibrated_offset = state[i].cal.sum / state[i].cal.count;
593
// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind
594
if (fixed_wing_parameters != nullptr) {
595
float airspeed_min = fixed_wing_parameters->airspeed_min.get();
596
// use percentage of AIRSPEED_MIN as criteria for max allowed change in offset
597
float max_change = 0.5*(sq((1 + (max_speed_pcnt * 0.01))*airspeed_min) - sq(airspeed_min));
598
if (max_speed_pcnt > 0 && (abs(calibrated_offset-param[i].offset) > max_change) && (abs(param[i].offset) > 0)) {
599
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Arspd %d offset change large;cover and recal", i +1);
600
}
601
}
602
param[i].offset.set_and_save(calibrated_offset);
603
state[i].cal.state = CalibrationState::SUCCESS;
604
if (_options & AP_Airspeed::OptionsMask::REPORT_OFFSET ){
605
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated, offset = %4.0f", i + 1, calibrated_offset);
606
} else {
607
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);
608
}
609
}
610
state[i].cal.start_ms = 0;
611
return;
612
}
613
// we discard the first 5 samples
614
if (state[i].healthy && state[i].cal.read_count > 5) {
615
state[i].cal.sum += raw_pressure;
616
state[i].cal.count++;
617
}
618
state[i].cal.read_count++;
619
#endif // HAL_BUILD_AP_PERIPH
620
}
621
622
// get aggregate calibration state for the Airspeed library:
623
AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const
624
{
625
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
626
if (!enabled(i)) {
627
continue;
628
}
629
630
switch (state[i].cal.state) {
631
case CalibrationState::SUCCESS:
632
case CalibrationState::NOT_REQUIRED_ZERO_OFFSET:
633
continue;
634
case CalibrationState::NOT_STARTED:
635
return CalibrationState::NOT_STARTED;
636
case CalibrationState::IN_PROGRESS:
637
return CalibrationState::IN_PROGRESS;
638
case CalibrationState::FAILED:
639
return CalibrationState::FAILED;
640
}
641
}
642
return CalibrationState::SUCCESS;
643
}
644
645
// read one airspeed sensor
646
void AP_Airspeed::read(uint8_t i)
647
{
648
if (!enabled(i) || !sensor[i]) {
649
return;
650
}
651
state[i].last_update_ms = AP_HAL::millis();
652
653
// try and get a direct reading of airspeed
654
if (sensor[i]->has_airspeed()) {
655
state[i].healthy = sensor[i]->get_airspeed(state[i].airspeed);
656
state[i].raw_airspeed = state[i].airspeed; // for logging
657
return;
658
}
659
660
#ifndef HAL_BUILD_AP_PERIPH
661
/*
662
remember the old healthy state
663
*/
664
bool prev_healthy = state[i].healthy;
665
#endif
666
667
float raw_pressure = 0;
668
state[i].healthy = sensor[i]->get_differential_pressure(raw_pressure);
669
670
float airspeed_pressure = raw_pressure - get_offset(i);
671
672
// remember raw pressure for logging
673
state[i].corrected_pressure = airspeed_pressure;
674
675
#ifndef HAL_BUILD_AP_PERIPH
676
if (state[i].cal.start_ms != 0) {
677
update_calibration(i, raw_pressure);
678
}
679
680
// filter before clamping positive
681
if (!prev_healthy) {
682
// if the previous state was not healthy then we should not
683
// use an IIR filter, otherwise a bad reading will last for
684
// some time after the sensor becomes healthy again
685
state[i].filtered_pressure = airspeed_pressure;
686
} else {
687
state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;
688
}
689
690
/*
691
we support different pitot tube setups so user can choose if
692
they want to be able to detect pressure on the static port
693
*/
694
switch ((enum pitot_tube_order)param[i].tube_order.get()) {
695
case PITOT_TUBE_ORDER_NEGATIVE:
696
state[i].last_pressure = -airspeed_pressure;
697
state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);
698
state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);
699
break;
700
case PITOT_TUBE_ORDER_POSITIVE:
701
state[i].last_pressure = airspeed_pressure;
702
state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);
703
state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);
704
break;
705
case PITOT_TUBE_ORDER_AUTO:
706
default:
707
state[i].last_pressure = fabsf(airspeed_pressure);
708
state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);
709
state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
710
break;
711
}
712
#endif // HAL_BUILD_AP_PERIPH
713
}
714
715
// Select primary sensor based on user parameters and health
716
uint8_t AP_Airspeed::select_primary()
717
{
718
// user selected primary from parameter, track changes
719
const uint8_t user_primary = primary_sensor.get();
720
const bool user_primary_changed = user_primary != last_user_primary;
721
last_user_primary = user_primary;
722
723
// If user selected instance is both healthy and set to use then it is a valid primary
724
const bool user_healthy = healthy(user_primary);
725
const bool user_healthy_and_use = user_healthy && use(user_primary);
726
727
if ((user_primary_changed || !hal.util->get_soft_armed()) && user_healthy_and_use) {
728
/*
729
If user selected primary is healthy and set to use then:
730
Always change when the user changes the parameter.
731
Always change if disarmed, if armed its better to stick with the current sensor to avoid needless switching.
732
733
The EKF3 innovation check only applies to the active sensor so a bad sensor will appear good after some time because
734
the EKF is no longer using the sensor so cannot provide feedback.
735
736
We can't just stick with the current primary when disarmed due to variation in detection time.
737
*/
738
return user_primary;
739
}
740
741
// If the currently selected primary is valid there is no need to change
742
const bool primary_healthy = healthy(primary);
743
if (primary_healthy && use(primary)) {
744
return primary;
745
}
746
747
if (user_healthy_and_use) {
748
// The current primary is not valid, try the user set primary first
749
return user_primary;
750
}
751
752
// Select the first sensor which is both healthy and set to use
753
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
754
if ((i == primary) || (i == user_primary)) {
755
// No need to re-check current/user primary
756
continue;
757
}
758
if (healthy(i) && use(i)) {
759
return i;
760
}
761
}
762
763
// No sensor is both healthy and set to use
764
765
// Continue with current primary if healthy
766
if (primary_healthy) {
767
return primary;
768
}
769
770
// Use user selected instance if healthy
771
if (user_healthy) {
772
return user_primary;
773
}
774
775
// Select the first sensor which is healthy
776
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
777
if ((i == primary) || (i == user_primary)) {
778
// No need to re-check current/user primary
779
continue;
780
}
781
if (healthy(i)) {
782
return i;
783
}
784
}
785
786
// No healthy sensor, don't change primary
787
return primary;
788
}
789
790
// read all airspeed sensors
791
void AP_Airspeed::update()
792
{
793
if (!lib_enabled()) {
794
return;
795
}
796
797
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
798
read(i);
799
}
800
801
#if HAL_GCS_ENABLED
802
// debugging until we get MAVLink support for 2nd airspeed sensor
803
if (enabled(1)) {
804
gcs().send_named_float("AS2", get_airspeed(1));
805
}
806
#endif
807
808
// Check for failures possibly marking sensors and unhealthy
809
check_sensor_failures();
810
811
// Record old primary sensor for reporting
812
const uint8_t old_primary = primary;
813
814
// Select primary sensor based on user parameters and health
815
primary = select_primary();
816
817
if (primary != old_primary) {
818
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Airspeed primary changed: %i", primary+1);
819
}
820
821
#if HAL_LOGGING_ENABLED
822
if (primary != old_primary) {
823
AP::logger().Write_Event(LogEvent::AIRSPEED_PRIMARY_CHANGED);
824
}
825
if (_log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {
826
Log_Airspeed();
827
}
828
#endif
829
}
830
831
#if AP_AIRSPEED_MSP_ENABLED
832
/*
833
handle MSP airspeed data
834
*/
835
void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt)
836
{
837
if (!lib_enabled()) {
838
return;
839
}
840
841
if (pkt.instance > 1) {
842
return; //supporting 2 airspeed sensors at most
843
}
844
845
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
846
if (sensor[i]) {
847
sensor[i]->handle_msp(pkt);
848
}
849
}
850
}
851
#endif
852
853
#if AP_AIRSPEED_EXTERNAL_ENABLED
854
/*
855
handle airspeed airspeed data
856
*/
857
void AP_Airspeed::handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt)
858
{
859
if (!lib_enabled()) {
860
return;
861
}
862
863
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
864
if (param[i].type == TYPE_EXTERNAL && sensor[i]) {
865
sensor[i]->handle_external(pkt);
866
}
867
}
868
}
869
#endif
870
871
#if HAL_LOGGING_ENABLED
872
// @LoggerMessage: HYGR
873
// @Description: Hygrometer data
874
// @Field: TimeUS: Time since system startup
875
// @Field: Id: sensor ID
876
// @Field: Humidity: percentage humidity
877
// @Field: Temp: temperature in degrees C
878
879
void AP_Airspeed::Log_Airspeed()
880
{
881
const uint64_t now = AP_HAL::micros64();
882
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
883
if (!enabled(i) || sensor[i] == nullptr) {
884
continue;
885
}
886
float temperature;
887
if (!get_temperature(i, temperature)) {
888
temperature = 0;
889
}
890
const struct log_ARSP pkt{
891
LOG_PACKET_HEADER_INIT(LOG_ARSP_MSG),
892
time_us : now,
893
instance : i,
894
airspeed : get_raw_airspeed(i),
895
diffpressure : get_differential_pressure(i),
896
temperature : (int16_t)(temperature * 100.0f),
897
rawpressure : get_corrected_pressure(i),
898
offset : get_offset(i),
899
use : use(i),
900
healthy : healthy(i),
901
health_prob : get_health_probability(i),
902
test_ratio : get_test_ratio(i),
903
primary : get_primary()
904
};
905
AP::logger().WriteBlock(&pkt, sizeof(pkt));
906
907
#if AP_AIRSPEED_HYGROMETER_ENABLE
908
struct {
909
uint32_t sample_ms;
910
float temperature;
911
float humidity;
912
} hygrometer;
913
if (sensor[i]->get_hygrometer(hygrometer.sample_ms, hygrometer.temperature, hygrometer.humidity) &&
914
hygrometer.sample_ms != state[i].last_hygrometer_log_ms) {
915
AP::logger().WriteStreaming("HYGR",
916
"TimeUS,Id,Humidity,Temp",
917
"s#%O",
918
"F---",
919
"QBff",
920
AP_HAL::micros64(),
921
i,
922
hygrometer.humidity,
923
hygrometer.temperature);
924
state[i].last_hygrometer_log_ms = hygrometer.sample_ms;
925
}
926
#endif
927
}
928
}
929
#endif
930
931
bool AP_Airspeed::use(uint8_t i) const
932
{
933
#ifndef HAL_BUILD_AP_PERIPH
934
if (!lib_enabled()) {
935
return false;
936
}
937
if (_force_disable_use) {
938
return false;
939
}
940
if (!enabled(i) || !param[i].use) {
941
return false;
942
}
943
if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) {
944
// special case for gliders with airspeed sensors behind the
945
// propeller. Allow airspeed to be disabled when throttle is
946
// running
947
return false;
948
}
949
return true;
950
#else
951
return false;
952
#endif // HAL_BUILD_AP_PERIPH
953
}
954
955
/*
956
return true if all enabled sensors are healthy
957
*/
958
bool AP_Airspeed::all_healthy(void) const
959
{
960
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
961
if (enabled(i) && !healthy(i)) {
962
return false;
963
}
964
}
965
return true;
966
}
967
968
bool AP_Airspeed::lib_enabled() const {
969
#if ENABLE_PARAMETER
970
return _enable > 0;
971
#endif
972
return true;
973
}
974
975
// return true if airspeed is enabled
976
bool AP_Airspeed::enabled(uint8_t i) const {
977
if (!lib_enabled()) {
978
return false;
979
}
980
if (i < AIRSPEED_MAX_SENSORS) {
981
return param[i].type.get() != TYPE_NONE;
982
}
983
return false;
984
}
985
986
// return health status of sensor
987
bool AP_Airspeed::healthy(uint8_t i) const {
988
if (!enabled(i)) {
989
return false;
990
}
991
bool ok = state[i].healthy && sensor[i] != nullptr;
992
#ifndef HAL_BUILD_AP_PERIPH
993
// sanity check the offset parameter. Zero is permitted if we are skipping calibration.
994
const bool allowZeroOffset = (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) ||
995
((AP_Airspeed_Params::SkipCalType)param[i].skip_cal == AP_Airspeed_Params::SkipCalType::NoCalRequired);
996
ok &= allowZeroOffset || !is_zero(param[i].offset);
997
#endif
998
return ok;
999
}
1000
1001
// return the current airspeed in m/s
1002
float AP_Airspeed::get_airspeed(uint8_t i) const {
1003
if (!enabled(i)) {
1004
// we can't have negative airspeed so sending an obviously invalid value
1005
return -1.0;
1006
}
1007
return state[i].airspeed;
1008
}
1009
1010
// return the unfiltered airspeed in m/s
1011
float AP_Airspeed::get_raw_airspeed(uint8_t i) const {
1012
if (!enabled(i)) {
1013
// we can't have negative airspeed so sending an obviously invalid value
1014
return -1.0;
1015
}
1016
return state[i].raw_airspeed;
1017
}
1018
1019
// return the differential pressure in Pascal for the last airspeed reading
1020
float AP_Airspeed::get_differential_pressure(uint8_t i) const {
1021
if (!enabled(i)) {
1022
return 0.0;
1023
}
1024
return state[i].last_pressure;
1025
}
1026
1027
// return the current corrected pressure
1028
float AP_Airspeed::get_corrected_pressure(uint8_t i) const {
1029
if (!enabled(i)) {
1030
return 0.0;
1031
}
1032
return state[i].corrected_pressure;
1033
}
1034
1035
// return the current calibration offset
1036
float AP_Airspeed::get_offset(uint8_t i) const {
1037
#ifndef HAL_BUILD_AP_PERIPH
1038
if (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) {
1039
return 0.0;
1040
}
1041
return param[i].offset;
1042
#else
1043
return 0.0;
1044
#endif
1045
}
1046
1047
#if AP_AIRSPEED_HYGROMETER_ENABLE
1048
bool AP_Airspeed::get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const
1049
{
1050
if (!enabled(i) || sensor[i] == nullptr) {
1051
return false;
1052
}
1053
return sensor[i]->get_hygrometer(last_sample_ms, temperature, humidity);
1054
}
1055
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
1056
1057
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
1058
#ifndef HAL_BUILD_AP_PERIPH
1059
bool AP_Airspeed::arming_checks(size_t buflen, char *buffer) const
1060
{
1061
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
1062
if (!enabled(i) || !use(i)) {
1063
continue;
1064
}
1065
1066
switch (state[i].cal.state) {
1067
case CalibrationState::SUCCESS:
1068
case CalibrationState::NOT_REQUIRED_ZERO_OFFSET:
1069
break;
1070
1071
case CalibrationState::NOT_STARTED:
1072
case CalibrationState::FAILED:
1073
hal.util->snprintf(buffer, buflen, "%d need pre-flight calibration", i + 1);
1074
return false;
1075
1076
case CalibrationState::IN_PROGRESS:
1077
hal.util->snprintf(buffer, buflen, "%d pre-flight calibration in progress", i + 1);
1078
return false;
1079
}
1080
1081
if (!healthy(i)) {
1082
hal.util->snprintf(buffer, buflen, "%d not healthy", i + 1);
1083
return false;
1084
}
1085
}
1086
1087
1088
// If the primary sensor is marked to not use then user should either:
1089
// - change primary to a sensor which is marked to to use
1090
// - allow using the primary
1091
// If no sensors are marked for use then the check passes
1092
if (!use(primary_sensor.get())) {
1093
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
1094
if (use(i)) {
1095
hal.util->snprintf(buffer, buflen, "not using Primary (%i)", primary_sensor.get() + 1);
1096
return false;
1097
}
1098
}
1099
}
1100
1101
return true;
1102
}
1103
#endif
1104
1105
#else // build type is not appropriate; provide a dummy implementation:
1106
const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };
1107
1108
void AP_Airspeed::update() {};
1109
bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) const { return false; }
1110
void AP_Airspeed::calibrate(bool in_startup) {}
1111
AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const { return CalibrationState::NOT_STARTED; }
1112
bool AP_Airspeed::use(uint8_t i) const { return false; }
1113
bool AP_Airspeed::enabled(uint8_t i) const { return false; }
1114
bool AP_Airspeed::healthy(uint8_t i) const { return false; }
1115
float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; }
1116
float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; }
1117
bool AP_Airspeed::arming_checks(size_t buflen, char *buffer) const { return true; }
1118
1119
#if AP_AIRSPEED_MSP_ENABLED
1120
void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}
1121
#endif
1122
1123
bool AP_Airspeed::all_healthy(void) const { return false; }
1124
void AP_Airspeed::init(void) {};
1125
AP_Airspeed::AP_Airspeed() {}
1126
1127
#endif // #if AP_AIRSPEED_DUMMY_METHODS_ENABLED
1128
1129
// singleton instance
1130
AP_Airspeed *AP_Airspeed::_singleton;
1131
1132
namespace AP {
1133
1134
AP_Airspeed *airspeed()
1135
{
1136
return AP_Airspeed::get_singleton();
1137
}
1138
1139
};
1140
1141
#endif // AP_AIRSPEED_ENABLED
1142
1143