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