AP_Baro.h 9.9 KB

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