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.h
Views: 1798
1
#pragma once
2
3
#include "AP_Baro_config.h"
4
5
#include <AP_HAL/AP_HAL.h>
6
#include <AP_Param/AP_Param.h>
7
#include <AP_Math/AP_Math.h>
8
#include <Filter/DerivativeFilter.h>
9
#include <AP_MSP/msp.h>
10
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
11
12
// maximum number of sensor instances
13
#ifndef BARO_MAX_INSTANCES
14
#define BARO_MAX_INSTANCES 3
15
#endif
16
17
// maximum number of drivers. Note that a single driver can provide
18
// multiple sensor instances
19
#define BARO_MAX_DRIVERS 3
20
21
// timeouts for health reporting
22
#define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
23
#define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
24
25
class AP_Baro_Backend;
26
27
class AP_Baro
28
{
29
friend class AP_Baro_Backend;
30
friend class AP_Baro_SITL; // for access to sensors[]
31
friend class AP_Baro_DroneCAN; // for access to sensors[]
32
33
public:
34
AP_Baro();
35
36
/* Do not allow copies */
37
CLASS_NO_COPY(AP_Baro);
38
39
// get singleton
40
static AP_Baro *get_singleton(void) {
41
return _singleton;
42
}
43
44
// barometer types
45
typedef enum {
46
BARO_TYPE_AIR,
47
BARO_TYPE_WATER
48
} baro_type_t;
49
50
// initialise the barometer object, loading backend drivers
51
void init(void);
52
53
// update the barometer object, asking backends to push data to
54
// the frontend
55
void update(void);
56
57
// healthy - returns true if sensor and derived altitude are good
58
bool healthy(void) const { return healthy(_primary); }
59
60
bool healthy(uint8_t instance) const;
61
62
// check if all baros are healthy - used for SYS_STATUS report
63
bool all_healthy(void) const;
64
65
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
66
bool arming_checks(size_t buflen, char *buffer) const;
67
68
// get primary sensor
69
uint8_t get_primary(void) const { return _primary; }
70
71
// pressure in Pascal. Divide by 100 for millibars or hectopascals
72
float get_pressure(void) const { return get_pressure(_primary); }
73
float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
74
#if HAL_BARO_WIND_COMP_ENABLED
75
// dynamic pressure in Pascal. Divide by 100 for millibars or hectopascals
76
const Vector3f& get_dynamic_pressure(uint8_t instance) const { return sensors[instance].dynamic_pressure; }
77
#endif
78
79
// temperature in degrees C
80
float get_temperature(void) const { return get_temperature(_primary); }
81
float get_temperature(uint8_t instance) const { return sensors[instance].temperature; }
82
83
// get pressure correction in Pascal. Divide by 100 for millibars or hectopascals
84
float get_pressure_correction(void) const { return get_pressure_correction(_primary); }
85
float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; }
86
87
// calibrate the barometer. This must be called on startup if the
88
// altitude/climb_rate/acceleration interfaces are ever used
89
void calibrate(bool save=true);
90
91
// update the barometer calibration to the current pressure. Can
92
// be used for incremental preflight update of baro
93
void update_calibration(void);
94
95
// get current altitude in meters relative to altitude at the time
96
// of the last calibrate() call
97
float get_altitude(void) const { return get_altitude(_primary); }
98
float get_altitude(uint8_t instance) const { return sensors[instance].altitude; }
99
100
// get altitude above mean sea level
101
float get_altitude_AMSL(uint8_t instance) const { return get_altitude(instance) + _field_elevation_active; }
102
float get_altitude_AMSL(void) const { return get_altitude_AMSL(_primary); }
103
104
// returns which i2c bus is considered "the" external bus
105
uint8_t external_bus() const { return _ext_bus; }
106
107
// Atmospheric Model Functions
108
static float geometric_alt_to_geopotential(float alt);
109
static float geopotential_alt_to_geometric(float alt);
110
111
float get_temperature_from_altitude(float alt) const;
112
float get_altitude_from_pressure(float pressure) const;
113
114
// EAS2TAS for SITL
115
static float get_EAS2TAS_for_alt_amsl(float alt_amsl);
116
117
#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED
118
// lookup expected pressure for a given altitude. Used for SITL backend
119
static void get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K);
120
#endif
121
122
// lookup expected temperature in degrees C for a given altitude. Used for SITL backend
123
static float get_temperatureC_for_alt_amsl(const float alt_amsl);
124
125
// lookup expected pressure in Pa for a given altitude. Used for SITL backend
126
static float get_pressure_for_alt_amsl(const float alt_amsl);
127
128
// get air density for SITL
129
static float get_air_density_for_alt_amsl(float alt_amsl);
130
131
// get altitude difference in meters relative given a base
132
// pressure in Pascal
133
float get_altitude_difference(float base_pressure, float pressure) const;
134
135
// get sea level pressure relative to 1976 standard atmosphere model
136
// pressure in Pascal
137
float get_sealevel_pressure(float pressure, float altitude) const;
138
139
// get scale factor required to convert equivalent to true
140
// airspeed. This should only be used to update the AHRS value
141
// once per loop. Please use AP::ahrs().get_EAS2TAS()
142
float _get_EAS2TAS(void) const;
143
144
// get air density / sea level density - decreases as altitude climbs
145
// please use AP::ahrs()::get_air_density_ratio()
146
float _get_air_density_ratio(void);
147
148
// get current climb rate in meters/s. A positive number means
149
// going up
150
float get_climb_rate(void);
151
152
// ground temperature in degrees C
153
// the ground values are only valid after calibration
154
float get_ground_temperature(void) const;
155
156
// ground pressure in Pascal
157
// the ground values are only valid after calibration
158
float get_ground_pressure(void) const { return get_ground_pressure(_primary); }
159
float get_ground_pressure(uint8_t i) const { return sensors[i].ground_pressure.get(); }
160
161
// set the temperature to be used for altitude calibration. This
162
// allows an external temperature source (such as a digital
163
// airspeed sensor) to be used as the temperature source
164
void set_external_temperature(float temperature);
165
166
// get last time sample was taken (in ms)
167
uint32_t get_last_update(void) const { return get_last_update(_primary); }
168
uint32_t get_last_update(uint8_t instance) const { return sensors[instance].last_update_ms; }
169
170
// settable parameters
171
static const struct AP_Param::GroupInfo var_info[];
172
173
float get_external_temperature(void) const { return get_external_temperature(_primary); };
174
float get_external_temperature(const uint8_t instance) const;
175
176
// Set the primary baro
177
void set_primary_baro(uint8_t primary) { _primary_baro.set_and_save(primary); };
178
179
// Set the type (Air or Water) of a particular instance
180
void set_type(uint8_t instance, baro_type_t type) { sensors[instance].type = type; };
181
182
// Get the type (Air or Water) of a particular instance
183
baro_type_t get_type(uint8_t instance) { return sensors[instance].type; };
184
185
// register a new sensor, claiming a sensor slot. If we are out of
186
// slots it will panic
187
uint8_t register_sensor(void);
188
189
// return number of registered sensors
190
uint8_t num_instances(void) const { return _num_sensors; }
191
192
// set baro drift amount
193
void set_baro_drift_altitude(float alt) { _alt_offset.set(alt); }
194
195
// get baro drift amount
196
float get_baro_drift_offset(void) const { return _alt_offset_active; }
197
198
// simple underwater atmospheric model
199
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta);
200
201
// set a pressure correction from AP_TempCalibration
202
void set_pressure_correction(uint8_t instance, float p_correction);
203
204
uint8_t get_filter_range() const { return _filter_range; }
205
206
// indicate which bit in LOG_BITMASK indicates baro logging enabled
207
void set_log_baro_bit(uint32_t bit) { _log_baro_bit = bit; }
208
bool should_log() const;
209
210
// allow threads to lock against baro update
211
HAL_Semaphore &get_semaphore(void) {
212
return _rsem;
213
}
214
215
#if AP_BARO_MSP_ENABLED
216
void handle_msp(const MSP::msp_baro_data_message_t &pkt);
217
#endif
218
#if AP_BARO_EXTERNALAHRS_ENABLED
219
void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt);
220
#endif
221
222
enum Options : uint16_t {
223
TreatMS5611AsMS5607 = (1U << 0U),
224
};
225
226
// check if an option is set
227
bool option_enabled(const Options option) const
228
{
229
return (uint16_t(_options.get()) & uint16_t(option)) != 0;
230
}
231
232
private:
233
// singleton
234
static AP_Baro *_singleton;
235
236
// how many drivers do we have?
237
uint8_t _num_drivers;
238
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
239
240
// how many sensors do we have?
241
uint8_t _num_sensors;
242
243
// what is the primary sensor at the moment?
244
uint8_t _primary;
245
246
uint32_t _log_baro_bit = -1;
247
248
bool init_done;
249
250
uint8_t msp_instance_mask;
251
252
// bitmask values for GND_PROBE_EXT
253
enum {
254
PROBE_BMP085=(1<<0),
255
PROBE_BMP280=(1<<1),
256
PROBE_MS5611=(1<<2),
257
PROBE_MS5607=(1<<3),
258
PROBE_MS5637=(1<<4),
259
PROBE_FBM320=(1<<5),
260
PROBE_DPS280=(1<<6),
261
PROBE_LPS25H=(1<<7),
262
PROBE_KELLER=(1<<8),
263
PROBE_MS5837=(1<<9),
264
PROBE_BMP388=(1<<10),
265
PROBE_SPL06 =(1<<11),
266
PROBE_MSP =(1<<12),
267
PROBE_BMP581=(1<<13),
268
};
269
270
#if HAL_BARO_WIND_COMP_ENABLED
271
class WindCoeff {
272
public:
273
static const struct AP_Param::GroupInfo var_info[];
274
275
AP_Int8 enable; // enable compensation for this barometer
276
AP_Float xp; // ratio of static pressure rise to dynamic pressure when flying forwards
277
AP_Float xn; // ratio of static pressure rise to dynamic pressure when flying backwards
278
AP_Float yp; // ratio of static pressure rise to dynamic pressure when flying to the right
279
AP_Float yn; // ratio of static pressure rise to dynamic pressure when flying to the left
280
AP_Float zp; // ratio of static pressure rise to dynamic pressure when flying up
281
AP_Float zn; // ratio of static pressure rise to dynamic pressure when flying down
282
};
283
#endif
284
285
struct sensor {
286
uint32_t last_update_ms; // last update time in ms
287
uint32_t last_change_ms; // last update time in ms that included a change in reading from previous readings
288
float pressure; // pressure in Pascal
289
float temperature; // temperature in degrees C
290
float altitude; // calculated altitude
291
AP_Float ground_pressure;
292
float p_correction;
293
baro_type_t type; // 0 for air pressure (default), 1 for water pressure
294
bool healthy; // true if sensor is healthy
295
bool alt_ok; // true if calculated altitude is ok
296
bool calibrated; // true if calculated calibrated successfully
297
AP_Int32 bus_id;
298
#if HAL_BARO_WIND_COMP_ENABLED
299
WindCoeff wind_coeff;
300
Vector3f dynamic_pressure; // calculated dynamic pressure
301
#endif
302
} sensors[BARO_MAX_INSTANCES];
303
304
AP_Float _alt_offset;
305
float _alt_offset_active;
306
AP_Float _field_elevation; // field elevation in meters
307
float _field_elevation_active;
308
uint32_t _field_elevation_last_ms;
309
AP_Int8 _primary_baro; // primary chosen by user
310
AP_Int8 _ext_bus; // bus number for external barometer
311
float _external_temperature;
312
uint32_t _last_external_temperature_ms;
313
DerivativeFilterFloat_Size7 _climb_rate_filter;
314
AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water
315
AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS
316
float _guessed_ground_temperature; // currently ground temperature estimate using our best available source
317
318
// when did we last notify the GCS of new pressure reference?
319
uint32_t _last_notify_ms;
320
321
// see if we already have probed a i2c driver by bus number and address
322
bool _have_i2c_driver(uint8_t bus_num, uint8_t address) const;
323
bool _add_backend(AP_Baro_Backend *backend);
324
void _probe_i2c_barometers(void);
325
AP_Int8 _filter_range; // valid value range from mean value
326
AP_Int32 _baro_probe_ext;
327
328
#ifndef HAL_BUILD_AP_PERIPH
329
AP_Float _alt_error_max;
330
#endif
331
332
AP_Int16 _options;
333
334
// semaphore for API access from threads
335
HAL_Semaphore _rsem;
336
337
#if HAL_BARO_WIND_COMP_ENABLED
338
/*
339
return pressure correction for wind based on GND_WCOEF parameters
340
*/
341
float wind_pressure_correction(uint8_t instance);
342
#endif
343
344
// Logging function
345
void Write_Baro(void);
346
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance);
347
348
void update_field_elevation();
349
350
// atmosphere model functions
351
float get_altitude_difference_extended(float base_pressure, float pressure) const;
352
float get_EAS2TAS_extended(float pressure) const;
353
static float get_temperature_by_altitude_layer(float alt, int8_t idx);
354
355
float get_altitude_difference_simple(float base_pressure, float pressure) const;
356
float get_EAS2TAS_simple(float altitude, float pressure) const;
357
};
358
359
namespace AP {
360
AP_Baro &baro();
361
};
362
363