AP_Baro.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * APM_Baro.cpp - barometer driver
  15. *
  16. */
  17. #include "AP_Baro.h"
  18. #include <utility>
  19. #include <stdio.h>
  20. #include <GCS_MAVLink/GCS.h>
  21. #include <AP_Common/AP_Common.h>
  22. #include <AP_HAL/AP_HAL.h>
  23. #include <AP_Math/AP_Math.h>
  24. #include <AP_BoardConfig/AP_BoardConfig.h>
  25. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  26. #include <AP_Vehicle/AP_Vehicle_Type.h>
  27. #include "AP_Baro_SITL.h"
  28. #include "AP_Baro_BMP085.h"
  29. #include "AP_Baro_BMP280.h"
  30. #include "AP_Baro_HIL.h"
  31. #include "AP_Baro_KellerLD.h"
  32. #include "AP_Baro_MS5611.h"
  33. #include "AP_Baro_ICM20789.h"
  34. #include "AP_Baro_LPS2XH.h"
  35. #include "AP_Baro_FBM320.h"
  36. #include "AP_Baro_DPS280.h"
  37. #include "AP_Baro_BMP388.h"
  38. #if HAL_WITH_UAVCAN
  39. #include "AP_Baro_UAVCAN.h"
  40. #endif
  41. #include <AP_Airspeed/AP_Airspeed.h>
  42. #include <AP_AHRS/AP_AHRS.h>
  43. #include <AP_Logger/AP_Logger.h>
  44. #define INTERNAL_TEMPERATURE_CLAMP 35.0f
  45. #ifndef HAL_BARO_FILTER_DEFAULT
  46. #define HAL_BARO_FILTER_DEFAULT 0 // turned off by default
  47. #endif
  48. #if !defined(HAL_PROBE_EXTERNAL_I2C_BAROS) && !HAL_MINIMIZE_FEATURES
  49. #define HAL_PROBE_EXTERNAL_I2C_BAROS
  50. #endif
  51. #ifndef HAL_BARO_PROBE_EXT_DEFAULT
  52. #define HAL_BARO_PROBE_EXT_DEFAULT 0
  53. #endif
  54. extern const AP_HAL::HAL& hal;
  55. // table of user settable parameters
  56. const AP_Param::GroupInfo AP_Baro::var_info[] = {
  57. // NOTE: Index numbers 0 and 1 were for the old integer
  58. // ground temperature and pressure
  59. // @Param: ABS_PRESS
  60. // @DisplayName: Absolute Pressure
  61. // @Description: calibrated ground pressure in Pascals
  62. // @Units: Pa
  63. // @Increment: 1
  64. // @ReadOnly: True
  65. // @Volatile: True
  66. // @User: Advanced
  67. AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0),
  68. // @Param: TEMP
  69. // @DisplayName: ground temperature
  70. // @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.
  71. // @Units: degC
  72. // @Increment: 1
  73. // @Volatile: True
  74. // @User: Advanced
  75. AP_GROUPINFO("TEMP", 3, AP_Baro, _user_ground_temperature, 0),
  76. // index 4 reserved for old AP_Int8 version in legacy FRAM
  77. //AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),
  78. // @Param: ALT_OFFSET
  79. // @DisplayName: altitude offset
  80. // @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.
  81. // @Units: m
  82. // @Increment: 0.1
  83. // @User: Advanced
  84. AP_GROUPINFO("ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
  85. // @Param: PRIMARY
  86. // @DisplayName: Primary barometer
  87. // @Description: This selects which barometer will be the primary if multiple barometers are found
  88. // @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
  89. // @User: Advanced
  90. AP_GROUPINFO("PRIMARY", 6, AP_Baro, _primary_baro, 0),
  91. // @Param: EXT_BUS
  92. // @DisplayName: External baro bus
  93. // @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 GND_PROBE_EXT parameter.
  94. // @Values: -1:Disabled,0:Bus0,1:Bus1
  95. // @User: Advanced
  96. AP_GROUPINFO("EXT_BUS", 7, AP_Baro, _ext_bus, -1),
  97. // @Param: SPEC_GRAV
  98. // @DisplayName: Specific Gravity (For water depth measurement)
  99. // @Description: This sets the specific gravity of the fluid when flying an underwater ROV.
  100. // @Values: 1.0:Freshwater,1.024:Saltwater
  101. AP_GROUPINFO_FRAME("SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
  102. #if BARO_MAX_INSTANCES > 1
  103. // @Param: ABS_PRESS2
  104. // @DisplayName: Absolute Pressure
  105. // @Description: calibrated ground pressure in Pascals
  106. // @Units: Pa
  107. // @Increment: 1
  108. // @ReadOnly: True
  109. // @Volatile: True
  110. // @User: Advanced
  111. AP_GROUPINFO("ABS_PRESS2", 9, AP_Baro, sensors[1].ground_pressure, 0),
  112. // Slot 10 used to be TEMP2
  113. #endif
  114. #if BARO_MAX_INSTANCES > 2
  115. // @Param: ABS_PRESS3
  116. // @DisplayName: Absolute Pressure
  117. // @Description: calibrated ground pressure in Pascals
  118. // @Units: Pa
  119. // @Increment: 1
  120. // @ReadOnly: True
  121. // @Volatile: True
  122. // @User: Advanced
  123. AP_GROUPINFO("ABS_PRESS3", 11, AP_Baro, sensors[2].ground_pressure, 0),
  124. // Slot 12 used to be TEMP3
  125. #endif
  126. // @Param: FLTR_RNG
  127. // @DisplayName: Range in which sample is accepted
  128. // @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.
  129. // @Units: %
  130. // @Range: 0 100
  131. // @Increment: 1
  132. AP_GROUPINFO("FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
  133. #ifdef HAL_PROBE_EXTERNAL_I2C_BAROS
  134. // @Param: PROBE_EXT
  135. // @DisplayName: External barometers to probe
  136. // @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 GND_EXT_BUS. If GND_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
  137. // @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,10:MS5837,11:BMP388
  138. // @Values: 1:BMP085,2:BMP280,4:MS5611,8:MS5607,16:MS5637,32:FBM320,64:DPS280,128:LPS25H,256:Keller,512:MS5837,1024:BMP388
  139. // @User: Advanced
  140. AP_GROUPINFO("PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),
  141. #endif
  142. AP_GROUPEND
  143. };
  144. // singleton instance
  145. AP_Baro *AP_Baro::_singleton;
  146. #ifdef HAL_NO_GCS
  147. #define BARO_SEND_TEXT(severity, format, args...)
  148. #else
  149. #define BARO_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
  150. #endif
  151. /*
  152. AP_Baro constructor
  153. */
  154. AP_Baro::AP_Baro()
  155. {
  156. _singleton = this;
  157. AP_Param::setup_object_defaults(this, var_info);
  158. }
  159. // calibrate the barometer. This must be called at least once before
  160. // the altitude() or climb_rate() interfaces can be used
  161. void AP_Baro::calibrate(bool save)
  162. {
  163. // start by assuming all sensors are calibrated (for healthy() test)
  164. for (uint8_t i=0; i<_num_sensors; i++) {
  165. sensors[i].calibrated = true;
  166. sensors[i].alt_ok = true;
  167. }
  168. if (hal.util->was_watchdog_reset()) {
  169. BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration");
  170. return;
  171. }
  172. BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");
  173. // reset the altitude offset when we calibrate. The altitude
  174. // offset is supposed to be for within a flight
  175. //_alt_offset.set_and_save(0);
  176. // let the barometer settle for a full second after startup
  177. // the MS5611 reads quite a long way off for the first second,
  178. // leading to about 1m of error if we don't wait
  179. for (uint8_t i = 0; i < 10; i++) {
  180. uint32_t tstart = AP_HAL::millis();
  181. do {
  182. update();
  183. if (AP_HAL::millis() - tstart > 500) {
  184. AP_BoardConfig::sensor_config_error("Baro: unable to calibrate");
  185. }
  186. hal.scheduler->delay(10);
  187. } while (!healthy());
  188. hal.scheduler->delay(100);
  189. }
  190. // now average over 5 values for the ground pressure settings
  191. float sum_pressure[BARO_MAX_INSTANCES] = {0};
  192. uint8_t count[BARO_MAX_INSTANCES] = {0};
  193. const uint8_t num_samples = 5;
  194. for (uint8_t c = 0; c < num_samples; c++) {
  195. uint32_t tstart = AP_HAL::millis();
  196. do {
  197. update();
  198. if (AP_HAL::millis() - tstart > 500) {
  199. AP_BoardConfig::sensor_config_error("Baro: unable to calibrate");
  200. }
  201. } while (!healthy());
  202. for (uint8_t i=0; i<_num_sensors; i++) {
  203. if (healthy(i)) {
  204. sum_pressure[i] += sensors[i].pressure;
  205. count[i] += 1;
  206. }
  207. }
  208. hal.scheduler->delay(100);
  209. }
  210. for (uint8_t i=0; i<_num_sensors; i++) {
  211. if (count[i] == 0) {
  212. sensors[i].calibrated = false;
  213. } else {
  214. if (save) {
  215. sensors[i].ground_pressure.set_and_save(sum_pressure[i] / count[i]);
  216. }
  217. }
  218. }
  219. _guessed_ground_temperature = get_external_temperature();
  220. // panic if all sensors are not calibrated
  221. uint8_t num_calibrated = 0;
  222. for (uint8_t i=0; i<_num_sensors; i++) {
  223. if (sensors[i].calibrated) {
  224. BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);
  225. num_calibrated++;
  226. }
  227. }
  228. if (num_calibrated) {
  229. return;
  230. }
  231. AP_BoardConfig::sensor_config_error("AP_Baro: all sensors uncalibrated");
  232. }
  233. /*
  234. update the barometer calibration
  235. this updates the baro ground calibration to the current values. It
  236. can be used before arming to keep the baro well calibrated
  237. */
  238. void AP_Baro::update_calibration()
  239. {
  240. const uint32_t now = AP_HAL::millis();
  241. const bool do_notify = now - _last_notify_ms > 10000;
  242. if (do_notify) {
  243. _last_notify_ms = now;
  244. }
  245. for (uint8_t i=0; i<_num_sensors; i++) {
  246. if (healthy(i)) {
  247. float corrected_pressure = get_pressure(i) + sensors[i].p_correction;
  248. sensors[i].ground_pressure.set(corrected_pressure);
  249. }
  250. // don't notify the GCS too rapidly or we flood the link
  251. if (do_notify) {
  252. sensors[i].ground_pressure.notify();
  253. }
  254. }
  255. // always update the guessed ground temp
  256. _guessed_ground_temperature = get_external_temperature();
  257. // force EAS2TAS to recalculate
  258. _EAS2TAS = 0;
  259. }
  260. // return altitude difference in meters between current pressure and a
  261. // given base_pressure in Pascal
  262. float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const
  263. {
  264. float ret;
  265. float temp = get_ground_temperature() + C_TO_KELVIN;
  266. float scaling = pressure / base_pressure;
  267. // This is an exact calculation that is within +-2.5m of the standard
  268. // atmosphere tables in the troposphere (up to 11,000 m amsl).
  269. ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)));
  270. return ret;
  271. }
  272. // return current scale factor that converts from equivalent to true airspeed
  273. // valid for altitudes up to 10km AMSL
  274. // assumes standard atmosphere lapse rate
  275. float AP_Baro::get_EAS2TAS(void)
  276. {
  277. float altitude = get_altitude();
  278. if ((fabsf(altitude - _last_altitude_EAS2TAS) < 25.0f) && !is_zero(_EAS2TAS)) {
  279. // not enough change to require re-calculating
  280. return _EAS2TAS;
  281. }
  282. float pressure = get_pressure();
  283. if (is_zero(pressure)) {
  284. return 1.0f;
  285. }
  286. // only estimate lapse rate for the difference from the ground location
  287. // provides a more consistent reading then trying to estimate a complete
  288. // ISA model atmosphere
  289. float tempK = get_ground_temperature() + C_TO_KELVIN - ISA_LAPSE_RATE * altitude;
  290. const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK));
  291. if (!is_positive(eas2tas_squared)) {
  292. return 1.0f;
  293. }
  294. _EAS2TAS = sqrtf(eas2tas_squared);
  295. _last_altitude_EAS2TAS = altitude;
  296. return _EAS2TAS;
  297. }
  298. // return air density / sea level density - decreases as altitude climbs
  299. float AP_Baro::get_air_density_ratio(void)
  300. {
  301. const float eas2tas = get_EAS2TAS();
  302. if (eas2tas > 0.0f) {
  303. return 1.0f/(sq(eas2tas));
  304. } else {
  305. return 1.0f;
  306. }
  307. }
  308. // return current climb_rate estimate relative to time that calibrate()
  309. // was called. Returns climb rate in meters/s, positive means up
  310. // note that this relies on read() being called regularly to get new data
  311. float AP_Baro::get_climb_rate(void)
  312. {
  313. if (_hil.have_alt) {
  314. return _hil.climb_rate;
  315. }
  316. // we use a 7 point derivative filter on the climb rate. This seems
  317. // to produce somewhat reasonable results on real hardware
  318. return _climb_rate_filter.slope() * 1.0e3f;
  319. }
  320. // returns the ground temperature in degrees C, selecting either a user
  321. // provided one, or the internal estimate
  322. float AP_Baro::get_ground_temperature(void) const
  323. {
  324. if (is_zero(_user_ground_temperature)) {
  325. return _guessed_ground_temperature;
  326. } else {
  327. return _user_ground_temperature;
  328. }
  329. }
  330. /*
  331. set external temperature to be used for calibration (degrees C)
  332. */
  333. void AP_Baro::set_external_temperature(float temperature)
  334. {
  335. _external_temperature = temperature;
  336. _last_external_temperature_ms = AP_HAL::millis();
  337. }
  338. /*
  339. get the temperature in degrees C to be used for calibration purposes
  340. */
  341. float AP_Baro::get_external_temperature(const uint8_t instance) const
  342. {
  343. // if we have a recent external temperature then use it
  344. if (_last_external_temperature_ms != 0 && AP_HAL::millis() - _last_external_temperature_ms < 10000) {
  345. return _external_temperature;
  346. }
  347. #ifndef HAL_BUILD_AP_PERIPH
  348. // if we don't have an external temperature then try to use temperature
  349. // from the airspeed sensor
  350. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  351. if (airspeed != nullptr) {
  352. float temperature;
  353. if (airspeed->healthy() && airspeed->get_temperature(temperature)) {
  354. return temperature;
  355. }
  356. }
  357. #endif
  358. // if we don't have an external temperature and airspeed temperature
  359. // then use the minimum of the barometer temperature and 35 degrees C.
  360. // The reason for not just using the baro temperature is it tends to read high,
  361. // often 30 degrees above the actual temperature. That means the
  362. // EAS2TAS tends to be off by quite a large margin, as well as
  363. // the calculation of altitude difference betweeen two pressures
  364. // reporting a high temperature will cause the aircraft to
  365. // estimate itself as flying higher then it actually is.
  366. return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);
  367. }
  368. bool AP_Baro::_add_backend(AP_Baro_Backend *backend)
  369. {
  370. if (!backend) {
  371. return false;
  372. }
  373. if (_num_drivers >= BARO_MAX_DRIVERS) {
  374. AP_HAL::panic("Too many barometer drivers");
  375. }
  376. drivers[_num_drivers++] = backend;
  377. return true;
  378. }
  379. /*
  380. macro to add a backend with check for too many sensors
  381. We don't try to start more than the maximum allowed
  382. */
  383. #define ADD_BACKEND(backend) \
  384. do { _add_backend(backend); \
  385. if (_num_drivers == BARO_MAX_DRIVERS || \
  386. _num_sensors == BARO_MAX_INSTANCES) { \
  387. return; \
  388. } \
  389. } while (0)
  390. /*
  391. initialise the barometer object, loading backend drivers
  392. */
  393. void AP_Baro::init(void)
  394. {
  395. // ensure that there isn't a previous ground temperature saved
  396. if (!is_zero(_user_ground_temperature)) {
  397. _user_ground_temperature.set_and_save(0.0f);
  398. _user_ground_temperature.notify();
  399. }
  400. if (_hil_mode) {
  401. drivers[0] = new AP_Baro_HIL(*this);
  402. _num_drivers = 1;
  403. return;
  404. }
  405. #if HAL_WITH_UAVCAN
  406. // Detect UAVCAN Modules, try as many times as there are driver slots
  407. for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
  408. ADD_BACKEND(AP_Baro_UAVCAN::probe(*this));
  409. }
  410. #endif
  411. // macro for use by HAL_INS_PROBE_LIST
  412. #define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address)
  413. #if defined(HAL_BARO_PROBE_LIST)
  414. // probe list from BARO lines in hwdef.dat
  415. HAL_BARO_PROBE_LIST;
  416. #elif AP_FEATURE_BOARD_DETECT
  417. switch (AP_BoardConfig::get_board_type()) {
  418. case AP_BoardConfig::PX4_BOARD_PX4V1:
  419. #ifdef HAL_BARO_MS5611_I2C_BUS
  420. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  421. std::move(GET_I2C_DEVICE(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));
  422. #endif
  423. break;
  424. case AP_BoardConfig::PX4_BOARD_PIXHAWK:
  425. case AP_BoardConfig::PX4_BOARD_PHMINI:
  426. case AP_BoardConfig::PX4_BOARD_AUAV21:
  427. case AP_BoardConfig::PX4_BOARD_PH2SLIM:
  428. case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
  429. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  430. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  431. break;
  432. case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
  433. case AP_BoardConfig::PX4_BOARD_SP01:
  434. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  435. std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
  436. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  437. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  438. break;
  439. case AP_BoardConfig::PX4_BOARD_MINDPXV2:
  440. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  441. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  442. break;
  443. case AP_BoardConfig::PX4_BOARD_AEROFC:
  444. #ifdef HAL_BARO_MS5607_I2C_BUS
  445. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  446. std::move(GET_I2C_DEVICE(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
  447. AP_Baro_MS56XX::BARO_MS5607));
  448. #endif
  449. break;
  450. case AP_BoardConfig::VRX_BOARD_BRAIN54:
  451. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  452. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  453. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  454. std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
  455. #ifdef HAL_BARO_MS5611_SPI_IMU_NAME
  456. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  457. std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME))));
  458. #endif
  459. break;
  460. case AP_BoardConfig::VRX_BOARD_BRAIN51:
  461. case AP_BoardConfig::VRX_BOARD_BRAIN52:
  462. case AP_BoardConfig::VRX_BOARD_BRAIN52E:
  463. case AP_BoardConfig::VRX_BOARD_CORE10:
  464. case AP_BoardConfig::VRX_BOARD_UBRAIN51:
  465. case AP_BoardConfig::VRX_BOARD_UBRAIN52:
  466. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  467. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  468. break;
  469. case AP_BoardConfig::PX4_BOARD_PCNC1:
  470. ADD_BACKEND(AP_Baro_ICM20789::probe(*this,
  471. std::move(GET_I2C_DEVICE(1, 0x63)),
  472. std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME))));
  473. break;
  474. case AP_BoardConfig::PX4_BOARD_FMUV5:
  475. case AP_BoardConfig::PX4_BOARD_FMUV6:
  476. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  477. std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
  478. break;
  479. default:
  480. break;
  481. }
  482. #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
  483. SITL::SITL *sitl = AP::sitl();
  484. if (sitl == nullptr) {
  485. AP_HAL::panic("No SITL pointer");
  486. }
  487. if (sitl->baro_count > 1) {
  488. ::fprintf(stderr, "More than one baro not supported. Sorry.");
  489. }
  490. if (sitl->baro_count == 1) {
  491. ADD_BACKEND(new AP_Baro_SITL(*this));
  492. }
  493. #elif HAL_BARO_DEFAULT == HAL_BARO_HIL
  494. drivers[0] = new AP_Baro_HIL(*this);
  495. _num_drivers = 1;
  496. #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C
  497. ADD_BACKEND(AP_Baro_LPS2XH::probe_InvensenseIMU(*this,
  498. std::move(GET_I2C_DEVICE(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR)),
  499. HAL_BARO_LPS25H_I2C_IMU_ADDR));
  500. #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_I2C
  501. ADD_BACKEND(AP_Baro_ICM20789::probe(*this,
  502. std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
  503. std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_ICM))));
  504. #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_SPI
  505. ADD_BACKEND(AP_Baro_ICM20789::probe(*this,
  506. std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
  507. std::move(hal.spi->get_device("icm20789"))));
  508. #endif
  509. // can optionally have baro on I2C too
  510. if (_ext_bus >= 0) {
  511. #if APM_BUILD_TYPE(APM_BUILD_ArduSub)
  512. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  513. std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837));
  514. ADD_BACKEND(AP_Baro_KellerLD::probe(*this,
  515. std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR))));
  516. #else
  517. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  518. std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));
  519. #endif
  520. }
  521. #ifdef HAL_PROBE_EXTERNAL_I2C_BAROS
  522. _probe_i2c_barometers();
  523. #endif
  524. #if !defined(HAL_BARO_ALLOW_INIT_NO_BARO) // most boards requires external baro
  525. if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
  526. AP_BoardConfig::sensor_config_error("Baro: unable to initialise driver");
  527. }
  528. #endif
  529. }
  530. /*
  531. probe all the i2c barometers enabled with GND_PROBE_EXT. This is
  532. used on boards without a builtin barometer
  533. */
  534. void AP_Baro::_probe_i2c_barometers(void)
  535. {
  536. uint32_t probe = _baro_probe_ext.get();
  537. uint32_t mask = hal.i2c_mgr->get_bus_mask_external();
  538. if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
  539. // for the purpose of baro probing, treat CubeBlack internal i2c as external. It has
  540. // no internal i2c baros, so this is safe
  541. mask |= hal.i2c_mgr->get_bus_mask_internal();
  542. }
  543. // if the user has set GND_EXT_BUS then probe the bus given by that parameter
  544. int8_t ext_bus = _ext_bus;
  545. if (ext_bus >= 0) {
  546. mask = 1U << (uint8_t)ext_bus;
  547. }
  548. if (probe & PROBE_BMP085) {
  549. FOREACH_I2C_MASK(i,mask) {
  550. ADD_BACKEND(AP_Baro_BMP085::probe(*this,
  551. std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP085_I2C_ADDR))));
  552. }
  553. }
  554. if (probe & PROBE_BMP280) {
  555. FOREACH_I2C_MASK(i,mask) {
  556. ADD_BACKEND(AP_Baro_BMP280::probe(*this,
  557. std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR))));
  558. ADD_BACKEND(AP_Baro_BMP280::probe(*this,
  559. std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR2))));
  560. }
  561. }
  562. if (probe & PROBE_BMP388) {
  563. FOREACH_I2C_MASK(i,mask) {
  564. ADD_BACKEND(AP_Baro_BMP388::probe(*this,
  565. std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR))));
  566. ADD_BACKEND(AP_Baro_BMP388::probe(*this,
  567. std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR2))));
  568. }
  569. }
  570. if (probe & PROBE_MS5611) {
  571. FOREACH_I2C_MASK(i,mask) {
  572. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  573. std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5611_I2C_ADDR))));
  574. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  575. std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5611_I2C_ADDR2))));
  576. }
  577. }
  578. if (probe & PROBE_MS5607) {
  579. FOREACH_I2C_MASK(i,mask) {
  580. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  581. std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5607_I2C_ADDR)),
  582. AP_Baro_MS56XX::BARO_MS5607));
  583. }
  584. }
  585. if (probe & PROBE_MS5637) {
  586. FOREACH_I2C_MASK(i,mask) {
  587. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  588. std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5637_I2C_ADDR)),
  589. AP_Baro_MS56XX::BARO_MS5637));
  590. }
  591. }
  592. if (probe & PROBE_FBM320) {
  593. FOREACH_I2C_MASK(i,mask) {
  594. ADD_BACKEND(AP_Baro_FBM320::probe(*this,
  595. std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR))));
  596. ADD_BACKEND(AP_Baro_FBM320::probe(*this,
  597. std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR2))));
  598. }
  599. }
  600. if (probe & PROBE_DPS280) {
  601. FOREACH_I2C_MASK(i,mask) {
  602. ADD_BACKEND(AP_Baro_DPS280::probe(*this,
  603. std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR))));
  604. ADD_BACKEND(AP_Baro_DPS280::probe(*this,
  605. std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR2))));
  606. }
  607. }
  608. if (probe & PROBE_LPS25H) {
  609. FOREACH_I2C_MASK(i,mask) {
  610. ADD_BACKEND(AP_Baro_LPS2XH::probe(*this,
  611. std::move(GET_I2C_DEVICE(i, HAL_BARO_LPS25H_I2C_ADDR))));
  612. }
  613. }
  614. if (probe & PROBE_LPS25H) {
  615. FOREACH_I2C_MASK(i,mask) {
  616. ADD_BACKEND(AP_Baro_KellerLD::probe(*this,
  617. std::move(GET_I2C_DEVICE(i, HAL_BARO_KELLERLD_I2C_ADDR))));
  618. }
  619. }
  620. if (probe & PROBE_MS5837) {
  621. FOREACH_I2C_MASK(i,mask) {
  622. ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
  623. std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837));
  624. }
  625. }
  626. }
  627. bool AP_Baro::should_log() const
  628. {
  629. AP_Logger *logger = AP_Logger::get_singleton();
  630. if (logger == nullptr) {
  631. return false;
  632. }
  633. if (_log_baro_bit == (uint32_t)-1) {
  634. return false;
  635. }
  636. if (!logger->should_log(_log_baro_bit)) {
  637. return false;
  638. }
  639. return true;
  640. }
  641. /*
  642. call update on all drivers
  643. */
  644. void AP_Baro::update(void)
  645. {
  646. WITH_SEMAPHORE(_rsem);
  647. if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
  648. // If there's more than 1cm difference then slowly slew to it via LPF.
  649. // The EKF does not like step inputs so this keeps it happy.
  650. _alt_offset_active = (0.95f*_alt_offset_active) + (0.05f*_alt_offset);
  651. } else {
  652. _alt_offset_active = _alt_offset;
  653. }
  654. if (!_hil_mode) {
  655. for (uint8_t i=0; i<_num_drivers; i++) {
  656. drivers[i]->backend_update(i);
  657. }
  658. }
  659. for (uint8_t i=0; i<_num_sensors; i++) {
  660. if (sensors[i].healthy) {
  661. // update altitude calculation
  662. float ground_pressure = sensors[i].ground_pressure;
  663. if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
  664. sensors[i].ground_pressure = sensors[i].pressure;
  665. }
  666. float altitude = sensors[i].altitude;
  667. float corrected_pressure = sensors[i].pressure;
  668. altitude = ( 101325- corrected_pressure) / 9800.0f / _specific_gravity;//sensors[i].ground_pressure
  669. sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));
  670. if (sensors[i].alt_ok) {
  671. sensors[i].altitude = altitude + _alt_offset;
  672. }
  673. /*
  674. float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;
  675. if (sensors[i].type == BARO_TYPE_AIR) {
  676. altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure);
  677. } else if (sensors[i].type == BARO_TYPE_WATER) {
  678. //101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
  679. //No temperature or depth compensation for density of water.
  680. altitude = (sensors[i].ground_pressure - corrected_pressure) / 9800.0f / _specific_gravity;
  681. }
  682. // sanity check altitude
  683. sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));
  684. if (sensors[i].alt_ok) {
  685. sensors[i].altitude = altitude + _alt_offset_active;
  686. }*/
  687. }
  688. if (_hil.have_alt) {
  689. sensors[0].altitude = _hil.altitude;
  690. }
  691. if (_hil.have_last_update) {
  692. sensors[0].last_update_ms = _hil.last_update_ms;
  693. }
  694. }
  695. // ensure the climb rate filter is updated
  696. if (healthy()) {
  697. _climb_rate_filter.update(get_altitude(), get_last_update());
  698. }
  699. // choose primary sensor
  700. if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {
  701. _primary = _primary_baro;
  702. } else {
  703. _primary = 0;
  704. for (uint8_t i=0; i<_num_sensors; i++) {
  705. if (healthy(i)) {
  706. _primary = i;
  707. break;
  708. }
  709. }
  710. }
  711. // logging
  712. #ifndef HAL_NO_LOGGING
  713. if (should_log() && !AP::ahrs().have_ekf_logging()) {
  714. AP::logger().Write_Baro();
  715. }
  716. #endif
  717. }
  718. /*
  719. call accumulate on all drivers
  720. */
  721. void AP_Baro::accumulate(void)
  722. {
  723. for (uint8_t i=0; i<_num_drivers; i++) {
  724. drivers[i]->accumulate();
  725. }
  726. }
  727. /* register a new sensor, claiming a sensor slot. If we are out of
  728. slots it will panic
  729. */
  730. uint8_t AP_Baro::register_sensor(void)
  731. {
  732. if (_num_sensors >= BARO_MAX_INSTANCES) {
  733. AP_HAL::panic("Too many barometers");
  734. }
  735. return _num_sensors++;
  736. }
  737. /*
  738. check if all barometers are healthy
  739. */
  740. bool AP_Baro::all_healthy(void) const
  741. {
  742. for (uint8_t i=0; i<_num_sensors; i++) {
  743. if (!healthy(i)) {
  744. return false;
  745. }
  746. }
  747. return _num_sensors > 0;
  748. }
  749. // set a pressure correction from AP_TempCalibration
  750. void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
  751. {
  752. if (instance < _num_sensors) {
  753. sensors[instance].p_correction = p_correction;
  754. }
  755. }
  756. namespace AP {
  757. AP_Baro &baro()
  758. {
  759. return *AP_Baro::get_singleton();
  760. }
  761. };