APM:Libraries
AP_Baro.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_Param/AP_Param.h>
5 #include <Filter/Filter.h>
7 
8 // maximum number of sensor instances
9 #define BARO_MAX_INSTANCES 3
10 
11 // maximum number of drivers. Note that a single driver can provide
12 // multiple sensor instances
13 #define BARO_MAX_DRIVERS 3
14 
15 // timeouts for health reporting
16 #define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
17 #define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
18 
19 class AP_Baro_Backend;
20 
21 class AP_Baro
22 {
23  friend class AP_Baro_Backend;
24  friend class AP_Baro_SITL; // for access to sensors[]
25 
26 public:
27  AP_Baro();
28 
29  /* Do not allow copies */
30  AP_Baro(const AP_Baro &other) = delete;
31  AP_Baro &operator=(const AP_Baro&) = delete;
32 
33  // get singleton
34  static AP_Baro *get_instance(void) {
35  return _instance;
36  }
37 
38  // barometer types
39  typedef enum {
42  } baro_type_t;
43 
44  // initialise the barometer object, loading backend drivers
45  void init(void);
46 
47  // update the barometer object, asking backends to push data to
48  // the frontend
49  void update(void);
50 
51  // healthy - returns true if sensor and derived altitude are good
52  bool healthy(void) const { return healthy(_primary); }
53  bool healthy(uint8_t instance) const { return sensors[instance].healthy && sensors[instance].alt_ok && sensors[instance].calibrated; }
54 
55  // check if all baros are healthy - used for SYS_STATUS report
56  bool all_healthy(void) const;
57 
58  // pressure in Pascal. Divide by 100 for millibars or hectopascals
59  float get_pressure(void) const { return get_pressure(_primary); }
60  float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
61 
62  // temperature in degrees C
63  float get_temperature(void) const { return get_temperature(_primary); }
64  float get_temperature(uint8_t instance) const { return sensors[instance].temperature; }
65 
66  // get pressure correction in Pascal. Divide by 100 for millibars or hectopascals
68  float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; }
69 
70  // accumulate a reading on sensors. Some backends without their
71  // own thread or a timer may need this.
72  void accumulate(void);
73 
74  // calibrate the barometer. This must be called on startup if the
75  // altitude/climb_rate/acceleration interfaces are ever used
76  void calibrate(bool save=true);
77 
78  // update the barometer calibration to the current pressure. Can
79  // be used for incremental preflight update of baro
80  void update_calibration(void);
81 
82  // get current altitude in meters relative to altitude at the time
83  // of the last calibrate() call
84  float get_altitude(void) const { return get_altitude(_primary); }
85  float get_altitude(uint8_t instance) const { return sensors[instance].altitude; }
86 
87  // get altitude difference in meters relative given a base
88  // pressure in Pascal
89  float get_altitude_difference(float base_pressure, float pressure) const;
90 
91  // get scale factor required to convert equivalent to true airspeed
92  float get_EAS2TAS(void);
93 
94  // get air density / sea level density - decreases as altitude climbs
95  float get_air_density_ratio(void);
96 
97  // get current climb rate in meters/s. A positive number means
98  // going up
99  float get_climb_rate(void);
100 
101  // ground temperature in degrees C
102  // the ground values are only valid after calibration
103  float get_ground_temperature(void) const;
104 
105  // ground pressure in Pascal
106  // the ground values are only valid after calibration
107  float get_ground_pressure(void) const { return get_ground_pressure(_primary); }
108  float get_ground_pressure(uint8_t i) const { return sensors[i].ground_pressure.get(); }
109 
110  // set the temperature to be used for altitude calibration. This
111  // allows an external temperature source (such as a digital
112  // airspeed sensor) to be used as the temperature source
114 
115  // get last time sample was taken (in ms)
116  uint32_t get_last_update(void) const { return get_last_update(_primary); }
117  uint32_t get_last_update(uint8_t instance) const { return sensors[instance].last_update_ms; }
118 
119  // settable parameters
120  static const struct AP_Param::GroupInfo var_info[];
121 
123  float get_external_temperature(const uint8_t instance) const;
124 
125  // HIL (and SITL) interface, setting altitude
126  void setHIL(float altitude_msl);
127 
128  // HIL (and SITL) interface, setting pressure, temperature, altitude and climb_rate
129  // used by Replay
130  void setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate, uint32_t last_update_ms);
131 
132  // Set the primary baro
133  void set_primary_baro(uint8_t primary) { _primary_baro.set_and_save(primary); };
134 
135  // Set the type (Air or Water) of a particular instance
136  void set_type(uint8_t instance, baro_type_t type) { sensors[instance].type = type; };
137 
138  // Get the type (Air or Water) of a particular instance
139  baro_type_t get_type(uint8_t instance) { return sensors[instance].type; };
140 
141  // HIL variables
142  struct {
143  float pressure;
144  float temperature;
145  float altitude;
146  float climb_rate;
147  uint32_t last_update_ms;
148  bool updated:1;
149  bool have_alt:1;
151  } _hil;
152 
153  // register a new sensor, claiming a sensor slot. If we are out of
154  // slots it will panic
155  uint8_t register_sensor(void);
156 
157  // return number of registered sensors
158  uint8_t num_instances(void) const { return _num_sensors; }
159 
160  // enable HIL mode
161  void set_hil_mode(void) { _hil_mode = true; }
162 
163  // set baro drift amount
164  void set_baro_drift_altitude(float alt) { _alt_offset = alt; }
165 
166  // get baro drift amount
168 
169  // simple atmospheric model
170  static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
171 
172  // simple underwater atmospheric model
173  static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta);
174 
175  // set a pressure correction from AP_TempCalibration
176  void set_pressure_correction(uint8_t instance, float p_correction);
177 
178  uint8_t get_filter_range() const { return _filter_range; }
179 
180  // indicate which bit in LOG_BITMASK indicates baro logging enabled
181  void set_log_baro_bit(uint32_t bit) { _log_baro_bit = bit; }
182  bool should_df_log() const;
183 
184 private:
185  // singleton
187 
188  // how many drivers do we have?
189  uint8_t _num_drivers;
191 
192  // how many sensors do we have?
193  uint8_t _num_sensors;
194 
195  // what is the primary sensor at the moment?
196  uint8_t _primary;
197 
198  uint32_t _log_baro_bit = -1;
199 
200  struct sensor {
201  baro_type_t type; // 0 for air pressure (default), 1 for water pressure
202  uint32_t last_update_ms; // last update time in ms
203  uint32_t last_change_ms; // last update time in ms that included a change in reading from previous readings
204  bool healthy:1; // true if sensor is healthy
205  bool alt_ok:1; // true if calculated altitude is ok
206  bool calibrated:1; // true if calculated calibrated successfully
207  float pressure; // pressure in Pascal
208  float temperature; // temperature in degrees C
209  float altitude; // calculated altitude
210  AP_Float ground_pressure;
213 
214  AP_Float _alt_offset;
216  AP_Int8 _primary_baro; // primary chosen by user
217  AP_Int8 _ext_bus; // bus number for external barometer
219  float _EAS2TAS;
223  AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water
224  AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS
225  bool _hil_mode:1;
226  float _guessed_ground_temperature; // currently ground temperature estimate using our best abailable source
227 
228  // when did we last notify the GCS of new pressure reference?
229  uint32_t _last_notify_ms;
230 
231  bool _add_backend(AP_Baro_Backend *backend);
232  AP_Int8 _filter_range; // valid value range from mean value
233 };
234 
235 namespace AP {
236  AP_Baro &baro();
237 };
float _EAS2TAS
Definition: AP_Baro.h:219
AP_Float _user_ground_temperature
Definition: AP_Baro.h:224
float get_climb_rate(void)
Definition: AP_Baro.cpp:319
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:20
uint8_t num_instances(void) const
Definition: AP_Baro.h:158
float get_altitude(uint8_t instance) const
Definition: AP_Baro.h:85
void set_hil_mode(void)
Definition: AP_Baro.h:161
void update_calibration(void)
Definition: AP_Baro.cpp:246
void update(void)
Definition: AP_Baro.cpp:621
float climb_rate
Definition: AP_Baro.h:146
baro_type_t type
Definition: AP_Baro.h:201
static AP_Baro * _instance
Definition: AP_Baro.h:186
float _external_temperature
Definition: AP_Baro.h:220
float get_temperature(void) const
Definition: AP_Baro.h:63
float get_baro_drift_offset(void)
Definition: AP_Baro.h:167
uint8_t _num_drivers
Definition: AP_Baro.h:189
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
bool should_df_log() const
Definition: AP_Baro.cpp:603
DerivativeFilterFloat_Size7 _climb_rate_filter
Definition: AP_Baro.h:222
bool _add_backend(AP_Baro_Backend *backend)
Definition: AP_Baro.cpp:371
struct AP_Baro::@7 _hil
#define BARO_MAX_DRIVERS
Definition: AP_Baro.h:13
uint8_t get_filter_range() const
Definition: AP_Baro.h:178
AP_Float _specific_gravity
Definition: AP_Baro.h:223
float get_ground_pressure(uint8_t i) const
Definition: AP_Baro.h:108
static AP_Baro * get_instance(void)
Definition: AP_Baro.h:34
void set_pressure_correction(uint8_t instance, float p_correction)
Definition: AP_Baro.cpp:728
float _alt_offset_active
Definition: AP_Baro.h:215
bool _hil_mode
Definition: AP_Baro.h:225
uint32_t _last_external_temperature_ms
Definition: AP_Baro.h:221
void set_log_baro_bit(uint32_t bit)
Definition: AP_Baro.h:181
baro_type_t
Definition: AP_Baro.h:39
uint8_t _primary
Definition: AP_Baro.h:196
struct AP_Baro::sensor sensors[BARO_MAX_INSTANCES]
#define BARO_MAX_INSTANCES
Definition: AP_Baro.h:9
float get_EAS2TAS(void)
Definition: AP_Baro.cpp:288
baro_type_t get_type(uint8_t instance)
Definition: AP_Baro.h:139
float get_external_temperature(void) const
Definition: AP_Baro.h:122
uint32_t get_last_update(uint8_t instance) const
Definition: AP_Baro.h:117
float get_altitude_difference(float base_pressure, float pressure) const
Definition: AP_Baro.cpp:271
bool healthy(uint8_t instance) const
Definition: AP_Baro.h:53
static int8_t delta
Definition: RCOutput.cpp:21
float get_air_density_ratio(void)
Definition: AP_Baro.cpp:306
void accumulate(void)
Definition: AP_Baro.cpp:694
void calibrate(bool save=true)
Definition: AP_Baro.cpp:164
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta)
Definition: AP_Baro_HIL.cpp:43
A system for managing and storing variables that are of general interest to the system.
float p_correction
Definition: AP_Baro.h:211
uint32_t last_update_ms
Definition: AP_Baro.h:147
AP_Int8 _filter_range
Definition: AP_Baro.h:232
Definition: AP_AHRS.cpp:486
void set_primary_baro(uint8_t primary)
Definition: AP_Baro.h:133
float get_pressure_correction(uint8_t instance) const
Definition: AP_Baro.h:68
float get_ground_pressure(void) const
Definition: AP_Baro.h:107
uint32_t last_change_ms
Definition: AP_Baro.h:203
void init(void)
Definition: AP_Baro.cpp:398
float altitude
Definition: AP_Baro.h:145
float get_pressure(uint8_t instance) const
Definition: AP_Baro.h:60
float get_temperature(uint8_t instance) const
Definition: AP_Baro.h:64
static AP_Baro baro
Definition: ModuleTest.cpp:18
float temperature
Definition: AP_Baro.h:144
AP_Baro_Backend * drivers[BARO_MAX_DRIVERS]
Definition: AP_Baro.h:190
AP_Int8 _primary_baro
Definition: AP_Baro.h:216
float get_pressure_correction(void) const
Definition: AP_Baro.h:67
bool healthy(void) const
Definition: AP_Baro.h:52
float get_pressure(void) const
Definition: AP_Baro.h:59
uint32_t last_update_ms
Definition: AP_Baro.h:202
void set_type(uint8_t instance, baro_type_t type)
Definition: AP_Baro.h:136
AP_Baro & operator=(const AP_Baro &)=delete
uint32_t _log_baro_bit
Definition: AP_Baro.h:198
float _guessed_ground_temperature
Definition: AP_Baro.h:226
float get_altitude(void) const
Definition: AP_Baro.h:84
AP_Baro()
Definition: AP_Baro.cpp:155
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Baro.h:120
uint32_t _last_notify_ms
Definition: AP_Baro.h:229
float pressure
Definition: AP_Baro.h:143
float get_ground_temperature(void) const
Definition: AP_Baro.cpp:331
bool have_alt
Definition: AP_Baro.h:149
float _last_altitude_EAS2TAS
Definition: AP_Baro.h:218
bool calibrated
Definition: AP_Baro.h:206
float temperature
Definition: AP_Baro.h:208
AP_Int8 _ext_bus
Definition: AP_Baro.h:217
void set_external_temperature(float temperature)
Definition: AP_Baro.cpp:344
AP_Float _alt_offset
Definition: AP_Baro.h:214
AP_Float ground_pressure
Definition: AP_Baro.h:210
uint32_t get_last_update(void) const
Definition: AP_Baro.h:116
uint8_t _num_sensors
Definition: AP_Baro.h:193
float pressure
Definition: AP_Baro.h:207
bool have_last_update
Definition: AP_Baro.h:150
bool all_healthy(void) const
Definition: AP_Baro.cpp:717
bool updated
Definition: AP_Baro.h:148
void set_baro_drift_altitude(float alt)
Definition: AP_Baro.h:164
void setHIL(float altitude_msl)
Definition: AP_Baro_HIL.cpp:83
float altitude
Definition: AP_Baro.h:209