APM:Libraries
AP_Baro.cpp
Go to the documentation of this file.
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>
32 
33 #include "AP_Baro_SITL.h"
34 #include "AP_Baro_BMP085.h"
35 #include "AP_Baro_BMP280.h"
36 #include "AP_Baro_HIL.h"
37 #include "AP_Baro_KellerLD.h"
38 #include "AP_Baro_MS5611.h"
39 #include "AP_Baro_ICM20789.h"
40 #include "AP_Baro_LPS2XH.h"
41 #include "AP_Baro_FBM320.h"
42 #include "AP_Baro_DPS280.h"
43 #if HAL_WITH_UAVCAN
44 #include "AP_Baro_UAVCAN.h"
45 #endif
46 
47 #define INTERNAL_TEMPERATURE_CLAMP 35.0f
48 
49 #ifndef HAL_BARO_FILTER_DEFAULT
50  #define HAL_BARO_FILTER_DEFAULT 0 // turned off by default
51 #endif
52 
53 extern const AP_HAL::HAL& hal;
54 
55 // table of user settable parameters
57  // NOTE: Index numbers 0 and 1 were for the old integer
58  // ground temperature and pressure
59 
60  // @Param: ABS_PRESS
61  // @DisplayName: Absolute Pressure
62  // @Description: calibrated ground pressure in Pascals
63  // @Units: Pa
64  // @Increment: 1
65  // @ReadOnly: True
66  // @Volatile: True
67  // @User: Advanced
68  AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0),
69 
70  // @Param: TEMP
71  // @DisplayName: ground temperature
72  // @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.
73  // @Units: degC
74  // @Increment: 1
75  // @Volatile: True
76  // @User: Advanced
77  AP_GROUPINFO("TEMP", 3, AP_Baro, _user_ground_temperature, 0),
78 
79  // index 4 reserved for old AP_Int8 version in legacy FRAM
80  //AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),
81 
82  // @Param: ALT_OFFSET
83  // @DisplayName: altitude offset
84  // @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.
85  // @Units: m
86  // @Increment: 0.1
87  // @User: Advanced
88  AP_GROUPINFO("ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
89 
90  // @Param: PRIMARY
91  // @DisplayName: Primary barometer
92  // @Description: This selects which barometer will be the primary if multiple barometers are found
93  // @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
94  // @User: Advanced
95  AP_GROUPINFO("PRIMARY", 6, AP_Baro, _primary_baro, 0),
96 
97  // @Param: EXT_BUS
98  // @DisplayName: External baro bus
99  // @Description: This selects the bus number for looking for an I2C barometer
100  // @Values: -1:Disabled,0:Bus0,1:Bus1
101  // @User: Advanced
102  AP_GROUPINFO("EXT_BUS", 7, AP_Baro, _ext_bus, -1),
103 
104  // @Param: SPEC_GRAV
105  // @DisplayName: Specific Gravity (For water depth measurement)
106  // @Description: This sets the specific gravity of the fluid when flying an underwater ROV.
107  // @Values: 1.0:Freshwater,1.024:Saltwater
108  AP_GROUPINFO_FRAME("SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
109 
110 #if BARO_MAX_INSTANCES > 1
111  // @Param: ABS_PRESS2
112  // @DisplayName: Absolute Pressure
113  // @Description: calibrated ground pressure in Pascals
114  // @Units: Pa
115  // @Increment: 1
116  // @ReadOnly: True
117  // @Volatile: True
118  // @User: Advanced
119  AP_GROUPINFO("ABS_PRESS2", 9, AP_Baro, sensors[1].ground_pressure, 0),
120 
121  // Slot 10 used to be TEMP2
122 #endif
123 
124 #if BARO_MAX_INSTANCES > 2
125  // @Param: ABS_PRESS3
126  // @DisplayName: Absolute Pressure
127  // @Description: calibrated ground pressure in Pascals
128  // @Units: Pa
129  // @Increment: 1
130  // @ReadOnly: True
131  // @Volatile: True
132  // @User: Advanced
133  AP_GROUPINFO("ABS_PRESS3", 11, AP_Baro, sensors[2].ground_pressure, 0),
134 
135  // Slot 12 used to be TEMP3
136 #endif
137 
138  // @Param: FLTR_RNG
139  // @DisplayName: Range in which sample is accepted
140  // @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.
141  // @Units: %
142  // @Range: 0 100
143  // @Increment: 1
144  AP_GROUPINFO("FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
145 
147 };
148 
149 // singleton instance
151 
152 /*
153  AP_Baro constructor
154  */
156 {
157  _instance = this;
158 
160 }
161 
162 // calibrate the barometer. This must be called at least once before
163 // the altitude() or climb_rate() interfaces can be used
164 void AP_Baro::calibrate(bool save)
165 {
166  gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
167 
168  // reset the altitude offset when we calibrate. The altitude
169  // offset is supposed to be for within a flight
170  _alt_offset.set_and_save(0);
171 
172  // start by assuming all sensors are calibrated (for healthy() test)
173  for (uint8_t i=0; i<_num_sensors; i++) {
174  sensors[i].calibrated = true;
175  sensors[i].alt_ok = true;
176  }
177 
178  // let the barometer settle for a full second after startup
179  // the MS5611 reads quite a long way off for the first second,
180  // leading to about 1m of error if we don't wait
181  for (uint8_t i = 0; i < 10; i++) {
182  uint32_t tstart = AP_HAL::millis();
183  do {
184  update();
185  if (AP_HAL::millis() - tstart > 500) {
186  AP_HAL::panic("PANIC: AP_Baro::read unsuccessful "
187  "for more than 500ms in AP_Baro::calibrate [2]\r\n");
188  }
189  hal.scheduler->delay(10);
190  } while (!healthy());
191  hal.scheduler->delay(100);
192  }
193 
194  // now average over 5 values for the ground pressure and
195  // temperature settings
196  float sum_pressure[BARO_MAX_INSTANCES] = {0};
197  float sum_temperature[BARO_MAX_INSTANCES] = {0};
198  uint8_t count[BARO_MAX_INSTANCES] = {0};
199  const uint8_t num_samples = 5;
200 
201  for (uint8_t c = 0; c < num_samples; c++) {
202  uint32_t tstart = AP_HAL::millis();
203  do {
204  update();
205  if (AP_HAL::millis() - tstart > 500) {
206  AP_HAL::panic("PANIC: AP_Baro::read unsuccessful "
207  "for more than 500ms in AP_Baro::calibrate [3]\r\n");
208  }
209  } while (!healthy());
210  for (uint8_t i=0; i<_num_sensors; i++) {
211  if (healthy(i)) {
212  sum_pressure[i] += sensors[i].pressure;
213  sum_temperature[i] += sensors[i].temperature;
214  count[i] += 1;
215  }
216  }
217  hal.scheduler->delay(100);
218  }
219  for (uint8_t i=0; i<_num_sensors; i++) {
220  if (count[i] == 0) {
221  sensors[i].calibrated = false;
222  } else {
223  if (save) {
224  sensors[i].ground_pressure.set_and_save(sum_pressure[i] / count[i]);
225  }
226  }
227  }
228 
230 
231  // panic if all sensors are not calibrated
232  for (uint8_t i=0; i<_num_sensors; i++) {
233  if (sensors[i].calibrated) {
234  gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
235  return;
236  }
237  }
238  AP_HAL::panic("AP_Baro: all sensors uncalibrated");
239 }
240 
241 /*
242  update the barometer calibration
243  this updates the baro ground calibration to the current values. It
244  can be used before arming to keep the baro well calibrated
245 */
247 {
248  for (uint8_t i=0; i<_num_sensors; i++) {
249  if (healthy(i)) {
250  float corrected_pressure = get_pressure(i) + sensors[i].p_correction;
251  sensors[i].ground_pressure.set(corrected_pressure);
252  }
253 
254  // don't notify the GCS too rapidly or we flood the link
255  uint32_t now = AP_HAL::millis();
256  if (now - _last_notify_ms > 10000) {
257  sensors[i].ground_pressure.notify();
258  _last_notify_ms = now;
259  }
260  }
261 
262  // always update the guessed ground temp
264 
265  // force EAS2TAS to recalculate
266  _EAS2TAS = 0;
267 }
268 
269 // return altitude difference in meters between current pressure and a
270 // given base_pressure in Pascal
271 float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const
272 {
273  float ret;
274  float temp = get_ground_temperature() + C_TO_KELVIN;
275  float scaling = pressure / base_pressure;
276 
277  // This is an exact calculation that is within +-2.5m of the standard
278  // atmosphere tables in the troposphere (up to 11,000 m amsl).
279  ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)));
280 
281  return ret;
282 }
283 
284 
285 // return current scale factor that converts from equivalent to true airspeed
286 // valid for altitudes up to 10km AMSL
287 // assumes standard atmosphere lapse rate
289 {
290  float altitude = get_altitude();
291  if ((fabsf(altitude - _last_altitude_EAS2TAS) < 25.0f) && !is_zero(_EAS2TAS)) {
292  // not enough change to require re-calculating
293  return _EAS2TAS;
294  }
295 
296  // only estimate lapse rate for the difference from the ground location
297  // provides a more consistent reading then trying to estimate a complete
298  // ISA model atmosphere
300  _EAS2TAS = safe_sqrt(SSL_AIR_DENSITY / ((float)get_pressure() / (ISA_GAS_CONSTANT * tempK)));
302  return _EAS2TAS;
303 }
304 
305 // return air density / sea level density - decreases as altitude climbs
307 {
308  const float eas2tas = get_EAS2TAS();
309  if (eas2tas > 0.0f) {
310  return 1.0f/(sq(eas2tas));
311  } else {
312  return 1.0f;
313  }
314 }
315 
316 // return current climb_rate estimate relative to time that calibrate()
317 // was called. Returns climb rate in meters/s, positive means up
318 // note that this relies on read() being called regularly to get new data
320 {
321  if (_hil.have_alt) {
322  return _hil.climb_rate;
323  }
324  // we use a 7 point derivative filter on the climb rate. This seems
325  // to produce somewhat reasonable results on real hardware
326  return _climb_rate_filter.slope() * 1.0e3f;
327 }
328 
329 // returns the ground temperature in degrees C, selecting either a user
330 // provided one, or the internal estimate
332 {
335  } else {
337  }
338 }
339 
340 
341 /*
342  set external temperature to be used for calibration (degrees C)
343  */
345 {
348 }
349 
350 /*
351  get the temperature in degrees C to be used for calibration purposes
352  */
353 float AP_Baro::get_external_temperature(const uint8_t instance) const
354 {
355  // if we have a recent external temperature then use it
357  return _external_temperature;
358  }
359  // if we don't have an external temperature then use the minimum
360  // of the barometer temperature and 35 degrees C. The reason for
361  // not just using the baro temperature is it tends to read high,
362  // often 30 degrees above the actual temperature. That means the
363  // EAS2TAS tends to be off by quite a large margin, as well as
364  // the calculation of altitude difference betweeen two pressures
365  // reporting a high temperature will cause the aircraft to
366  // estimate itself as flying higher then it actually is.
368 }
369 
370 
372 {
373  if (!backend) {
374  return false;
375  }
377  AP_HAL::panic("Too many barometer drivers");
378  }
379  drivers[_num_drivers++] = backend;
380  return true;
381 }
382 
383 /*
384  macro to add a backend with check for too many sensors
385  We don't try to start more than the maximum allowed
386  */
387 #define ADD_BACKEND(backend) \
388  do { _add_backend(backend); \
389  if (_num_drivers == BARO_MAX_DRIVERS || \
390  _num_sensors == BARO_MAX_INSTANCES) { \
391  return; \
392  } \
393  } while (0)
394 
395 /*
396  initialise the barometer object, loading backend drivers
397  */
398 void AP_Baro::init(void)
399 {
400  // ensure that there isn't a previous ground temperature saved
402  _user_ground_temperature.set_and_save(0.0f);
403  _user_ground_temperature.notify();
404  }
405 
406  if (_hil_mode) {
407  drivers[0] = new AP_Baro_HIL(*this);
408  _num_drivers = 1;
409  return;
410  }
411 
412 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
413  ADD_BACKEND(new AP_Baro_SITL(*this));
414  return;
415 #endif
416 
417 #if HAL_WITH_UAVCAN
418  bool added;
419  do {
420  added = _add_backend(AP_Baro_UAVCAN::probe(*this));
422  return;
423  }
424  } while (added);
425 #endif
426 
427 #if AP_FEATURE_BOARD_DETECT
428  switch (AP_BoardConfig::get_board_type()) {
430 #ifdef HAL_BARO_MS5611_I2C_BUS
433 #endif
434  break;
435 
442  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
443  break;
444 
448  std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
450  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
451  break;
452 
455  std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_INT_NAME))));
456  break;
457 
460  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
461  break;
462 
464 #ifdef HAL_BARO_MS5607_I2C_BUS
468 #endif
469  break;
470 
473  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
475  std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
476 #ifdef HAL_BARO_MS5611_SPI_IMU_NAME
478  std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME))));
479 #endif
480  break;
481 
489  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
490  break;
491 
494  std::move(hal.i2c_mgr->get_device(1, 0x63)),
495  std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME))));
496  break;
497 
498  default:
499  break;
500  }
501 #elif HAL_BARO_DEFAULT == HAL_BARO_HIL
502  drivers[0] = new AP_Baro_HIL(*this);
503  _num_drivers = 1;
504 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP085
505  drivers[0] = new AP_Baro_BMP085(*this,
507  _num_drivers = 1;
508 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_I2C
511 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_SPI
513  std::move(hal.spi->get_device(HAL_BARO_BMP280_NAME))));
514 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_I2C
517 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI
519  std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
520 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5607_I2C
524 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5637_I2C
526  std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)),
528 #elif HAL_BARO_DEFAULT == HAL_BARO_FBM320_I2C
530  std::move(hal.i2c_mgr->get_device(HAL_BARO_FBM320_I2C_BUS, HAL_BARO_FBM320_I2C_ADDR))));
531 #elif HAL_BARO_DEFAULT == HAL_BARO_DPS280_I2C
533  std::move(hal.i2c_mgr->get_device(HAL_BARO_DPS280_I2C_BUS, HAL_BARO_DPS280_I2C_ADDR))));
534 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H
537 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C
540  HAL_BARO_LPS25H_I2C_IMU_ADDR));
541 #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_I2C
543  std::move(hal.i2c_mgr->get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
544  std::move(hal.i2c_mgr->get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_ICM))));
545 #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_SPI
547  std::move(hal.i2c_mgr->get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
548  std::move(hal.spi->get_device("icm20789"))));
549 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS22H_SPI
551  std::move(hal.spi->get_device(HAL_BARO_LPS22H_NAME))));
552 #endif
553 
554 #if defined(BOARD_I2C_BUS_EXT) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
557 
560  #ifdef HAL_BARO_BMP280_I2C_ADDR_ALT
563  #endif
564 
567 #endif
568 
569  // can optionally have baro on I2C too
570  if (_ext_bus >= 0) {
571 #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
574 
577 #else
580 
581  #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT // we don't know which baro user will solder
582 
585  #ifdef HAL_BARO_BMP280_I2C_ADDR_ALT
588  #endif
591  #endif
592 #endif
593  }
594 
595 #if CONFIG_HAL_BOARD != HAL_BOARD_F4LIGHT // most boards requires external baro
596 
597  if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
598  AP_BoardConfig::sensor_config_error("Baro: unable to initialise driver");
599  }
600 #endif
601 }
602 
604 {
606  if (instance == nullptr) {
607  return false;
608  }
609  if (_log_baro_bit == (uint32_t)-1) {
610  return false;
611  }
612  if (!instance->should_log(_log_baro_bit)) {
613  return false;
614  }
615  return true;
616 }
617 
618 /*
619  call update on all drivers
620  */
621 void AP_Baro::update(void)
622 {
623  if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
624  // If there's more than 1cm difference then slowly slew to it via LPF.
625  // The EKF does not like step inputs so this keeps it happy.
627  } else {
629  }
630 
631  if (!_hil_mode) {
632  for (uint8_t i=0; i<_num_drivers; i++) {
633  drivers[i]->backend_update(i);
634  }
635  }
636 
637  for (uint8_t i=0; i<_num_sensors; i++) {
638  if (sensors[i].healthy) {
639  // update altitude calculation
640  float ground_pressure = sensors[i].ground_pressure;
641  if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
643  }
644  float altitude = sensors[i].altitude;
645  float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;
646  if (sensors[i].type == BARO_TYPE_AIR) {
647  altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure);
648  } else if (sensors[i].type == BARO_TYPE_WATER) {
649  //101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
650  //No temperature or depth compensation for density of water.
651  altitude = (sensors[i].ground_pressure - corrected_pressure) / 9800.0f / _specific_gravity;
652  }
653  // sanity check altitude
654  sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));
655  if (sensors[i].alt_ok) {
656  sensors[i].altitude = altitude + _alt_offset_active;
657  }
658  }
659  if (_hil.have_alt) {
660  sensors[0].altitude = _hil.altitude;
661  }
662  if (_hil.have_last_update) {
663  sensors[0].last_update_ms = _hil.last_update_ms;
664  }
665  }
666 
667  // ensure the climb rate filter is updated
668  if (healthy()) {
670  }
671 
672  // choose primary sensor
673  if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {
675  } else {
676  _primary = 0;
677  for (uint8_t i=0; i<_num_sensors; i++) {
678  if (healthy(i)) {
679  _primary = i;
680  break;
681  }
682  }
683  }
684 
685  // logging
686  if (should_df_log() && !AP::ahrs().have_ekf_logging()) {
688  }
689 }
690 
691 /*
692  call accumulate on all drivers
693  */
695 {
696  for (uint8_t i=0; i<_num_drivers; i++) {
697  drivers[i]->accumulate();
698  }
699 }
700 
701 
702 /* register a new sensor, claiming a sensor slot. If we are out of
703  slots it will panic
704 */
706 {
708  AP_HAL::panic("Too many barometers");
709  }
710  return _num_sensors++;
711 }
712 
713 
714 /*
715  check if all barometers are healthy
716  */
717 bool AP_Baro::all_healthy(void) const
718 {
719  for (uint8_t i=0; i<_num_sensors; i++) {
720  if (!healthy(i)) {
721  return false;
722  }
723  }
724  return _num_sensors > 0;
725 }
726 
727 // set a pressure correction from AP_TempCalibration
728 void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
729 {
730  if (instance < _num_sensors) {
731  sensors[instance].p_correction = p_correction;
732  }
733 }
734 
735 namespace AP {
736 
738 {
739  return *AP_Baro::get_instance();
740 }
741 
742 };
#define HAL_BARO_MS5611_NAME
Definition: chibios.h:47
float _EAS2TAS
Definition: AP_Baro.h:219
float scaling
Definition: AnalogIn.cpp:40
AP_Float _user_ground_temperature
Definition: AP_Baro.h:224
float get_climb_rate(void)
Definition: AP_Baro.cpp:319
static AP_Baro_Backend * probe(AP_Baro &baro)
#define HAL_BARO_MS5607_I2C_ADDR
Definition: board.h:120
#define HAL_BARO_FILTER_DEFAULT
Definition: AP_Baro.cpp:50
#define HAL_BARO_MS5611_I2C_BUS
Definition: board.h:110
#define HAL_BARO_MS5611_SPI_EXT_NAME
Definition: chibios.h:51
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
void update_calibration(void)
Definition: AP_Baro.cpp:246
static enum px4_board_type get_board_type(void)
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
#define C_TO_KELVIN
Definition: definitions.h:74
void update(void)
Definition: AP_Baro.cpp:621
#define HAL_BARO_BMP280_I2C_ADDR_ALT
Definition: board.h:115
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
uint8_t _num_drivers
Definition: AP_Baro.h:189
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
#define SSL_AIR_DENSITY
Definition: definitions.h:82
Interface definition for the various Ground Control System.
bool should_df_log() const
Definition: AP_Baro.cpp:603
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
DerivativeFilterFloat_Size7 _climb_rate_filter
Definition: AP_Baro.h:222
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
bool _add_backend(AP_Baro_Backend *backend)
Definition: AP_Baro.cpp:371
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
struct AP_Baro::@7 _hil
#define HAL_BARO_BMP280_I2C_ADDR
#define ISA_GAS_CONSTANT
Definition: definitions.h:77
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define BARO_MAX_DRIVERS
Definition: AP_Baro.h:13
AP_Float _specific_gravity
Definition: AP_Baro.h:223
static AP_Baro * get_instance(void)
Definition: AP_Baro.h:34
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611)
void set_pressure_correction(uint8_t instance, float p_correction)
Definition: AP_Baro.cpp:728
float _alt_offset_active
Definition: AP_Baro.h:215
void update(T sample, uint32_t timestamp)
bool _hil_mode
Definition: AP_Baro.h:225
uint32_t _last_external_temperature_ms
Definition: AP_Baro.h:221
GCS & gcs()
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
uint8_t _primary
Definition: AP_Baro.h:196
virtual void accumulate(void)
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
float get_external_temperature(void) const
Definition: AP_Baro.h:122
#define MIN(a, b)
Definition: usb_conf.h:215
float get_altitude_difference(float base_pressure, float pressure) const
Definition: AP_Baro.cpp:271
#define INTERNAL_TEMPERATURE_CLAMP
Definition: AP_Baro.cpp:47
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_imu)
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
virtual void delay(uint16_t ms)=0
float p_correction
Definition: AP_Baro.h:211
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
Definition: AP_AHRS.cpp:486
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define HAL_INS_MPU60x0_NAME
Definition: chibios.h:55
#define HAL_BARO_MS5607_I2C_BUS
Definition: board.h:119
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
#define HAL_BARO_MS5611_I2C_ADDR
void init(void)
Definition: AP_Baro.cpp:398
#define HAL_BARO_BMP280_BUS
Definition: board.h:113
float altitude
Definition: AP_Baro.h:145
#define HAL_BARO_LPS25H_I2C_ADDR
static AP_Baro baro
Definition: ModuleTest.cpp:18
#define ADD_BACKEND(backend)
Definition: AP_Baro.cpp:387
uint32_t millis()
Definition: system.cpp:157
float temperature
Definition: AP_Baro.h:144
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
AP_Baro_Backend * drivers[BARO_MAX_DRIVERS]
Definition: AP_Baro.h:190
AP_Int8 _primary_baro
Definition: AP_Baro.h:216
friend class AP_Baro_SITL
Definition: AP_Baro.h:24
#define HAL_BARO_LPS22H_NAME
Definition: chibios.h:52
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool healthy(void) const
Definition: AP_Baro.h:52
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
float get_pressure(void) const
Definition: AP_Baro.h:59
uint32_t last_update_ms
Definition: AP_Baro.h:202
void backend_update(uint8_t instance)
uint32_t _log_baro_bit
Definition: AP_Baro.h:198
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
Common definitions and utility routines for the ArduPilot libraries.
float _guessed_ground_temperature
Definition: AP_Baro.h:226
#define HAL_BARO_MS5611_SPI_IMU_NAME
Definition: vrbrain.h:55
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
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 sq(const T val)
Definition: AP_Math.h:170
float get_ground_temperature(void) const
Definition: AP_Baro.cpp:331
#define HAL_BARO_BMP280_NAME
Definition: chibios.h:53
#define HAL_BARO_LPS25H_I2C_BUS
Definition: AP_Baro_LPS2XH.h:9
float _last_altitude_EAS2TAS
Definition: AP_Baro.h:218
bool calibrated
Definition: AP_Baro.h:206
static AP_Baro_Backend * probe_InvensenseIMU(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, uint8_t imu_address)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
float temperature
Definition: AP_Baro.h:208
#define ISA_LAPSE_RATE
Definition: definitions.h:78
#define AP_PARAM_FRAME_SUB
Definition: AP_Param.h:80
AP_Int8 _ext_bus
Definition: AP_Baro.h:217
#define HAL_BARO_MS5837_I2C_ADDR
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
#define AP_GROUPEND
Definition: AP_Param.h:121
bool all_healthy(void) const
Definition: AP_Baro.cpp:717
void Log_Write_Baro(uint64_t time_us=0)
Definition: LogFile.cpp:279
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define HAL_BARO_BMP085_I2C_ADDR
#define HAL_BARO_MS5611_SPI_INT_NAME
Definition: chibios.h:49
#define HAL_BARO_BMP085_BUS
Definition: board.h:116
#define BOARD_I2C_BUS_EXT
Definition: board.h:107
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
#define HAL_BARO_KELLERLD_I2C_ADDR
float altitude
Definition: AP_Baro.h:209
static void sensor_config_error(const char *reason)