#include "AP_Baro.h"
#include <stdio.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_CANManager/AP_CANManager.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_Baro_SITL.h"
#include "AP_Baro_BMP085.h"
#include "AP_Baro_BMP280.h"
#include "AP_Baro_BMP388.h"
#include "AP_Baro_BMP581.h"
#include "AP_Baro_SPL06.h"
#include "AP_Baro_KellerLD.h"
#include "AP_Baro_MS5611.h"
#include "AP_Baro_ICM20789.h"
#include "AP_Baro_LPS2XH.h"
#include "AP_Baro_FBM320.h"
#include "AP_Baro_DPS280.h"
#include "AP_Baro_Dummy.h"
#include "AP_Baro_DroneCAN.h"
#include "AP_Baro_MSP.h"
#include "AP_Baro_ExternalAHRS.h"
#include "AP_Baro_ICP101XX.h"
#include "AP_Baro_ICP201XX.h"
#include "AP_Baro_AUAV.h"
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#if AP_BARO_THST_COMP_ENABLED
#include <AP_Motors/AP_Motors.h>
#endif
#define INTERNAL_TEMPERATURE_CLAMP 35.0f
#ifndef HAL_BARO_FILTER_DEFAULT
#define HAL_BARO_FILTER_DEFAULT 0
#endif
#ifndef HAL_BARO_PROBE_EXT_DEFAULT
#define HAL_BARO_PROBE_EXT_DEFAULT 0
#endif
#ifndef HAL_BARO_EXTERNAL_BUS_DEFAULT
#define HAL_BARO_EXTERNAL_BUS_DEFAULT -1
#endif
#ifdef HAL_BUILD_AP_PERIPH
#define HAL_BARO_ALLOW_INIT_NO_BARO
#endif
#ifndef AP_FIELD_ELEVATION_ENABLED
#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub)
#endif
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_Baro::var_info[] = {
#ifndef HAL_BUILD_AP_PERIPH
AP_GROUPINFO_FLAGS("1_GND_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
AP_GROUPINFO("_GND_TEMP", 3, AP_Baro, _user_ground_temperature, 0),
AP_GROUPINFO("_ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
AP_GROUPINFO("_PRIMARY", 6, AP_Baro, _primary_baro, 0),
#endif
AP_GROUPINFO("_EXT_BUS", 7, AP_Baro, _ext_bus, HAL_BARO_EXTERNAL_BUS_DEFAULT),
AP_GROUPINFO_FRAME("_SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
#if BARO_MAX_INSTANCES > 1
AP_GROUPINFO_FLAGS("2_GND_PRESS", 9, AP_Baro, sensors[1].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#endif
#if BARO_MAX_INSTANCES > 2
AP_GROUPINFO_FLAGS("3_GND_PRESS", 11, AP_Baro, sensors[2].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#endif
AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED
AP_GROUPINFO("_PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),
#endif
AP_GROUPINFO_FLAGS("1_DEVID", 15, AP_Baro, sensors[0].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#if BARO_MAX_INSTANCES > 1
AP_GROUPINFO_FLAGS("2_DEVID", 16, AP_Baro, sensors[1].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#endif
#if BARO_MAX_INSTANCES > 2
AP_GROUPINFO_FLAGS("3_DEVID", 17, AP_Baro, sensors[2].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#endif
#if HAL_BARO_WIND_COMP_ENABLED
AP_SUBGROUPINFO(sensors[0].wind_coeff, "1_WCF_", 18, AP_Baro, WindCoeff),
#if BARO_MAX_INSTANCES > 1
AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff),
#endif
#if BARO_MAX_INSTANCES > 2
AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff),
#endif
#endif
#if AP_FIELD_ELEVATION_ENABLED
AP_GROUPINFO("_FIELD_ELV", 22, AP_Baro, _field_elevation, 0),
#endif
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
AP_GROUPINFO("_ALTERR_MAX", 23, AP_Baro, _alt_error_max, 2000),
AP_GROUPINFO("_OPTIONS", 24, AP_Baro, _options, 0),
#endif
#if AP_BARO_THST_COMP_ENABLED
AP_GROUPINFO("1_THST_SCALE", 25, AP_Baro, sensors[0].mot_scale, 0),
#endif
AP_GROUPEND
};
AP_Baro *AP_Baro::_singleton;
AP_Baro::AP_Baro()
{
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
_field_elevation_active = _field_elevation;
}
void AP_Baro::calibrate(bool save)
{
for (uint8_t i=0; i<_num_sensors; i++) {
sensors[i].calibrated = true;
sensors[i].alt_ok = true;
}
if (hal.util->was_watchdog_reset()) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset");
return;
}
#if AP_SIM_BARO_ENABLED
if (AP::sitl()->baro_count == 0) {
return;
}
#endif
#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");
return;
}
#endif
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer");
_alt_offset.set_and_save(0);
for (uint8_t i = 0; i < 10; i++) {
uint32_t tstart = AP_HAL::millis();
do {
update();
if (AP_HAL::millis() - tstart > 500) {
AP_BoardConfig::config_error("Baro: unable to calibrate");
}
hal.scheduler->delay(10);
} while (!healthy());
hal.scheduler->delay(100);
}
float sum_pressure[BARO_MAX_INSTANCES] = {0};
uint8_t count[BARO_MAX_INSTANCES] = {0};
const uint8_t num_samples = 5;
for (uint8_t c = 0; c < num_samples; c++) {
uint32_t tstart = AP_HAL::millis();
do {
update();
if (AP_HAL::millis() - tstart > 500) {
AP_BoardConfig::config_error("Baro: unable to calibrate");
}
} while (!healthy());
for (uint8_t i=0; i<_num_sensors; i++) {
if (healthy(i)) {
sum_pressure[i] += sensors[i].pressure;
count[i] += 1;
}
}
hal.scheduler->delay(100);
}
for (uint8_t i=0; i<_num_sensors; i++) {
if (count[i] == 0) {
sensors[i].calibrated = false;
} else {
if (save) {
float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i], _field_elevation_active);
sensors[i].ground_pressure.set_and_save(p0_sealevel);
}
}
}
_guessed_ground_temperature = get_external_temperature();
uint8_t num_calibrated = 0;
for (uint8_t i=0; i<_num_sensors; i++) {
if (sensors[i].calibrated) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1);
num_calibrated++;
}
}
if (num_calibrated) {
return;
}
AP_BoardConfig::config_error("Baro: all sensors uncalibrated");
}
void AP_Baro::update_calibration()
{
const uint32_t now = AP_HAL::millis();
const bool do_notify = now - _last_notify_ms > 10000;
if (do_notify) {
_last_notify_ms = now;
}
for (uint8_t i=0; i<_num_sensors; i++) {
if (healthy(i)) {
float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction, _field_elevation_active);
sensors[i].ground_pressure.set(corrected_pressure);
}
if (do_notify) {
sensors[i].ground_pressure.notify();
}
}
_guessed_ground_temperature = get_external_temperature();
}
float AP_Baro::_get_air_density_ratio(void)
{
const float eas2tas = _get_EAS2TAS();
if (eas2tas > 0.0f) {
return 1.0f/(sq(eas2tas));
} else {
return 1.0f;
}
}
float AP_Baro::get_climb_rate(void)
{
return _climb_rate_filter.slope() * 1.0e3f;
}
float AP_Baro::get_ground_temperature(void) const
{
if (is_zero(_user_ground_temperature)) {
return _guessed_ground_temperature;
} else {
return _user_ground_temperature;
}
}
void AP_Baro::set_external_temperature(float temperature)
{
_external_temperature = temperature;
_last_external_temperature_ms = AP_HAL::millis();
}
float AP_Baro::get_external_temperature(const uint8_t instance) const
{
if (_last_external_temperature_ms != 0 && AP_HAL::millis() - _last_external_temperature_ms < 10000) {
return _external_temperature;
}
#ifndef HAL_BUILD_AP_PERIPH
#if AP_AIRSPEED_ENABLED
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (airspeed != nullptr) {
float temperature;
if (airspeed->healthy() && airspeed->get_temperature(temperature)) {
return temperature;
}
}
#endif
#endif
return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP);
}
bool AP_Baro::_add_backend(AP_Baro_Backend *backend)
{
if (!backend) {
return false;
}
if (_num_drivers >= ARRAY_SIZE(drivers)) {
AP_HAL::panic("Too many barometer drivers");
}
drivers[_num_drivers++] = backend;
return true;
}
bool AP_Baro::_i2c_sensor_is_registered(uint8_t bus, uint8_t address) const
{
for (int i=0; i<_num_sensors; ++i) {
if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==
AP_HAL::Device::change_bus_id(uint32_t(sensors[i].bus_id.get()), 0)) {
return true;
}
}
return false;
}
#define RETURN_IF_NO_SPACE \
do { \
if (_num_drivers == BARO_MAX_DRIVERS || \
_num_sensors == BARO_MAX_INSTANCES) { \
return; \
} \
} while (0)
#define GET_I2C_DEVICE_PTR(bus, address) _i2c_sensor_is_registered(bus, address)?nullptr:hal.i2c_mgr->get_device_ptr(bus, address)
void AP_Baro::probe_i2c_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), uint8_t bus, uint8_t addr)
{
auto *dev = GET_I2C_DEVICE_PTR(bus, addr);
probe_dev(probefn, dev);
}
void AP_Baro::probe_spi_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), const char *name)
{
auto *dev = hal.spi->get_device_ptr(name);
probe_dev(probefn, dev);
}
void AP_Baro::probe_dev(AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&), AP_HAL::Device *dev)
{
if (dev == nullptr) {
return;
}
AP_Baro_Backend *backend = probefn(*this, *dev);
if (backend == nullptr) {
delete dev;
return;
}
if (!_add_backend(backend)) {
delete backend;
delete dev;
return;
}
}
#if AP_BARO_LPS2XH_ENABLED
void AP_Baro::probe_lps2xh_via_Invensense_IMU(uint8_t bus, uint8_t addr, uint8_t mpu_addr)
{
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
AP_Baro_Backend *backend = AP_Baro_LPS2XH::probe_InvensenseIMU(*this, *i2c_dev, mpu_addr);
if (!_add_backend(backend)) {
delete i2c_dev;
}
}
#endif
#if AP_BARO_ICM20789_ENABLED
void AP_Baro::probe_icm20789(uint8_t bus, uint8_t addr, uint8_t mpu_bus, uint8_t mpu_addr)
{
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
AP_HAL::I2CDevice *mpu_dev = GET_I2C_DEVICE_PTR(mpu_bus, mpu_addr);
_probe_icm20789(i2c_dev, mpu_dev);
}
void AP_Baro::probe_icm20789(uint8_t bus, uint8_t addr, const char *mpu_name)
{
auto *i2c_dev = GET_I2C_DEVICE_PTR(bus, addr);
AP_HAL::SPIDevice *mpu_dev = hal.spi->get_device_ptr(mpu_name);
_probe_icm20789(i2c_dev, mpu_dev);
}
void AP_Baro::_probe_icm20789(AP_HAL::I2CDevice *i2c_dev, AP_HAL::Device *mpu_dev)
{
if (i2c_dev == nullptr) {
return;
}
if (mpu_dev == nullptr) {
delete i2c_dev;
return;
}
AP_Baro_Backend *backend = AP_Baro_ICM20789::probe(*this, *i2c_dev, *mpu_dev);
if (!_add_backend(backend)) {
delete i2c_dev;
delete mpu_dev;
}
}
#endif
void AP_Baro::init(void)
{
init_done = true;
if (!is_zero(_field_elevation)) {
_field_elevation.set_and_save(0.0f);
_field_elevation.notify();
}
for (auto &sensor : sensors) {
sensor.bus_id.set(0);
}
#if AP_SIM_BARO_ENABLED
SITL::SIM *sitl = AP::sitl();
if (sitl == nullptr) {
AP_HAL::panic("No SITL pointer");
}
#if !AP_TEST_DRONECAN_DRIVERS
for(uint8_t i = 0; i < sitl->baro_count; i++) {
_add_backend(NEW_NOTHROW AP_Baro_SITL(*this));
RETURN_IF_NO_SPACE;
}
#endif
#endif
#if AP_BARO_DRONECAN_ENABLED
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
_add_backend(AP_Baro_DroneCAN::probe(*this));
RETURN_IF_NO_SPACE;
}
#endif
#if AP_BARO_EXTERNALAHRS_ENABLED
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO);
if (serial_port >= 0) {
_add_backend(NEW_NOTHROW AP_Baro_ExternalAHRS(*this, serial_port));
RETURN_IF_NO_SPACE;
}
#endif
#if AP_SIM_BARO_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_BARO_MS5611_ENABLED
probe_i2c_dev(AP_Baro_MS5611::probe, _ext_bus, HAL_BARO_MS5611_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
return;
#endif
#if defined(HAL_BARO_PROBE_LIST)
HAL_BARO_PROBE_LIST;
#elif AP_FEATURE_BOARD_DETECT
switch (AP_BoardConfig::get_board_type()) {
case AP_BoardConfig::PX4_BOARD_PX4V1:
#if AP_BARO_MS5611_ENABLED && defined(HAL_BARO_MS5611_I2C_BUS)
probe_i2c_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
break;
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
case AP_BoardConfig::PX4_BOARD_PHMINI:
case AP_BoardConfig::PX4_BOARD_AUAV21:
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
case AP_BoardConfig::PX4_BOARD_FMUV6:
#if AP_BARO_MS5611_ENABLED
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_NAME);
RETURN_IF_NO_SPACE;
#endif
break;
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
#if AP_BARO_MS5611_ENABLED
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_SPI_EXT_NAME);
RETURN_IF_NO_SPACE;
probe_spi_dev(AP_Baro_MS5611::probe, HAL_BARO_MS5611_NAME);
RETURN_IF_NO_SPACE;
#endif
break;
case AP_BoardConfig::PX4_BOARD_AEROFC:
#if AP_BARO_MS5607_ENABLED
#ifdef HAL_BARO_MS5607_I2C_BUS
probe_i2c_dev(AP_Baro_MS5607::probe, HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
#endif
break;
default:
break;
}
#endif
if (_ext_bus >= 0) {
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if AP_BARO_MS5837_ENABLED
probe_i2c_dev(AP_Baro_MS5837::probe, _ext_bus, HAL_BARO_MS5837_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
#if AP_BARO_KELLERLD_ENABLED
probe_i2c_dev(AP_Baro_KellerLD::probe, _ext_bus, HAL_BARO_KELLERLD_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
#else
#if AP_BARO_MS5611_ENABLED
probe_i2c_dev(AP_Baro_MS5611::probe, _ext_bus, HAL_BARO_MS5611_I2C_ADDR);
RETURN_IF_NO_SPACE;
#endif
#endif
}
#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES
_probe_i2c_barometers();
RETURN_IF_NO_SPACE;
#endif
#if AP_BARO_MSP_ENABLED
if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) {
msp_instance_mask |= 1;
}
for (uint8_t i=0; i<8; i++) {
if (msp_instance_mask & (1U<<i)) {
_add_backend(NEW_NOTHROW AP_Baro_MSP(*this, i));
RETURN_IF_NO_SPACE;
}
}
#endif
#if !defined(HAL_BARO_ALLOW_INIT_NO_BARO)
#if AP_SIM_BARO_ENABLED
if (sitl->baro_count == 0) {
return;
}
#endif
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
AP_BoardConfig::config_error("Baro: unable to initialise driver");
}
#endif
#ifdef HAL_BUILD_AP_PERIPH
for (uint8_t i=0; i<_num_sensors; i++) {
sensors[i].calibrated = true;
sensors[i].alt_ok = true;
}
#endif
}
#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES
void AP_Baro::_probe_i2c_barometers(void)
{
uint32_t probe = _baro_probe_ext.get();
(void)probe;
uint32_t mask = hal.i2c_mgr->get_bus_mask_external();
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
mask |= hal.i2c_mgr->get_bus_mask_internal();
}
int8_t ext_bus = _ext_bus;
if (ext_bus >= 0) {
mask = 1U << (uint8_t)ext_bus;
}
static const struct BaroProbeSpec {
uint32_t bit;
AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::Device&);
uint8_t addr;
} baroprobespec[] {
#if AP_BARO_BMP085_ENABLED
{ PROBE_BMP085, AP_Baro_BMP085::probe, HAL_BARO_BMP085_I2C_ADDR },
#endif
#if AP_BARO_BMP280_ENABLED
{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR },
{ PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR2 },
#endif
#if AP_BARO_SPL06_ENABLED
{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR },
{ PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR2 },
#endif
#if AP_BARO_BMP388_ENABLED
{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR },
{ PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR2 },
#endif
#if AP_BARO_BMP581_ENABLED
{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR },
{ PROBE_BMP581, AP_Baro_BMP581::probe, HAL_BARO_BMP581_I2C_ADDR2 },
#endif
#if AP_BARO_MS5611_ENABLED
{ PROBE_MS5611, AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_ADDR },
{ PROBE_MS5611, AP_Baro_MS5611::probe, HAL_BARO_MS5611_I2C_ADDR2 },
#endif
#if AP_BARO_MS5607_ENABLED
{ PROBE_MS5607, AP_Baro_MS5607::probe, HAL_BARO_MS5607_I2C_ADDR },
#endif
#if AP_BARO_MS5637_ENABLED
{ PROBE_MS5637, AP_Baro_MS5637::probe, HAL_BARO_MS5637_I2C_ADDR },
#endif
#if AP_BARO_FBM320_ENABLED
{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR },
{ PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR2 },
#endif
#if AP_BARO_DPS280_ENABLED
{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR },
{ PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR2 },
#endif
#if AP_BARO_LPS2XH_ENABLED
{ PROBE_LPS25H, AP_Baro_LPS2XH::probe, HAL_BARO_LPS25H_I2C_ADDR },
#endif
#if AP_BARO_AUAV_ENABLED
{ PROBE_AUAV, AP_Baro_AUAV::probe, HAL_BARO_AUAV_I2C_ADDR },
#endif
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if AP_BARO_KELLERLD_ENABLED
{ PROBE_KELLER, AP_Baro_KellerLD::probe, HAL_BARO_KELLERLD_I2C_ADDR },
#endif
#if AP_BARO_MS5837_ENABLED
{ PROBE_MS5837, AP_Baro_MS5837::probe, HAL_BARO_MS5837_I2C_ADDR },
#endif
#endif
};
for (const auto &spec : baroprobespec) {
if (!(probe & spec.bit)) {
continue;
}
FOREACH_I2C_MASK(i, mask) {
probe_i2c_dev(spec.probefn, i, spec.addr);
RETURN_IF_NO_SPACE;
}
}
}
#endif
#if HAL_LOGGING_ENABLED
bool AP_Baro::should_log() const
{
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
return false;
}
if (_log_baro_bit == (uint32_t)-1) {
return false;
}
if (!logger->should_log(_log_baro_bit)) {
return false;
}
return true;
}
#endif
void AP_Baro::update(void)
{
WITH_SEMAPHORE(_rsem);
if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
_alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset);
} else {
_alt_offset_active = _alt_offset;
}
#if HAL_LOGGING_ENABLED
bool old_primary_healthy = sensors[_primary].healthy;
#endif
for (uint8_t i=0; i<_num_drivers; i++) {
drivers[i]->backend_update(i);
}
for (uint8_t i=0; i<_num_sensors; i++) {
if (sensors[i].healthy) {
float ground_pressure = sensors[i].ground_pressure;
if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
sensors[i].ground_pressure.set(sensors[i].pressure);
}
float altitude = sensors[i].altitude;
float corrected_pressure = sensors[i].pressure + sensors[i].p_correction;
if (sensors[i].type == BARO_TYPE_AIR) {
#if HAL_BARO_WIND_COMP_ENABLED
corrected_pressure -= wind_pressure_correction(i);
#endif
#if AP_BARO_THST_COMP_ENABLED
corrected_pressure -= thrust_pressure_correction(i);
#endif
#if (HAL_BARO_WIND_COMP_ENABLED || AP_BARO_THST_COMP_ENABLED)
sensors[i].corrected_pressure = corrected_pressure;
#endif
altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure);
altitude -= _field_elevation_active;
} else if (sensors[i].type == BARO_TYPE_WATER) {
altitude = (sensors[i].ground_pressure - corrected_pressure) / 9800.0f / _specific_gravity;
}
sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));
if (sensors[i].alt_ok) {
sensors[i].altitude = altitude + _alt_offset_active;
}
}
}
if (healthy()) {
_climb_rate_filter.update(get_altitude(), get_last_update());
}
if (_primary_baro >= 0 && _primary_baro < _num_sensors && healthy(_primary_baro)) {
_primary = _primary_baro;
} else {
_primary = 0;
for (uint8_t i=0; i<_num_sensors; i++) {
if (healthy(i)) {
_primary = i;
break;
}
}
}
#if AP_FIELD_ELEVATION_ENABLED
update_field_elevation();
#endif
#if HAL_LOGGING_ENABLED
if (should_log()) {
Write_Baro();
}
#define MASK_LOG_ANY 0xFFFF
if (sensors[_primary].healthy != old_primary_healthy) {
if (AP::logger().should_log(MASK_LOG_ANY)) {
const LogErrorCode code = sensors[_primary].healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;
AP::logger().Write_Error(LogErrorSubsystem::BARO, code);
}
}
#endif
}
#ifdef HAL_BUILD_AP_PERIPH
bool AP_Baro::healthy(uint8_t instance) const {
if (instance >= BARO_MAX_INSTANCES) {
return false;
}
return sensors[instance].healthy;
}
#else
bool AP_Baro::healthy(uint8_t instance) const {
if (instance >= BARO_MAX_INSTANCES) {
return false;
}
return sensors[instance].healthy && sensors[instance].alt_ok && sensors[instance].calibrated;
}
#endif
void AP_Baro::update_field_elevation(void)
{
#if AP_FIELD_ELEVATION_ENABLED
const uint32_t now_ms = AP_HAL::millis();
bool new_field_elev = false;
const bool armed = hal.util->get_soft_armed();
if (now_ms - _field_elevation_last_ms >= 1000) {
if (is_zero(_field_elevation_active) &&
is_zero(_field_elevation)) {
Location origin;
if (!armed && AP::ahrs().get_origin(origin)) {
_field_elevation_active = origin.alt * 0.01;
if (is_zero(_field_elevation_active)) {
_field_elevation_active = 0.001f;
}
new_field_elev = true;
}
} else if (fabsf(_field_elevation_active-_field_elevation) > 1.0 &&
!is_zero(_field_elevation)) {
if (!armed) {
_field_elevation_active = _field_elevation;
new_field_elev = true;
} else {
_field_elevation.set(_field_elevation_active);
_field_elevation.notify();
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed");
}
}
}
if (new_field_elev && !armed) {
_field_elevation_last_ms = now_ms;
AP::ahrs().resetHeightDatum();
update_calibration();
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active);
}
#endif
}
#if AP_BARO_THST_COMP_ENABLED
float AP_Baro::thrust_pressure_correction(uint8_t instance)
{
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_COPTER_OR_HELI
const AP_Motors* motors = AP::motors();
if (motors == nullptr) {
return 0.0f;
}
const float motors_throttle = MAX(0,motors->get_throttle_out());
return sensors[instance].mot_scale * motors_throttle;
#else
return 0.0f;
#endif
}
#endif
uint8_t AP_Baro::register_sensor(void)
{
if (_num_sensors >= ARRAY_SIZE(sensors)) {
AP_HAL::panic("Too many barometers");
}
return _num_sensors++;
}
bool AP_Baro::all_healthy(void) const
{
for (uint8_t i=0; i<_num_sensors; i++) {
if (!healthy(i)) {
return false;
}
}
return _num_sensors > 0;
}
void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction)
{
if (instance < _num_sensors) {
sensors[instance].p_correction = p_correction;
}
}
#if AP_BARO_MSP_ENABLED
void AP_Baro::handle_msp(const MSP::msp_baro_data_message_t &pkt)
{
if (pkt.instance > 7) {
return;
}
if (!init_done) {
msp_instance_mask |= 1U<<pkt.instance;
} else if (msp_instance_mask != 0) {
for (uint8_t i=0; i<_num_drivers; i++) {
drivers[i]->handle_msp(pkt);
}
}
}
#endif
#if AP_BARO_EXTERNALAHRS_ENABLED
void AP_Baro::handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt)
{
for (uint8_t i=0; i<_num_drivers; i++) {
drivers[i]->handle_external(pkt);
}
}
#endif
bool AP_Baro::arming_checks(size_t buflen, char *buffer) const
{
if (!all_healthy()) {
hal.util->snprintf(buffer, buflen, "not healthy");
return false;
}
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
const auto &gps = AP::gps();
if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) {
const float alt_amsl = gps.location().alt*0.01;
const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure());
const float error = fabsf(alt_amsl - alt_pressure);
if (error > _alt_error_max) {
hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error);
return false;
}
}
#endif
return true;
}
namespace AP {
AP_Baro &baro()
{
return *AP_Baro::get_singleton();
}
};