CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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