Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Baro/AP_Baro.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16* APM_Baro.cpp - barometer driver17*18*/19#include "AP_Baro.h"2021#include <utility>22#include <stdio.h>2324#include <GCS_MAVLink/GCS.h>25#include <AP_Common/AP_Common.h>26#include <AP_HAL/AP_HAL.h>27#include <AP_Math/AP_Math.h>28#include <AP_BoardConfig/AP_BoardConfig.h>29#include <AP_CANManager/AP_CANManager.h>30#include <AP_Vehicle/AP_Vehicle_Type.h>31#include <AP_HAL/I2CDevice.h>3233#include "AP_Baro_SITL.h"34#include "AP_Baro_BMP085.h"35#include "AP_Baro_BMP280.h"36#include "AP_Baro_BMP388.h"37#include "AP_Baro_BMP581.h"38#include "AP_Baro_SPL06.h"39#include "AP_Baro_KellerLD.h"40#include "AP_Baro_MS5611.h"41#include "AP_Baro_ICM20789.h"42#include "AP_Baro_LPS2XH.h"43#include "AP_Baro_FBM320.h"44#include "AP_Baro_DPS280.h"45#include "AP_Baro_Dummy.h"46#include "AP_Baro_DroneCAN.h"47#include "AP_Baro_MSP.h"48#include "AP_Baro_ExternalAHRS.h"49#include "AP_Baro_ICP101XX.h"50#include "AP_Baro_ICP201XX.h"5152#include <AP_Airspeed/AP_Airspeed.h>53#include <AP_AHRS/AP_AHRS.h>54#include <AP_Arming/AP_Arming.h>55#include <AP_Logger/AP_Logger.h>56#include <AP_GPS/AP_GPS.h>57#include <AP_Vehicle/AP_Vehicle.h>5859#define INTERNAL_TEMPERATURE_CLAMP 35.0f6061#ifndef HAL_BARO_FILTER_DEFAULT62#define HAL_BARO_FILTER_DEFAULT 0 // turned off by default63#endif6465#ifndef HAL_BARO_PROBE_EXT_DEFAULT66#define HAL_BARO_PROBE_EXT_DEFAULT 067#endif6869#ifndef HAL_BARO_EXTERNAL_BUS_DEFAULT70#define HAL_BARO_EXTERNAL_BUS_DEFAULT -171#endif7273#ifdef HAL_BUILD_AP_PERIPH74#define HAL_BARO_ALLOW_INIT_NO_BARO75#endif7677#ifndef AP_FIELD_ELEVATION_ENABLED78#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub)79#endif8081extern const AP_HAL::HAL& hal;8283// table of user settable parameters84const AP_Param::GroupInfo AP_Baro::var_info[] = {85// NOTE: Index numbers 0 and 1 were for the old integer86// ground temperature and pressure8788#ifndef HAL_BUILD_AP_PERIPH89// @Param: 1_GND_PRESS90// @DisplayName: Ground Pressure91// @Description: calibrated ground pressure in Pascals92// @Units: Pa93// @Increment: 194// @ReadOnly: True95// @Volatile: True96// @User: Advanced97AP_GROUPINFO_FLAGS("1_GND_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),9899// @Param: _GND_TEMP100// @DisplayName: ground temperature101// @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.102// @Units: degC103// @Increment: 1104// @Volatile: True105// @User: Advanced106AP_GROUPINFO("_GND_TEMP", 3, AP_Baro, _user_ground_temperature, 0),107108// index 4 reserved for old AP_Int8 version in legacy FRAM109//AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),110111// @Param: _ALT_OFFSET112// @DisplayName: altitude offset113// @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.114// @Units: m115// @Increment: 0.1116// @User: Advanced117AP_GROUPINFO("_ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),118119// @Param: _PRIMARY120// @DisplayName: Primary barometer121// @Description: This selects which barometer will be the primary if multiple barometers are found122// @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro123// @User: Advanced124AP_GROUPINFO("_PRIMARY", 6, AP_Baro, _primary_baro, 0),125#endif // HAL_BUILD_AP_PERIPH126127// @Param: _EXT_BUS128// @DisplayName: External baro bus129// @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 BARO_PROBE_EXT parameter.130// @Values: -1:Disabled,0:Bus0,1:Bus1,6:Bus6131// @User: Advanced132AP_GROUPINFO("_EXT_BUS", 7, AP_Baro, _ext_bus, HAL_BARO_EXTERNAL_BUS_DEFAULT),133134// @Param{Sub}: _SPEC_GRAV135// @DisplayName: Specific Gravity (For water depth measurement)136// @Description: This sets the specific gravity of the fluid when flying an underwater ROV.137// @Values: 1.0:Freshwater,1.024:Saltwater138AP_GROUPINFO_FRAME("_SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),139140#if BARO_MAX_INSTANCES > 1141// @Param: 2_GND_PRESS142// @DisplayName: Ground Pressure143// @Description: calibrated ground pressure in Pascals144// @Units: Pa145// @Increment: 1146// @ReadOnly: True147// @Volatile: True148// @User: Advanced149AP_GROUPINFO_FLAGS("2_GND_PRESS", 9, AP_Baro, sensors[1].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),150151// Slot 10 used to be TEMP2152#endif153154#if BARO_MAX_INSTANCES > 2155// @Param: 3_GND_PRESS156// @DisplayName: Absolute Pressure157// @Description: calibrated ground pressure in Pascals158// @Units: Pa159// @Increment: 1160// @ReadOnly: True161// @Volatile: True162// @User: Advanced163AP_GROUPINFO_FLAGS("3_GND_PRESS", 11, AP_Baro, sensors[2].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),164165// Slot 12 used to be TEMP3166#endif167168// @Param: _FLTR_RNG169// @DisplayName: Range in which sample is accepted170// @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.171// @Units: %172// @Range: 0 100173// @Increment: 1174AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),175176#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED177// @Param: _PROBE_EXT178// @DisplayName: External barometers to probe179// @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 BARO_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in BARO_EXT_BUS.180// @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP,13:BMP581181// @User: Advanced182AP_GROUPINFO("_PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),183#endif184185// @Param: 1_DEVID186// @DisplayName: Baro ID187// @Description: Barometer sensor ID, taking into account its type, bus and instance188// @ReadOnly: True189// @User: Advanced190AP_GROUPINFO_FLAGS("1_DEVID", 15, AP_Baro, sensors[0].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),191192#if BARO_MAX_INSTANCES > 1193// @Param: 2_DEVID194// @DisplayName: Baro ID2195// @Description: Barometer2 sensor ID, taking into account its type, bus and instance196// @ReadOnly: True197// @User: Advanced198AP_GROUPINFO_FLAGS("2_DEVID", 16, AP_Baro, sensors[1].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),199#endif200201#if BARO_MAX_INSTANCES > 2202// @Param: 3_DEVID203// @DisplayName: Baro ID3204// @Description: Barometer3 sensor ID, taking into account its type, bus and instance205// @ReadOnly: True206// @User: Advanced207AP_GROUPINFO_FLAGS("3_DEVID", 17, AP_Baro, sensors[2].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),208#endif209210#if HAL_BARO_WIND_COMP_ENABLED211// @Group: 1_WCF_212// @Path: AP_Baro_Wind.cpp213AP_SUBGROUPINFO(sensors[0].wind_coeff, "1_WCF_", 18, AP_Baro, WindCoeff),214215#if BARO_MAX_INSTANCES > 1216// @Group: 2_WCF_217// @Path: AP_Baro_Wind.cpp218AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff),219#endif220#if BARO_MAX_INSTANCES > 2221// @Group: 3_WCF_222// @Path: AP_Baro_Wind.cpp223AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff),224#endif225#endif // HAL_BARO_WIND_COMP_ENABLED226227#if AP_FIELD_ELEVATION_ENABLED228// @Param: _FIELD_ELV229// @DisplayName: field elevation230// @Description: User provided field elevation in meters. 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. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level.231// @Units: m232// @Increment: 0.1233// @Volatile: True234// @User: Advanced235AP_GROUPINFO("_FIELD_ELV", 22, AP_Baro, _field_elevation, 0),236#endif237238#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)239// @Param: _ALTERR_MAX240// @DisplayName: Altitude error maximum241// @Description: This is the maximum acceptable altitude discrepancy between GPS altitude and barometric presssure altitude calculated against a standard atmosphere for arming checks to pass. If you are getting an arming error due to this parameter then you may have a faulty or substituted barometer. A common issue is vendors replacing a MS5611 in a "Pixhawk" with a MS5607. If you have that issue then please see BARO_OPTIONS parameter to force the MS5611 to be treated as a MS5607. This check is disabled if the value is zero.242// @Units: m243// @Increment: 1244// @Range: 0 5000245// @User: Advanced246AP_GROUPINFO("_ALTERR_MAX", 23, AP_Baro, _alt_error_max, 2000),247248// @Param: _OPTIONS249// @DisplayName: Barometer options250// @Description: Barometer options251// @Bitmask: 0:Treat MS5611 as MS5607252// @User: Advanced253AP_GROUPINFO("_OPTIONS", 24, AP_Baro, _options, 0),254#endif255256AP_GROUPEND257};258259// singleton instance260AP_Baro *AP_Baro::_singleton;261262/*263AP_Baro constructor264*/265AP_Baro::AP_Baro()266{267_singleton = this;268269AP_Param::setup_object_defaults(this, var_info);270_field_elevation_active = _field_elevation;271}272273// calibrate the barometer. This must be called at least once before274// the altitude() or climb_rate() interfaces can be used275void AP_Baro::calibrate(bool save)276{277// start by assuming all sensors are calibrated (for healthy() test)278for (uint8_t i=0; i<_num_sensors; i++) {279sensors[i].calibrated = true;280sensors[i].alt_ok = true;281}282283if (hal.util->was_watchdog_reset()) {284GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset");285return;286}287288#if AP_SIM_BARO_ENABLED289if (AP::sitl()->baro_count == 0) {290return;291}292#endif293294#ifdef HAL_BARO_ALLOW_INIT_NO_BARO295if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {296GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");297return;298}299#endif300301GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");302303// reset the altitude offset when we calibrate. The altitude304// offset is supposed to be for within a flight305_alt_offset.set_and_save(0);306307// let the barometer settle for a full second after startup308// the MS5611 reads quite a long way off for the first second,309// leading to about 1m of error if we don't wait310for (uint8_t i = 0; i < 10; i++) {311uint32_t tstart = AP_HAL::millis();312do {313update();314if (AP_HAL::millis() - tstart > 500) {315AP_BoardConfig::config_error("Baro: unable to calibrate");316}317hal.scheduler->delay(10);318} while (!healthy());319hal.scheduler->delay(100);320}321322// now average over 5 values for the ground pressure settings323float sum_pressure[BARO_MAX_INSTANCES] = {0};324uint8_t count[BARO_MAX_INSTANCES] = {0};325const uint8_t num_samples = 5;326327for (uint8_t c = 0; c < num_samples; c++) {328uint32_t tstart = AP_HAL::millis();329do {330update();331if (AP_HAL::millis() - tstart > 500) {332AP_BoardConfig::config_error("Baro: unable to calibrate");333}334} while (!healthy());335for (uint8_t i=0; i<_num_sensors; i++) {336if (healthy(i)) {337sum_pressure[i] += sensors[i].pressure;338count[i] += 1;339}340}341hal.scheduler->delay(100);342}343for (uint8_t i=0; i<_num_sensors; i++) {344if (count[i] == 0) {345sensors[i].calibrated = false;346} else {347if (save) {348float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i], _field_elevation_active);349sensors[i].ground_pressure.set_and_save(p0_sealevel);350}351}352}353354_guessed_ground_temperature = get_external_temperature();355356// panic if all sensors are not calibrated357uint8_t num_calibrated = 0;358for (uint8_t i=0; i<_num_sensors; i++) {359if (sensors[i].calibrated) {360GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);361num_calibrated++;362}363}364if (num_calibrated) {365return;366}367AP_BoardConfig::config_error("Baro: all sensors uncalibrated");368}369370/*371update the barometer calibration372this updates the baro ground calibration to the current values. It373can be used before arming to keep the baro well calibrated374*/375void AP_Baro::update_calibration()376{377const uint32_t now = AP_HAL::millis();378const bool do_notify = now - _last_notify_ms > 10000;379if (do_notify) {380_last_notify_ms = now;381}382for (uint8_t i=0; i<_num_sensors; i++) {383if (healthy(i)) {384float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction, _field_elevation_active);385sensors[i].ground_pressure.set(corrected_pressure);386}387388// don't notify the GCS too rapidly or we flood the link389if (do_notify) {390sensors[i].ground_pressure.notify();391}392}393394// always update the guessed ground temp395_guessed_ground_temperature = get_external_temperature();396}397398399// return air density / sea level density - decreases as altitude climbs400float AP_Baro::_get_air_density_ratio(void)401{402const float eas2tas = _get_EAS2TAS();403if (eas2tas > 0.0f) {404return 1.0f/(sq(eas2tas));405} else {406return 1.0f;407}408}409410// return current climb_rate estimate relative to time that calibrate()411// was called. Returns climb rate in meters/s, positive means up412// note that this relies on read() being called regularly to get new data413float AP_Baro::get_climb_rate(void)414{415// we use a 7 point derivative filter on the climb rate. This seems416// to produce somewhat reasonable results on real hardware417return _climb_rate_filter.slope() * 1.0e3f;418}419420// returns the ground temperature in degrees C, selecting either a user421// provided one, or the internal estimate422float AP_Baro::get_ground_temperature(void) const423{424if (is_zero(_user_ground_temperature)) {425return _guessed_ground_temperature;426} else {427return _user_ground_temperature;428}429}430431432/*433set external temperature to be used for calibration (degrees C)434*/435void AP_Baro::set_external_temperature(float temperature)436{437_external_temperature = temperature;438_last_external_temperature_ms = AP_HAL::millis();439}440441/*442get the temperature in degrees C to be used for calibration purposes443*/444float AP_Baro::get_external_temperature(const uint8_t instance) const445{446// if we have a recent external temperature then use it447if (_last_external_temperature_ms != 0 && AP_HAL::millis() - _last_external_temperature_ms < 10000) {448return _external_temperature;449}450451#ifndef HAL_BUILD_AP_PERIPH452#if AP_AIRSPEED_ENABLED453// if we don't have an external temperature then try to use temperature454// from the airspeed sensor455AP_Airspeed *airspeed = AP_Airspeed::get_singleton();456if (airspeed != nullptr) {457float temperature;458if (airspeed->healthy() && airspeed->get_temperature(temperature)) {459return temperature;460}461}462#endif463#endif464465// if we don't have an external temperature and airspeed temperature466// then use the minimum of the barometer temperature and 35 degrees C.467// The reason for not just using the baro temperature is it tends to read high,468// often 30 degrees above the actual temperature. That means the469// EAS2TAS tends to be off by quite a large margin, as well as470// the calculation of altitude difference between two pressures471// reporting a high temperature will cause the aircraft to472// estimate itself as flying higher then it actually is.473return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);474}475476477bool AP_Baro::_add_backend(AP_Baro_Backend *backend)478{479if (!backend) {480return false;481}482if (_num_drivers >= BARO_MAX_DRIVERS) {483AP_HAL::panic("Too many barometer drivers");484}485drivers[_num_drivers++] = backend;486return true;487}488489/*490wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened491*/492bool AP_Baro::_have_i2c_driver(uint8_t bus, uint8_t address) const493{494for (int i=0; i<_num_drivers; ++i) {495if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==496AP_HAL::Device::change_bus_id(uint32_t(sensors[i].bus_id.get()), 0)) {497// device already has been defined.498return true;499}500}501return false;502}503504/*505macro to add a backend with check for too many sensors506We don't try to start more than the maximum allowed507*/508#define ADD_BACKEND(backend) \509do { _add_backend(backend); \510if (_num_drivers == BARO_MAX_DRIVERS || \511_num_sensors == BARO_MAX_INSTANCES) { \512return; \513} \514} while (0)515516/*517initialise the barometer object, loading backend drivers518*/519void AP_Baro::init(void)520{521init_done = true;522523// always set field elevation to zero on reboot in the case user524// fails to update. TBD automate sanity checking error bounds on525// on previously saved value at new location etc.526if (!is_zero(_field_elevation)) {527_field_elevation.set_and_save(0.0f);528_field_elevation.notify();529}530531// zero bus IDs before probing532for (uint8_t i = 0; i < BARO_MAX_INSTANCES; i++) {533sensors[i].bus_id.set(0);534}535536#if AP_SIM_BARO_ENABLED537SITL::SIM *sitl = AP::sitl();538if (sitl == nullptr) {539AP_HAL::panic("No SITL pointer");540}541#if !AP_TEST_DRONECAN_DRIVERS542// use dronecan instances instead of SITL instances543for(uint8_t i = 0; i < sitl->baro_count; i++) {544ADD_BACKEND(NEW_NOTHROW AP_Baro_SITL(*this));545}546#endif547#endif548549#if AP_BARO_DRONECAN_ENABLED550// Detect UAVCAN Modules, try as many times as there are driver slots551for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {552ADD_BACKEND(AP_Baro_DroneCAN::probe(*this));553}554#endif555556#if AP_BARO_EXTERNALAHRS_ENABLED557const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO);558if (serial_port >= 0) {559ADD_BACKEND(NEW_NOTHROW AP_Baro_ExternalAHRS(*this, serial_port));560}561#endif562563// macro for use by HAL_INS_PROBE_LIST564#define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address)565566#if AP_SIM_BARO_ENABLED567#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_BARO_MS56XX_ENABLED568ADD_BACKEND(AP_Baro_MS56XX::probe(*this,569std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));570#endif571// do not probe for other drivers when using simulation:572return;573#endif574575#if defined(HAL_BARO_PROBE_LIST)576// probe list from BARO lines in hwdef.dat577HAL_BARO_PROBE_LIST;578#elif AP_FEATURE_BOARD_DETECT579switch (AP_BoardConfig::get_board_type()) {580case AP_BoardConfig::PX4_BOARD_PX4V1:581#if AP_BARO_MS56XX_ENABLED && defined(HAL_BARO_MS5611_I2C_BUS)582ADD_BACKEND(AP_Baro_MS56XX::probe(*this,583std::move(GET_I2C_DEVICE(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));584#endif585break;586587case AP_BoardConfig::PX4_BOARD_PIXHAWK:588case AP_BoardConfig::PX4_BOARD_PHMINI:589case AP_BoardConfig::PX4_BOARD_AUAV21:590case AP_BoardConfig::PX4_BOARD_PH2SLIM:591case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:592#if AP_BARO_MS56XX_ENABLED593ADD_BACKEND(AP_Baro_MS56XX::probe(*this,594std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));595#endif596break;597598case AP_BoardConfig::PX4_BOARD_PIXHAWK2:599case AP_BoardConfig::PX4_BOARD_SP01:600#if AP_BARO_MS56XX_ENABLED601ADD_BACKEND(AP_Baro_MS56XX::probe(*this,602std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));603ADD_BACKEND(AP_Baro_MS56XX::probe(*this,604std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));605#endif606break;607608case AP_BoardConfig::PX4_BOARD_MINDPXV2:609#if AP_BARO_MS56XX_ENABLED610ADD_BACKEND(AP_Baro_MS56XX::probe(*this,611std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));612#endif613break;614615case AP_BoardConfig::PX4_BOARD_AEROFC:616#if AP_BARO_MS56XX_ENABLED617#ifdef HAL_BARO_MS5607_I2C_BUS618ADD_BACKEND(AP_Baro_MS56XX::probe(*this,619std::move(GET_I2C_DEVICE(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),620AP_Baro_MS56XX::BARO_MS5607));621#endif622#endif // AP_BARO_MS56XX_ENABLED623break;624625case AP_BoardConfig::VRX_BOARD_BRAIN54:626#if AP_BARO_MS56XX_ENABLED627ADD_BACKEND(AP_Baro_MS56XX::probe(*this,628std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));629ADD_BACKEND(AP_Baro_MS56XX::probe(*this,630std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));631#ifdef HAL_BARO_MS5611_SPI_IMU_NAME632ADD_BACKEND(AP_Baro_MS56XX::probe(*this,633std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME))));634#endif635#endif // AP_BARO_MS56XX_ENABLED636break;637638case AP_BoardConfig::VRX_BOARD_BRAIN51:639case AP_BoardConfig::VRX_BOARD_BRAIN52:640case AP_BoardConfig::VRX_BOARD_BRAIN52E:641case AP_BoardConfig::VRX_BOARD_CORE10:642case AP_BoardConfig::VRX_BOARD_UBRAIN51:643case AP_BoardConfig::VRX_BOARD_UBRAIN52:644#if AP_BARO_MS56XX_ENABLED645ADD_BACKEND(AP_Baro_MS56XX::probe(*this,646std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));647#endif // AP_BARO_MS56XX_ENABLED648break;649650case AP_BoardConfig::PX4_BOARD_PCNC1:651#if AP_BARO_ICM20789_ENABLED652ADD_BACKEND(AP_Baro_ICM20789::probe(*this,653std::move(GET_I2C_DEVICE(1, 0x63)),654std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME))));655#endif656break;657658case AP_BoardConfig::PX4_BOARD_FMUV5:659case AP_BoardConfig::PX4_BOARD_FMUV6:660#if AP_BARO_MS56XX_ENABLED661ADD_BACKEND(AP_Baro_MS56XX::probe(*this,662std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));663#endif664break;665666default:667break;668}669#elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C670ADD_BACKEND(AP_Baro_LPS2XH::probe_InvensenseIMU(*this,671std::move(GET_I2C_DEVICE(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR)),672HAL_BARO_LPS25H_I2C_IMU_ADDR));673#elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_I2C674ADD_BACKEND(AP_Baro_ICM20789::probe(*this,675std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),676std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_ICM))));677#elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_SPI678ADD_BACKEND(AP_Baro_ICM20789::probe(*this,679std::move(GET_I2C_DEVICE(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),680std::move(hal.spi->get_device("icm20789"))));681#endif682683// can optionally have baro on I2C too684if (_ext_bus >= 0) {685#if APM_BUILD_TYPE(APM_BUILD_ArduSub)686#if AP_BARO_MS56XX_ENABLED687ADD_BACKEND(AP_Baro_MS56XX::probe(*this,688std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837));689#endif690#if AP_BARO_KELLERLD_ENABLED691ADD_BACKEND(AP_Baro_KellerLD::probe(*this,692std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR))));693#endif694#else695#if AP_BARO_MS56XX_ENABLED696ADD_BACKEND(AP_Baro_MS56XX::probe(*this,697std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));698#endif699#endif700}701702#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES703_probe_i2c_barometers();704#endif705706#if AP_BARO_MSP_ENABLED707if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) {708// allow for late addition of MSP sensor709msp_instance_mask |= 1;710}711for (uint8_t i=0; i<8; i++) {712if (msp_instance_mask & (1U<<i)) {713ADD_BACKEND(NEW_NOTHROW AP_Baro_MSP(*this, i));714}715}716#endif717718#if !defined(HAL_BARO_ALLOW_INIT_NO_BARO) // most boards requires external baro719#if AP_SIM_BARO_ENABLED720if (sitl->baro_count == 0) {721return;722}723#endif724if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {725AP_BoardConfig::config_error("Baro: unable to initialise driver");726}727#endif728#ifdef HAL_BUILD_AP_PERIPH729// AP_Periph always is set calibrated. We only want the pressure,730// so ground calibration is unnecessary731for (uint8_t i=0; i<_num_sensors; i++) {732sensors[i].calibrated = true;733sensors[i].alt_ok = true;734}735#endif736}737738/*739probe all the i2c barometers enabled with BARO_PROBE_EXT. This is740used on boards without a builtin barometer741*/742void AP_Baro::_probe_i2c_barometers(void)743{744uint32_t probe = _baro_probe_ext.get();745(void)probe; // may be unused if most baros compiled out746uint32_t mask = hal.i2c_mgr->get_bus_mask_external();747if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {748// for the purpose of baro probing, treat CubeBlack internal i2c as external. It has749// no internal i2c baros, so this is safe750mask |= hal.i2c_mgr->get_bus_mask_internal();751}752// if the user has set BARO_EXT_BUS then probe the bus given by that parameter753int8_t ext_bus = _ext_bus;754if (ext_bus >= 0) {755mask = 1U << (uint8_t)ext_bus;756}757758static const struct BaroProbeSpec {759uint32_t bit;760AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::OwnPtr<AP_HAL::Device>);761uint8_t addr;762} baroprobespec[] {763#if AP_BARO_BMP085_ENABLED764{ PROBE_BMP085, AP_Baro_BMP085::probe, HAL_BARO_BMP085_I2C_ADDR },765#endif766#if AP_BARO_BMP280_ENABLED767{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR },768{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR2 },769#endif770#if AP_BARO_SPL06_ENABLED771{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR },772{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR2 },773#endif774#if AP_BARO_BMP388_ENABLED775{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR },776{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR2 },777#endif778#if AP_BARO_BMP581_ENABLED779{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR },780{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR2 },781#endif782#if AP_BARO_MS56XX_ENABLED783{ PROBE_MS5611, AP_Baro_MS56XX::probe_5611, HAL_BARO_MS5611_I2C_ADDR },784{ PROBE_MS5611, AP_Baro_MS56XX::probe_5611, HAL_BARO_MS5611_I2C_ADDR2 },785{ PROBE_MS5607, AP_Baro_MS56XX::probe_5607, HAL_BARO_MS5607_I2C_ADDR },786{ PROBE_MS5637, AP_Baro_MS56XX::probe_5637, HAL_BARO_MS5637_I2C_ADDR },787#endif788#if AP_BARO_FBM320_ENABLED789{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR },790{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR2 },791#endif792#if AP_BARO_DPS280_ENABLED793{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR },794{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR2 },795#endif796#if AP_BARO_LPS2XH_ENABLED797{ PROBE_LPS25H, AP_Baro_LPS2XH::probe, HAL_BARO_LPS25H_I2C_ADDR },798#endif799800#if APM_BUILD_TYPE(APM_BUILD_ArduSub)801#if AP_BARO_KELLERLD_ENABLED802{ PROBE_KELLER, AP_Baro_KellerLD::probe, HAL_BARO_KELLERLD_I2C_ADDR },803#endif804#if AP_BARO_MS56XX_ENABLED805{ PROBE_MS5837, AP_Baro_MS56XX::probe_5837, HAL_BARO_MS5837_I2C_ADDR },806#endif807#endif // APM_BUILD_TYPE(APM_BUILD_ArduSub)808};809810for (const auto &spec : baroprobespec) {811if (!(probe & spec.bit)) {812// not in mask to be probed for813continue;814}815FOREACH_I2C_MASK(i, mask) {816ADD_BACKEND(spec.probefn(*this, std::move(GET_I2C_DEVICE(i, spec.addr))));817}818}819}820821#if HAL_LOGGING_ENABLED822bool AP_Baro::should_log() const823{824AP_Logger *logger = AP_Logger::get_singleton();825if (logger == nullptr) {826return false;827}828if (_log_baro_bit == (uint32_t)-1) {829return false;830}831if (!logger->should_log(_log_baro_bit)) {832return false;833}834return true;835}836#endif837838/*839call update on all drivers840*/841void AP_Baro::update(void)842{843WITH_SEMAPHORE(_rsem);844845if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {846// If there's more than 1cm difference then slowly slew to it via LPF.847// The EKF does not like step inputs so this keeps it happy.848_alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset);849} else {850_alt_offset_active = _alt_offset;851}852853#if HAL_LOGGING_ENABLED854bool old_primary_healthy = sensors[_primary].healthy;855#endif856857for (uint8_t i=0; i<_num_drivers; i++) {858drivers[i]->backend_update(i);859}860861for (uint8_t i=0; i<_num_sensors; i++) {862if (sensors[i].healthy) {863// update altitude calculation864float ground_pressure = sensors[i].ground_pressure;865if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {866sensors[i].ground_pressure.set(sensors[i].pressure);867}868float altitude = sensors[i].altitude;869float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;870if (sensors[i].type == BARO_TYPE_AIR) {871#if HAL_BARO_WIND_COMP_ENABLED872corrected_pressure -= wind_pressure_correction(i);873#endif874altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure);875876// the ground pressure is references against the field elevation877altitude -= _field_elevation_active;878} else if (sensors[i].type == BARO_TYPE_WATER) {879//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.880//No temperature or depth compensation for density of water.881altitude = (sensors[i].ground_pressure - corrected_pressure) / 9800.0f / _specific_gravity;882}883// sanity check altitude884sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));885if (sensors[i].alt_ok) {886sensors[i].altitude = altitude + _alt_offset_active;887}888}889}890891// ensure the climb rate filter is updated892if (healthy()) {893_climb_rate_filter.update(get_altitude(), get_last_update());894}895896// choose primary sensor897if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {898_primary = _primary_baro;899} else {900_primary = 0;901for (uint8_t i=0; i<_num_sensors; i++) {902if (healthy(i)) {903_primary = i;904break;905}906}907}908#if AP_FIELD_ELEVATION_ENABLED909update_field_elevation();910#endif911912// logging913#if HAL_LOGGING_ENABLED914if (should_log()) {915Write_Baro();916}917918#define MASK_LOG_ANY 0xFFFF919920// log sensor healthy state change:921if (sensors[_primary].healthy != old_primary_healthy) {922if (AP::logger().should_log(MASK_LOG_ANY)) {923const LogErrorCode code = sensors[_primary].healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;924AP::logger().Write_Error(LogErrorSubsystem::BARO, code);925}926}927#endif928}929930#ifdef HAL_BUILD_AP_PERIPH931// calibration and alt check not valid for AP_Periph932bool AP_Baro::healthy(uint8_t instance) const {933// If the requested instance was outside max instances it is not healthy (it doesn't exist)934if (instance >= BARO_MAX_INSTANCES) {935return false;936}937return sensors[instance].healthy;938}939#else940bool AP_Baro::healthy(uint8_t instance) const {941// If the requested instance was outside max instances it is not healthy (it doesn't exist)942if (instance >= BARO_MAX_INSTANCES) {943return false;944}945return sensors[instance].healthy && sensors[instance].alt_ok && sensors[instance].calibrated;946}947#endif948949/*950update field elevation value951*/952void AP_Baro::update_field_elevation(void)953{954#if AP_FIELD_ELEVATION_ENABLED955const uint32_t now_ms = AP_HAL::millis();956bool new_field_elev = false;957const bool armed = hal.util->get_soft_armed();958if (now_ms - _field_elevation_last_ms >= 1000) {959if (is_zero(_field_elevation_active) &&960is_zero(_field_elevation)) {961// auto-set based on origin962Location origin;963if (!armed && AP::ahrs().get_origin(origin)) {964_field_elevation_active = origin.alt * 0.01;965new_field_elev = true;966}967} else if (fabsf(_field_elevation_active-_field_elevation) > 1.0 &&968!is_zero(_field_elevation)) {969// user has set field elevation970if (!armed) {971_field_elevation_active = _field_elevation;972new_field_elev = true;973} else {974_field_elevation.set(_field_elevation_active);975_field_elevation.notify();976GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed");977}978}979}980if (new_field_elev && !armed) {981_field_elevation_last_ms = now_ms;982AP::ahrs().resetHeightDatum();983update_calibration();984GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active);985}986#endif987}988989990/* register a new sensor, claiming a sensor slot. If we are out of991slots it will panic992*/993uint8_t AP_Baro::register_sensor(void)994{995if (_num_sensors >= BARO_MAX_INSTANCES) {996AP_HAL::panic("Too many barometers");997}998return _num_sensors++;999}100010011002/*1003check if all barometers are healthy1004*/1005bool AP_Baro::all_healthy(void) const1006{1007for (uint8_t i=0; i<_num_sensors; i++) {1008if (!healthy(i)) {1009return false;1010}1011}1012return _num_sensors > 0;1013}10141015// set a pressure correction from AP_TempCalibration1016void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)1017{1018if (instance < _num_sensors) {1019sensors[instance].p_correction = p_correction;1020}1021}10221023#if AP_BARO_MSP_ENABLED1024/*1025handle MSP barometer data1026*/1027void AP_Baro::handle_msp(const MSP::msp_baro_data_message_t &pkt)1028{1029if (pkt.instance > 7) {1030return;1031}1032if (!init_done) {1033msp_instance_mask |= 1U<<pkt.instance;1034} else if (msp_instance_mask != 0) {1035for (uint8_t i=0; i<_num_drivers; i++) {1036drivers[i]->handle_msp(pkt);1037}1038}1039}1040#endif10411042#if AP_BARO_EXTERNALAHRS_ENABLED1043/*1044handle ExternalAHRS barometer data1045*/1046void AP_Baro::handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt)1047{1048for (uint8_t i=0; i<_num_drivers; i++) {1049drivers[i]->handle_external(pkt);1050}1051}1052#endif // AP_BARO_EXTERNALAHRS_ENABLED10531054// returns false if we fail arming checks, in which case the buffer will be populated with a failure message1055bool AP_Baro::arming_checks(size_t buflen, char *buffer) const1056{1057if (!all_healthy()) {1058hal.util->snprintf(buffer, buflen, "not healthy");1059return false;1060}10611062#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)1063/*1064check for a pressure altitude discrepancy between GPS alt and1065baro alt this catches bad barometers, such as when a MS5607 has1066been substituted for a MS56111067*/1068const auto &gps = AP::gps();1069if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) {1070const float alt_amsl = gps.location().alt*0.01;1071// note the addition of _field_elevation_active as this is subtracted in get_altitude_difference()1072const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure());1073const float error = fabsf(alt_amsl - alt_pressure);1074if (error > _alt_error_max) {1075hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error);1076return false;1077}1078}1079#endif1080return true;1081}10821083namespace AP {10841085AP_Baro &baro()1086{1087return *AP_Baro::get_singleton();1088}10891090};109110921093