Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro.cpp
9447 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
/*
17
* APM_Baro.cpp - barometer driver
18
*
19
*/
20
#include "AP_Baro.h"
21
22
#include <stdio.h>
23
24
#include <GCS_MAVLink/GCS.h>
25
#include <AP_Common/AP_Common.h>
26
#include <AP_HAL/AP_HAL.h>
27
#include <AP_Math/AP_Math.h>
28
#include <AP_BoardConfig/AP_BoardConfig.h>
29
#include <AP_CANManager/AP_CANManager.h>
30
#include <AP_Vehicle/AP_Vehicle_Type.h>
31
#include <AP_HAL/I2CDevice.h>
32
33
#include "AP_Baro_SITL.h"
34
#include "AP_Baro_BMP085.h"
35
#include "AP_Baro_BMP280.h"
36
#include "AP_Baro_BMP388.h"
37
#include "AP_Baro_BMP581.h"
38
#include "AP_Baro_SPL06.h"
39
#include "AP_Baro_KellerLD.h"
40
#include "AP_Baro_MS5611.h"
41
#include "AP_Baro_ICM20789.h"
42
#include "AP_Baro_LPS2XH.h"
43
#include "AP_Baro_FBM320.h"
44
#include "AP_Baro_DPS280.h"
45
#include "AP_Baro_Dummy.h"
46
#include "AP_Baro_DroneCAN.h"
47
#include "AP_Baro_MSP.h"
48
#include "AP_Baro_ExternalAHRS.h"
49
#include "AP_Baro_ICP101XX.h"
50
#include "AP_Baro_ICP201XX.h"
51
#include "AP_Baro_AUAV.h"
52
53
#include <AP_Airspeed/AP_Airspeed.h>
54
#include <AP_AHRS/AP_AHRS.h>
55
#include <AP_Arming/AP_Arming.h>
56
#include <AP_Logger/AP_Logger.h>
57
#include <AP_GPS/AP_GPS.h>
58
#include <AP_Vehicle/AP_Vehicle.h>
59
#if AP_BARO_THST_COMP_ENABLED
60
#include <AP_Motors/AP_Motors.h>
61
#endif
62
63
#define INTERNAL_TEMPERATURE_CLAMP 35.0f
64
65
#ifndef HAL_BARO_FILTER_DEFAULT
66
#define HAL_BARO_FILTER_DEFAULT 0 // turned off by default
67
#endif
68
69
#ifndef HAL_BARO_PROBE_EXT_DEFAULT
70
#define HAL_BARO_PROBE_EXT_DEFAULT 0
71
#endif
72
73
#ifndef HAL_BARO_EXTERNAL_BUS_DEFAULT
74
#define HAL_BARO_EXTERNAL_BUS_DEFAULT -1
75
#endif
76
77
#ifdef HAL_BUILD_AP_PERIPH
78
#define HAL_BARO_ALLOW_INIT_NO_BARO
79
#endif
80
81
#ifndef AP_FIELD_ELEVATION_ENABLED
82
#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub)
83
#endif
84
85
extern const AP_HAL::HAL& hal;
86
87
// table of user settable parameters
88
const AP_Param::GroupInfo AP_Baro::var_info[] = {
89
// NOTE: Index numbers 0 and 1 were for the old integer
90
// ground temperature and pressure
91
92
#ifndef HAL_BUILD_AP_PERIPH
93
// @Param: 1_GND_PRESS
94
// @DisplayName: Ground Pressure
95
// @Description: calibrated ground pressure in Pascals
96
// @Units: Pa
97
// @Increment: 1
98
// @ReadOnly: True
99
// @Volatile: True
100
// @User: Advanced
101
AP_GROUPINFO_FLAGS("1_GND_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
102
103
// @Param: _GND_TEMP
104
// @DisplayName: ground temperature
105
// @Description: User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature.
106
// @Units: degC
107
// @Increment: 1
108
// @Volatile: True
109
// @User: Advanced
110
AP_GROUPINFO("_GND_TEMP", 3, AP_Baro, _user_ground_temperature, 0),
111
112
// index 4 reserved for old AP_Int8 version in legacy FRAM
113
//AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),
114
115
// @Param: _ALT_OFFSET
116
// @DisplayName: altitude offset
117
// @Description: altitude offset in meters added to barometric altitude. This is used to allow for automatic adjustment of the base barometric altitude by a ground station equipped with a barometer. The value is added to the barometric altitude read by the aircraft. It is automatically reset to 0 when the barometer is calibrated on each reboot or when a preflight calibration is performed.
118
// @Units: m
119
// @Increment: 0.1
120
// @User: Advanced
121
AP_GROUPINFO("_ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
122
123
// @Param: _PRIMARY
124
// @DisplayName: Primary barometer
125
// @Description: This selects which barometer will be the primary if multiple barometers are found
126
// @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
127
// @User: Advanced
128
AP_GROUPINFO("_PRIMARY", 6, AP_Baro, _primary_baro, 0),
129
#endif // HAL_BUILD_AP_PERIPH
130
131
// @Param: _EXT_BUS
132
// @DisplayName: External baro bus
133
// @Description: This selects the bus number for looking for an I2C barometer. When set to -1 it will probe all external i2c buses based on the BARO_PROBE_EXT parameter.
134
// @Values: -1:Disabled,0:Bus0,1:Bus1,6:Bus6
135
// @User: Advanced
136
AP_GROUPINFO("_EXT_BUS", 7, AP_Baro, _ext_bus, HAL_BARO_EXTERNAL_BUS_DEFAULT),
137
138
// @Param{Sub}: _SPEC_GRAV
139
// @DisplayName: Specific Gravity (For water depth measurement)
140
// @Description: This sets the specific gravity of the fluid when flying an underwater ROV.
141
// @Values: 1.0:Freshwater,1.024:Saltwater
142
// @Range: 0.98 1.05
143
AP_GROUPINFO_FRAME("_SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
144
145
#if BARO_MAX_INSTANCES > 1
146
// @Param: 2_GND_PRESS
147
// @DisplayName: Ground Pressure
148
// @Description: calibrated ground pressure in Pascals
149
// @Units: Pa
150
// @Increment: 1
151
// @ReadOnly: True
152
// @Volatile: True
153
// @User: Advanced
154
AP_GROUPINFO_FLAGS("2_GND_PRESS", 9, AP_Baro, sensors[1].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
155
156
// Slot 10 used to be TEMP2
157
#endif
158
159
#if BARO_MAX_INSTANCES > 2
160
// @Param: 3_GND_PRESS
161
// @DisplayName: Absolute Pressure
162
// @Description: calibrated ground pressure in Pascals
163
// @Units: Pa
164
// @Increment: 1
165
// @ReadOnly: True
166
// @Volatile: True
167
// @User: Advanced
168
AP_GROUPINFO_FLAGS("3_GND_PRESS", 11, AP_Baro, sensors[2].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
169
170
// Slot 12 used to be TEMP3
171
#endif
172
173
// @Param: _FLTR_RNG
174
// @DisplayName: Range in which sample is accepted
175
// @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
176
// @Units: %
177
// @Range: 0 100
178
// @Increment: 1
179
AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
180
181
#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED
182
// @Param: _PROBE_EXT
183
// @DisplayName: External barometers to probe
184
// @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on BARO_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in BARO_EXT_BUS.
185
// @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP,13:BMP581,14:AUAV
186
// @User: Advanced
187
AP_GROUPINFO("_PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),
188
#endif
189
190
// @Param: 1_DEVID
191
// @DisplayName: Baro ID
192
// @Description: Barometer sensor ID, taking into account its type, bus and instance
193
// @ReadOnly: True
194
// @User: Advanced
195
AP_GROUPINFO_FLAGS("1_DEVID", 15, AP_Baro, sensors[0].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
196
197
#if BARO_MAX_INSTANCES > 1
198
// @Param: 2_DEVID
199
// @DisplayName: Baro ID2
200
// @Description: Barometer2 sensor ID, taking into account its type, bus and instance
201
// @ReadOnly: True
202
// @User: Advanced
203
AP_GROUPINFO_FLAGS("2_DEVID", 16, AP_Baro, sensors[1].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
204
#endif
205
206
#if BARO_MAX_INSTANCES > 2
207
// @Param: 3_DEVID
208
// @DisplayName: Baro ID3
209
// @Description: Barometer3 sensor ID, taking into account its type, bus and instance
210
// @ReadOnly: True
211
// @User: Advanced
212
AP_GROUPINFO_FLAGS("3_DEVID", 17, AP_Baro, sensors[2].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
213
#endif
214
215
#if HAL_BARO_WIND_COMP_ENABLED
216
// @Group: 1_WCF_
217
// @Path: AP_Baro_Wind.cpp
218
AP_SUBGROUPINFO(sensors[0].wind_coeff, "1_WCF_", 18, AP_Baro, WindCoeff),
219
220
#if BARO_MAX_INSTANCES > 1
221
// @Group: 2_WCF_
222
// @Path: AP_Baro_Wind.cpp
223
AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff),
224
#endif
225
#if BARO_MAX_INSTANCES > 2
226
// @Group: 3_WCF_
227
// @Path: AP_Baro_Wind.cpp
228
AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff),
229
#endif
230
#endif // HAL_BARO_WIND_COMP_ENABLED
231
232
#if AP_FIELD_ELEVATION_ENABLED
233
// @Param: _FIELD_ELV
234
// @DisplayName: field elevation
235
// @Description: User provided field elevation in meters. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level.
236
// @Units: m
237
// @Increment: 0.1
238
// @Volatile: True
239
// @User: Advanced
240
AP_GROUPINFO("_FIELD_ELV", 22, AP_Baro, _field_elevation, 0),
241
#endif
242
243
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
244
// @Param: _ALTERR_MAX
245
// @DisplayName: Altitude error maximum
246
// @Description: This is the maximum acceptable altitude discrepancy between GPS altitude and barometric presssure altitude calculated against a standard atmosphere for arming checks to pass. If you are getting an arming error due to this parameter then you may have a faulty or substituted barometer. A common issue is vendors replacing a MS5611 in a "Pixhawk" with a MS5607. If you have that issue then please see BARO_OPTIONS parameter to force the MS5611 to be treated as a MS5607. This check is disabled if the value is zero.
247
// @Units: m
248
// @Increment: 1
249
// @Range: 0 5000
250
// @User: Advanced
251
AP_GROUPINFO("_ALTERR_MAX", 23, AP_Baro, _alt_error_max, 2000),
252
253
// @Param: _OPTIONS
254
// @DisplayName: Barometer options
255
// @Description: Barometer options
256
// @Bitmask: 0:Treat MS5611 as MS5607
257
// @User: Advanced
258
AP_GROUPINFO("_OPTIONS", 24, AP_Baro, _options, 0),
259
#endif
260
261
#if AP_BARO_THST_COMP_ENABLED
262
// @Param: 1_THST_SCALE
263
// @DisplayName: Thrust compensation
264
// @Description: Thrust scaling in Pascals. This value scaled by the normalized thrust is subtracted from the barometer pressure. This is used to adjust linearly based on the thrust output for local pressure difference induced by the props.
265
// @Range: -300 300
266
// @User: Advanced
267
AP_GROUPINFO("1_THST_SCALE", 25, AP_Baro, sensors[0].mot_scale, 0),
268
#endif // AP_BARO_THST_COMP_ENABLED
269
AP_GROUPEND
270
};
271
272
// singleton instance
273
AP_Baro *AP_Baro::_singleton;
274
275
/*
276
AP_Baro constructor
277
*/
278
AP_Baro::AP_Baro()
279
{
280
_singleton = this;
281
282
AP_Param::setup_object_defaults(this, var_info);
283
_field_elevation_active = _field_elevation;
284
}
285
286
// calibrate the barometer. This must be called at least once before
287
// the altitude() or climb_rate() interfaces can be used
288
void AP_Baro::calibrate(bool save)
289
{
290
// start by assuming all sensors are calibrated (for healthy() test)
291
for (uint8_t i=0; i<_num_sensors; i++) {
292
sensors[i].calibrated = true;
293
sensors[i].alt_ok = true;
294
}
295
296
if (hal.util->was_watchdog_reset()) {
297
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset");
298
return;
299
}
300
301
#if AP_SIM_BARO_ENABLED
302
if (AP::sitl()->baro_count == 0) {
303
return;
304
}
305
#endif
306
307
#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
308
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
309
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");
310
return;
311
}
312
#endif
313
314
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");
315
316
// reset the altitude offset when we calibrate. The altitude
317
// offset is supposed to be for within a flight
318
_alt_offset.set_and_save(0);
319
320
// let the barometer settle for a full second after startup
321
// the MS5611 reads quite a long way off for the first second,
322
// leading to about 1m of error if we don't wait
323
for (uint8_t i = 0; i < 10; i++) {
324
uint32_t tstart = AP_HAL::millis();
325
do {
326
update();
327
if (AP_HAL::millis() - tstart > 500) {
328
AP_BoardConfig::config_error("Baro: unable to calibrate");
329
}
330
hal.scheduler->delay(10);
331
} while (!healthy());
332
hal.scheduler->delay(100);
333
}
334
335
// now average over 5 values for the ground pressure settings
336
float sum_pressure[BARO_MAX_INSTANCES] = {0};
337
uint8_t count[BARO_MAX_INSTANCES] = {0};
338
const uint8_t num_samples = 5;
339
340
for (uint8_t c = 0; c < num_samples; c++) {
341
uint32_t tstart = AP_HAL::millis();
342
do {
343
update();
344
if (AP_HAL::millis() - tstart > 500) {
345
AP_BoardConfig::config_error("Baro: unable to calibrate");
346
}
347
} while (!healthy());
348
for (uint8_t i=0; i<_num_sensors; i++) {
349
if (healthy(i)) {
350
sum_pressure[i] += sensors[i].pressure;
351
count[i] += 1;
352
}
353
}
354
hal.scheduler->delay(100);
355
}
356
for (uint8_t i=0; i<_num_sensors; i++) {
357
if (count[i] == 0) {
358
sensors[i].calibrated = false;
359
} else {
360
if (save) {
361
float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i], _field_elevation_active);
362
sensors[i].ground_pressure.set_and_save(p0_sealevel);
363
}
364
}
365
}
366
367
_guessed_ground_temperature = get_external_temperature();
368
369
// panic if all sensors are not calibrated
370
uint8_t num_calibrated = 0;
371
for (uint8_t i=0; i<_num_sensors; i++) {
372
if (sensors[i].calibrated) {
373
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);
374
num_calibrated++;
375
}
376
}
377
if (num_calibrated) {
378
return;
379
}
380
AP_BoardConfig::config_error("Baro: all sensors uncalibrated");
381
}
382
383
/*
384
update the barometer calibration
385
this updates the baro ground calibration to the current values. It
386
can be used before arming to keep the baro well calibrated
387
*/
388
void AP_Baro::update_calibration()
389
{
390
const uint32_t now = AP_HAL::millis();
391
const bool do_notify = now - _last_notify_ms > 10000;
392
if (do_notify) {
393
_last_notify_ms = now;
394
}
395
for (uint8_t i=0; i<_num_sensors; i++) {
396
if (healthy(i)) {
397
float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction, _field_elevation_active);
398
sensors[i].ground_pressure.set(corrected_pressure);
399
}
400
401
// don't notify the GCS too rapidly or we flood the link
402
if (do_notify) {
403
sensors[i].ground_pressure.notify();
404
}
405
}
406
407
// always update the guessed ground temp
408
_guessed_ground_temperature = get_external_temperature();
409
}
410
411
412
// return air density / sea level density - decreases as altitude climbs
413
float AP_Baro::_get_air_density_ratio(void)
414
{
415
const float eas2tas = _get_EAS2TAS();
416
if (eas2tas > 0.0f) {
417
return 1.0f/(sq(eas2tas));
418
} else {
419
return 1.0f;
420
}
421
}
422
423
// return current climb_rate estimate relative to time that calibrate()
424
// was called. Returns climb rate in meters/s, positive means up
425
// note that this relies on read() being called regularly to get new data
426
float AP_Baro::get_climb_rate(void)
427
{
428
// we use a 7 point derivative filter on the climb rate. This seems
429
// to produce somewhat reasonable results on real hardware
430
return _climb_rate_filter.slope() * 1.0e3f;
431
}
432
433
// returns the ground temperature in degrees C, selecting either a user
434
// provided one, or the internal estimate
435
float AP_Baro::get_ground_temperature(void) const
436
{
437
if (is_zero(_user_ground_temperature)) {
438
return _guessed_ground_temperature;
439
} else {
440
return _user_ground_temperature;
441
}
442
}
443
444
445
/*
446
set external temperature to be used for calibration (degrees C)
447
*/
448
void AP_Baro::set_external_temperature(float temperature)
449
{
450
_external_temperature = temperature;
451
_last_external_temperature_ms = AP_HAL::millis();
452
}
453
454
/*
455
get the temperature in degrees C to be used for calibration purposes
456
*/
457
float AP_Baro::get_external_temperature(const uint8_t instance) const
458
{
459
// if we have a recent external temperature then use it
460
if (_last_external_temperature_ms != 0 && AP_HAL::millis() - _last_external_temperature_ms < 10000) {
461
return _external_temperature;
462
}
463
464
#ifndef HAL_BUILD_AP_PERIPH
465
#if AP_AIRSPEED_ENABLED
466
// if we don't have an external temperature then try to use temperature
467
// from the airspeed sensor
468
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
469
if (airspeed != nullptr) {
470
float temperature;
471
if (airspeed->healthy() && airspeed->get_temperature(temperature)) {
472
return temperature;
473
}
474
}
475
#endif
476
#endif
477
478
// if we don't have an external temperature and airspeed temperature
479
// then use the minimum of the barometer temperature and 35 degrees C.
480
// The reason for not just using the baro temperature is it tends to read high,
481
// often 30 degrees above the actual temperature. That means the
482
// EAS2TAS tends to be off by quite a large margin, as well as
483
// the calculation of altitude difference between two pressures
484
// reporting a high temperature will cause the aircraft to
485
// estimate itself as flying higher then it actually is.
486
return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);
487
}
488
489
490
bool AP_Baro::_add_backend(AP_Baro_Backend *backend)
491
{
492
if (!backend) {
493
return false;
494
}
495
if (_num_drivers >= ARRAY_SIZE(drivers)) {
496
AP_HAL::panic("Too many barometer drivers");
497
}
498
drivers[_num_drivers++] = backend;
499
return true;
500
}
501
502
/*
503
wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened
504
*/
505
bool AP_Baro::_i2c_sensor_is_registered(uint8_t bus, uint8_t address) const
506
{
507
for (int i=0; i<_num_sensors; ++i) {
508
if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==
509
AP_HAL::Device::change_bus_id(uint32_t(sensors[i].bus_id.get()), 0)) {
510
// device already has been defined.
511
return true;
512
}
513
}
514
return false;
515
}
516
517
#define RETURN_IF_NO_SPACE \
518
do { \
519
if (_num_drivers == BARO_MAX_DRIVERS || \
520
_num_sensors == BARO_MAX_INSTANCES) { \
521
return; \
522
} \
523
} while (0)
524
525
// macro for use by HAL_INS_PROBE_LIST and various helper functions
526
#define GET_I2C_DEVICE_PTR(bus, address) _i2c_sensor_is_registered(bus, address)?nullptr:hal.i2c_mgr->get_device_ptr(bus, address)
527
528
// probe for an I2C barometer.
529
void AP_Baro::probe_i2c_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), uint8_t bus, uint8_t addr)
530
{
531
auto *dev = GET_I2C_DEVICE_PTR(bus, addr); // dev may be freed by probe_dev
532
probe_dev(probefn, dev);
533
}
534
535
// probe for an I2C barometer
536
void AP_Baro::probe_spi_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), const char *name)
537
{
538
auto *dev = hal.spi->get_device_ptr(name); // dev may be freed by probe_dev
539
probe_dev(probefn, dev);
540
}
541
542
// see if Device dev exists. If it does not delete it.
543
void AP_Baro::probe_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), AP_HAL::Device *dev)
544
{
545
if (dev == nullptr) {
546
return;
547
}
548
AP_Baro_Backend *backend = probefn(*this, *dev);
549
if (backend == nullptr) {
550
delete dev;
551
return;
552
}
553
if (!_add_backend(backend)) {
554
delete backend;
555
delete dev;
556
return;
557
}
558
}
559
560
#if AP_BARO_LPS2XH_ENABLED
561
void AP_Baro::probe_lps2xh_via_Invensense_IMU(uint8_t bus, uint8_t addr, uint8_t mpu_addr)
562
{
563
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
564
AP_Baro_Backend *backend = AP_Baro_LPS2XH::probe_InvensenseIMU(*this, *i2c_dev, mpu_addr);
565
if (!_add_backend(backend)) {
566
delete i2c_dev;
567
}
568
}
569
#endif // AP_BARO_LPS2XH_ENABLED
570
571
#if AP_BARO_ICM20789_ENABLED
572
void AP_Baro::probe_icm20789(uint8_t bus, uint8_t addr, uint8_t mpu_bus, uint8_t mpu_addr)
573
{
574
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
575
AP_HAL::I2CDevice *mpu_dev = GET_I2C_DEVICE_PTR(mpu_bus, mpu_addr);
576
_probe_icm20789(i2c_dev, mpu_dev); // deletes devices on failure
577
}
578
579
void AP_Baro::probe_icm20789(uint8_t bus, uint8_t addr, const char *mpu_name)
580
{
581
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
582
AP_HAL::SPIDevice *mpu_dev = hal.spi->get_device_ptr(mpu_name);
583
_probe_icm20789(i2c_dev, mpu_dev); // deletes devices on failure
584
}
585
586
// convenience underlying method for other probe functions;
587
// will. delete the passed-in devices if a backend is not found
588
void AP_Baro::_probe_icm20789(AP_HAL::I2CDevice *i2c_dev, AP_HAL::Device *mpu_dev)
589
{
590
if (i2c_dev == nullptr) {
591
return;
592
}
593
if (mpu_dev == nullptr) {
594
delete i2c_dev;
595
return;
596
}
597
AP_Baro_Backend *backend = AP_Baro_ICM20789::probe(*this, *i2c_dev, *mpu_dev);
598
if (!_add_backend(backend)) {
599
delete i2c_dev;
600
delete mpu_dev;
601
}
602
}
603
#endif // AP_BARO_ICM20789_ENABLED
604
605
/*
606
initialise the barometer object, loading backend drivers
607
*/
608
void AP_Baro::init(void)
609
{
610
init_done = true;
611
612
// always set field elevation to zero on reboot in the case user
613
// fails to update. TBD automate sanity checking error bounds on
614
// on previously saved value at new location etc.
615
if (!is_zero(_field_elevation)) {
616
_field_elevation.set_and_save(0.0f);
617
_field_elevation.notify();
618
}
619
620
// zero bus IDs before probing
621
for (auto &sensor : sensors) {
622
sensor.bus_id.set(0);
623
}
624
625
#if AP_SIM_BARO_ENABLED
626
SITL::SIM *sitl = AP::sitl();
627
if (sitl == nullptr) {
628
AP_HAL::panic("No SITL pointer");
629
}
630
#if !AP_TEST_DRONECAN_DRIVERS
631
// use dronecan instances instead of SITL instances
632
for(uint8_t i = 0; i < sitl->baro_count; i++) {
633
_add_backend(NEW_NOTHROW AP_Baro_SITL(*this));
634
RETURN_IF_NO_SPACE;
635
}
636
#endif
637
#endif
638
639
#if AP_BARO_DRONECAN_ENABLED
640
// Detect UAVCAN Modules, try as many times as there are driver slots
641
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
642
_add_backend(AP_Baro_DroneCAN::probe(*this));
643
RETURN_IF_NO_SPACE;
644
}
645
#endif
646
647
#if AP_BARO_EXTERNALAHRS_ENABLED
648
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO);
649
if (serial_port >= 0) {
650
_add_backend(NEW_NOTHROW AP_Baro_ExternalAHRS(*this, serial_port));
651
RETURN_IF_NO_SPACE;
652
}
653
#endif
654
655
#if AP_SIM_BARO_ENABLED
656
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_BARO_MS5611_ENABLED
657
probe_i2c_dev(AP_Baro_MS5611::probe, _ext_bus, HAL_BARO_MS5611_I2C_ADDR);
658
RETURN_IF_NO_SPACE;
659
#endif
660
// do not probe for other drivers when using simulation:
661
return;
662
#endif
663
664
#if defined(HAL_BARO_PROBE_LIST)
665
// probe list from BARO lines in hwdef.dat
666
HAL_BARO_PROBE_LIST;
667
#elif AP_FEATURE_BOARD_DETECT
668
switch (AP_BoardConfig::get_board_type()) {
669
case AP_BoardConfig::PX4_BOARD_PX4V1:
670
#if AP_BARO_MS5611_ENABLED && defined(HAL_BARO_MS5611_I2C_BUS)
671
probe_i2c_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR);
672
RETURN_IF_NO_SPACE;
673
#endif
674
break;
675
676
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
677
case AP_BoardConfig::PX4_BOARD_PHMINI:
678
case AP_BoardConfig::PX4_BOARD_AUAV21:
679
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
680
case AP_BoardConfig::PX4_BOARD_FMUV6:
681
#if AP_BARO_MS5611_ENABLED
682
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_NAME);
683
RETURN_IF_NO_SPACE;
684
#endif
685
break;
686
687
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
688
#if AP_BARO_MS5611_ENABLED
689
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_SPI_EXT_NAME);
690
RETURN_IF_NO_SPACE;
691
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_NAME);
692
RETURN_IF_NO_SPACE;
693
#endif
694
break;
695
696
case AP_BoardConfig::PX4_BOARD_AEROFC:
697
#if AP_BARO_MS5607_ENABLED
698
#ifdef HAL_BARO_MS5607_I2C_BUS
699
probe_i2c_dev(AP_Baro_MS5607::probe, HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR);
700
RETURN_IF_NO_SPACE;
701
#endif
702
#endif // AP_BARO_MS5607_ENABLED
703
break;
704
705
default:
706
break;
707
}
708
#endif // defined(HAL_BARO_PROBE_LIST) / AP_FEATURE_BOARD_DETECT
709
710
// can optionally have baro on I2C too
711
if (_ext_bus >= 0) {
712
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
713
#if AP_BARO_MS5837_ENABLED
714
probe_i2c_dev(AP_Baro_MS5837::probe, _ext_bus, HAL_BARO_MS5837_I2C_ADDR);
715
RETURN_IF_NO_SPACE;
716
#endif
717
#if AP_BARO_KELLERLD_ENABLED
718
probe_i2c_dev(AP_Baro_KellerLD::probe, _ext_bus, HAL_BARO_KELLERLD_I2C_ADDR);
719
RETURN_IF_NO_SPACE;
720
#endif
721
#else
722
#if AP_BARO_MS5611_ENABLED
723
probe_i2c_dev(AP_Baro_MS5611::probe, _ext_bus, HAL_BARO_MS5611_I2C_ADDR);
724
RETURN_IF_NO_SPACE;
725
#endif
726
#endif
727
}
728
729
#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES
730
_probe_i2c_barometers();
731
RETURN_IF_NO_SPACE;
732
#endif
733
734
#if AP_BARO_MSP_ENABLED
735
if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) {
736
// allow for late addition of MSP sensor
737
msp_instance_mask |= 1;
738
}
739
for (uint8_t i=0; i<8; i++) {
740
if (msp_instance_mask & (1U<<i)) {
741
_add_backend(NEW_NOTHROW AP_Baro_MSP(*this, i));
742
RETURN_IF_NO_SPACE;
743
}
744
}
745
#endif
746
747
#if !defined(HAL_BARO_ALLOW_INIT_NO_BARO) // most boards requires external baro
748
#if AP_SIM_BARO_ENABLED
749
if (sitl->baro_count == 0) {
750
return;
751
}
752
#endif
753
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
754
AP_BoardConfig::config_error("Baro: unable to initialise driver");
755
}
756
#endif
757
#ifdef HAL_BUILD_AP_PERIPH
758
// AP_Periph always is set calibrated. We only want the pressure,
759
// so ground calibration is unnecessary
760
for (uint8_t i=0; i<_num_sensors; i++) {
761
sensors[i].calibrated = true;
762
sensors[i].alt_ok = true;
763
}
764
#endif
765
}
766
767
#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES
768
/*
769
probe all the i2c barometers enabled with BARO_PROBE_EXT. This is
770
used on boards without a builtin barometer
771
*/
772
void AP_Baro::_probe_i2c_barometers(void)
773
{
774
uint32_t probe = _baro_probe_ext.get();
775
(void)probe; // may be unused if most baros compiled out
776
uint32_t mask = hal.i2c_mgr->get_bus_mask_external();
777
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
778
// for the purpose of baro probing, treat CubeBlack internal i2c as external. It has
779
// no internal i2c baros, so this is safe
780
mask |= hal.i2c_mgr->get_bus_mask_internal();
781
}
782
// if the user has set BARO_EXT_BUS then probe the bus given by that parameter
783
int8_t ext_bus = _ext_bus;
784
if (ext_bus >= 0) {
785
mask = 1U << (uint8_t)ext_bus;
786
}
787
788
static const struct BaroProbeSpec {
789
uint32_t bit;
790
AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&);
791
uint8_t addr;
792
} baroprobespec[] {
793
#if AP_BARO_BMP085_ENABLED
794
{ PROBE_BMP085, AP_Baro_BMP085::probe, HAL_BARO_BMP085_I2C_ADDR },
795
#endif
796
#if AP_BARO_BMP280_ENABLED
797
{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR },
798
{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR2 },
799
#endif
800
#if AP_BARO_SPL06_ENABLED
801
{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR },
802
{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR2 },
803
#endif
804
#if AP_BARO_BMP388_ENABLED
805
{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR },
806
{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR2 },
807
#endif
808
#if AP_BARO_BMP581_ENABLED
809
{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR },
810
{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR2 },
811
#endif
812
#if AP_BARO_MS5611_ENABLED
813
{ PROBE_MS5611, AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_ADDR },
814
{ PROBE_MS5611, AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_ADDR2 },
815
#endif // AP_BARO_MS5611_ENABLED
816
#if AP_BARO_MS5607_ENABLED
817
{ PROBE_MS5607, AP_Baro_MS5607::probe, HAL_BARO_MS5607_I2C_ADDR },
818
#endif // AP_BARO_MS5607_ENABLED
819
#if AP_BARO_MS5637_ENABLED
820
{ PROBE_MS5637, AP_Baro_MS5637::probe, HAL_BARO_MS5637_I2C_ADDR },
821
#endif // AP_BARO_MS5637_ENABLED
822
#if AP_BARO_FBM320_ENABLED
823
{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR },
824
{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR2 },
825
#endif
826
#if AP_BARO_DPS280_ENABLED
827
{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR },
828
{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR2 },
829
#endif
830
#if AP_BARO_LPS2XH_ENABLED
831
{ PROBE_LPS25H, AP_Baro_LPS2XH::probe, HAL_BARO_LPS25H_I2C_ADDR },
832
#endif
833
#if AP_BARO_AUAV_ENABLED
834
{ PROBE_AUAV, AP_Baro_AUAV::probe, HAL_BARO_AUAV_I2C_ADDR },
835
#endif
836
837
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
838
#if AP_BARO_KELLERLD_ENABLED
839
{ PROBE_KELLER, AP_Baro_KellerLD::probe, HAL_BARO_KELLERLD_I2C_ADDR },
840
#endif
841
#if AP_BARO_MS5837_ENABLED
842
{ PROBE_MS5837, AP_Baro_MS5837::probe, HAL_BARO_MS5837_I2C_ADDR },
843
#endif
844
#endif // APM_BUILD_TYPE(APM_BUILD_ArduSub)
845
};
846
847
for (const auto &spec : baroprobespec) {
848
if (!(probe & spec.bit)) {
849
// not in mask to be probed for
850
continue;
851
}
852
FOREACH_I2C_MASK(i, mask) {
853
probe_i2c_dev(spec.probefn, i, spec.addr);
854
RETURN_IF_NO_SPACE;
855
}
856
}
857
}
858
#endif // AP_BARO_PROBE_EXTERNAL_I2C_BUSES
859
860
#if HAL_LOGGING_ENABLED
861
bool AP_Baro::should_log() const
862
{
863
AP_Logger *logger = AP_Logger::get_singleton();
864
if (logger == nullptr) {
865
return false;
866
}
867
if (_log_baro_bit == (uint32_t)-1) {
868
return false;
869
}
870
if (!logger->should_log(_log_baro_bit)) {
871
return false;
872
}
873
return true;
874
}
875
#endif
876
877
/*
878
call update on all drivers
879
*/
880
void AP_Baro::update(void)
881
{
882
WITH_SEMAPHORE(_rsem);
883
884
if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
885
// If there's more than 1cm difference then slowly slew to it via LPF.
886
// The EKF does not like step inputs so this keeps it happy.
887
_alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset);
888
} else {
889
_alt_offset_active = _alt_offset;
890
}
891
892
#if HAL_LOGGING_ENABLED
893
bool old_primary_healthy = sensors[_primary].healthy;
894
#endif
895
896
for (uint8_t i=0; i<_num_drivers; i++) {
897
drivers[i]->backend_update(i);
898
}
899
900
for (uint8_t i=0; i<_num_sensors; i++) {
901
if (sensors[i].healthy) {
902
// update altitude calculation
903
float ground_pressure = sensors[i].ground_pressure;
904
if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
905
sensors[i].ground_pressure.set(sensors[i].pressure);
906
}
907
float altitude = sensors[i].altitude;
908
float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;
909
if (sensors[i].type == BARO_TYPE_AIR) {
910
#if HAL_BARO_WIND_COMP_ENABLED
911
corrected_pressure -= wind_pressure_correction(i);
912
#endif
913
#if AP_BARO_THST_COMP_ENABLED
914
corrected_pressure -= thrust_pressure_correction(i);
915
#endif
916
#if (HAL_BARO_WIND_COMP_ENABLED || AP_BARO_THST_COMP_ENABLED)
917
sensors[i].corrected_pressure = corrected_pressure;
918
#endif
919
altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure);
920
921
// the ground pressure is references against the field elevation
922
altitude -= _field_elevation_active;
923
} else if (sensors[i].type == BARO_TYPE_WATER) {
924
//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
925
//No temperature or depth compensation for density of water.
926
altitude = (sensors[i].ground_pressure - corrected_pressure) / 9800.0f / _specific_gravity;
927
}
928
// sanity check altitude
929
sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));
930
if (sensors[i].alt_ok) {
931
sensors[i].altitude = altitude + _alt_offset_active;
932
}
933
}
934
}
935
936
// ensure the climb rate filter is updated
937
if (healthy()) {
938
_climb_rate_filter.update(get_altitude(), get_last_update());
939
}
940
941
// choose primary sensor
942
if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {
943
_primary = _primary_baro;
944
} else {
945
_primary = 0;
946
for (uint8_t i=0; i<_num_sensors; i++) {
947
if (healthy(i)) {
948
_primary = i;
949
break;
950
}
951
}
952
}
953
#if AP_FIELD_ELEVATION_ENABLED
954
update_field_elevation();
955
#endif
956
957
// logging
958
#if HAL_LOGGING_ENABLED
959
if (should_log()) {
960
Write_Baro();
961
}
962
963
#define MASK_LOG_ANY 0xFFFF
964
965
// log sensor healthy state change:
966
if (sensors[_primary].healthy != old_primary_healthy) {
967
if (AP::logger().should_log(MASK_LOG_ANY)) {
968
const LogErrorCode code = sensors[_primary].healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;
969
AP::logger().Write_Error(LogErrorSubsystem::BARO, code);
970
}
971
}
972
#endif
973
}
974
975
#ifdef HAL_BUILD_AP_PERIPH
976
// calibration and alt check not valid for AP_Periph
977
bool AP_Baro::healthy(uint8_t instance) const {
978
// If the requested instance was outside max instances it is not healthy (it doesn't exist)
979
if (instance >= BARO_MAX_INSTANCES) {
980
return false;
981
}
982
return sensors[instance].healthy;
983
}
984
#else
985
bool AP_Baro::healthy(uint8_t instance) const {
986
// If the requested instance was outside max instances it is not healthy (it doesn't exist)
987
if (instance >= BARO_MAX_INSTANCES) {
988
return false;
989
}
990
return sensors[instance].healthy && sensors[instance].alt_ok && sensors[instance].calibrated;
991
}
992
#endif
993
994
/*
995
update field elevation value
996
*/
997
void AP_Baro::update_field_elevation(void)
998
{
999
#if AP_FIELD_ELEVATION_ENABLED
1000
const uint32_t now_ms = AP_HAL::millis();
1001
bool new_field_elev = false;
1002
const bool armed = hal.util->get_soft_armed();
1003
if (now_ms - _field_elevation_last_ms >= 1000) {
1004
if (is_zero(_field_elevation_active) &&
1005
is_zero(_field_elevation)) {
1006
// auto-set based on origin
1007
Location origin;
1008
if (!armed && AP::ahrs().get_origin(origin)) {
1009
_field_elevation_active = origin.alt * 0.01;
1010
if (is_zero(_field_elevation_active)) {
1011
_field_elevation_active = 0.001f; // prevent zero value so that we don't keep trying to auto-set
1012
}
1013
new_field_elev = true;
1014
}
1015
} else if (fabsf(_field_elevation_active-_field_elevation) > 1.0 &&
1016
!is_zero(_field_elevation)) {
1017
// user has set field elevation
1018
if (!armed) {
1019
_field_elevation_active = _field_elevation;
1020
new_field_elev = true;
1021
} else {
1022
_field_elevation.set(_field_elevation_active);
1023
_field_elevation.notify();
1024
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed");
1025
}
1026
}
1027
}
1028
if (new_field_elev && !armed) {
1029
_field_elevation_last_ms = now_ms;
1030
AP::ahrs().resetHeightDatum();
1031
update_calibration();
1032
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active);
1033
}
1034
#endif
1035
}
1036
1037
#if AP_BARO_THST_COMP_ENABLED
1038
// scale the baro linearly with thrust
1039
float AP_Baro::thrust_pressure_correction(uint8_t instance)
1040
{
1041
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_COPTER_OR_HELI
1042
const AP_Motors* motors = AP::motors();
1043
if (motors == nullptr) {
1044
return 0.0f;
1045
}
1046
const float motors_throttle = MAX(0,motors->get_throttle_out());
1047
return sensors[instance].mot_scale * motors_throttle;
1048
#else
1049
return 0.0f;
1050
#endif
1051
}
1052
#endif
1053
1054
/* register a new sensor, claiming a sensor slot. If we are out of
1055
slots it will panic
1056
*/
1057
uint8_t AP_Baro::register_sensor(void)
1058
{
1059
if (_num_sensors >= ARRAY_SIZE(sensors)) {
1060
AP_HAL::panic("Too many barometers");
1061
}
1062
return _num_sensors++;
1063
}
1064
1065
1066
/*
1067
check if all barometers are healthy
1068
*/
1069
bool AP_Baro::all_healthy(void) const
1070
{
1071
for (uint8_t i=0; i<_num_sensors; i++) {
1072
if (!healthy(i)) {
1073
return false;
1074
}
1075
}
1076
return _num_sensors > 0;
1077
}
1078
1079
// set a pressure correction from AP_TempCalibration
1080
void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
1081
{
1082
if (instance < _num_sensors) {
1083
sensors[instance].p_correction = p_correction;
1084
}
1085
}
1086
1087
#if AP_BARO_MSP_ENABLED
1088
/*
1089
handle MSP barometer data
1090
*/
1091
void AP_Baro::handle_msp(const MSP::msp_baro_data_message_t &pkt)
1092
{
1093
if (pkt.instance > 7) {
1094
return;
1095
}
1096
if (!init_done) {
1097
msp_instance_mask |= 1U<<pkt.instance;
1098
} else if (msp_instance_mask != 0) {
1099
for (uint8_t i=0; i<_num_drivers; i++) {
1100
drivers[i]->handle_msp(pkt);
1101
}
1102
}
1103
}
1104
#endif
1105
1106
#if AP_BARO_EXTERNALAHRS_ENABLED
1107
/*
1108
handle ExternalAHRS barometer data
1109
*/
1110
void AP_Baro::handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt)
1111
{
1112
for (uint8_t i=0; i<_num_drivers; i++) {
1113
drivers[i]->handle_external(pkt);
1114
}
1115
}
1116
#endif // AP_BARO_EXTERNALAHRS_ENABLED
1117
1118
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
1119
bool AP_Baro::arming_checks(size_t buflen, char *buffer) const
1120
{
1121
if (!all_healthy()) {
1122
hal.util->snprintf(buffer, buflen, "not healthy");
1123
return false;
1124
}
1125
1126
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1127
/*
1128
check for a pressure altitude discrepancy between GPS alt and
1129
baro alt this catches bad barometers, such as when a MS5607 has
1130
been substituted for a MS5611
1131
*/
1132
const auto &gps = AP::gps();
1133
if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) {
1134
const float alt_amsl = gps.location().alt*0.01;
1135
// note the addition of _field_elevation_active as this is subtracted in get_altitude_difference()
1136
const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure());
1137
const float error = fabsf(alt_amsl - alt_pressure);
1138
if (error > _alt_error_max) {
1139
hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error);
1140
return false;
1141
}
1142
}
1143
#endif
1144
return true;
1145
}
1146
1147
namespace AP {
1148
1149
AP_Baro &baro()
1150
{
1151
return *AP_Baro::get_singleton();
1152
}
1153
1154
};
1155
1156