47 #define INTERNAL_TEMPERATURE_CLAMP 35.0f 49 #ifndef HAL_BARO_FILTER_DEFAULT 50 #define HAL_BARO_FILTER_DEFAULT 0 // turned off by default 110 #if BARO_MAX_INSTANCES > 1 124 #if BARO_MAX_INSTANCES > 2 166 gcs().
send_text(MAV_SEVERITY_INFO,
"Calibrating barometer");
181 for (uint8_t i = 0; i < 10; i++) {
187 "for more than 500ms in AP_Baro::calibrate [2]\r\n");
199 const uint8_t num_samples = 5;
201 for (uint8_t c = 0; c < num_samples; c++) {
207 "for more than 500ms in AP_Baro::calibrate [3]\r\n");
234 gcs().
send_text(MAV_SEVERITY_INFO,
"Barometer calibration complete");
275 float scaling = pressure / base_pressure;
279 ret = 153.8462f * temp * (1.0f - expf(0.190259
f * logf(scaling)));
309 if (eas2tas > 0.0
f) {
310 return 1.0f/(
sq(eas2tas));
322 return _hil.climb_rate;
387 #define ADD_BACKEND(backend) \ 388 do { _add_backend(backend); \ 389 if (_num_drivers == BARO_MAX_DRIVERS || \ 390 _num_sensors == BARO_MAX_INSTANCES) { \ 412 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 427 #if AP_FEATURE_BOARD_DETECT 430 #ifdef HAL_BARO_MS5611_I2C_BUS 464 #ifdef HAL_BARO_MS5607_I2C_BUS 476 #ifdef HAL_BARO_MS5611_SPI_IMU_NAME 501 #elif HAL_BARO_DEFAULT == HAL_BARO_HIL 504 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP085 508 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_I2C 511 #elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_SPI 514 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_I2C 517 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI 520 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5607_I2C 524 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5637_I2C 526 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)),
528 #elif HAL_BARO_DEFAULT == HAL_BARO_FBM320_I2C 530 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_FBM320_I2C_BUS, HAL_BARO_FBM320_I2C_ADDR))));
531 #elif HAL_BARO_DEFAULT == HAL_BARO_DPS280_I2C 533 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_DPS280_I2C_BUS, HAL_BARO_DPS280_I2C_ADDR))));
534 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H 537 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C 540 HAL_BARO_LPS25H_I2C_IMU_ADDR));
541 #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_I2C 543 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
544 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_ICM))));
545 #elif HAL_BARO_DEFAULT == HAL_BARO_20789_I2C_SPI 547 std::move(hal.
i2c_mgr->
get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
549 #elif HAL_BARO_DEFAULT == HAL_BARO_LPS22H_SPI 554 #if defined(BOARD_I2C_BUS_EXT) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 560 #ifdef HAL_BARO_BMP280_I2C_ADDR_ALT 571 #if APM_BUILD_TYPE(APM_BUILD_ArduSub) 581 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT // we don't know which baro user will solder 585 #ifdef HAL_BARO_BMP280_I2C_ADDR_ALT 595 #if CONFIG_HAL_BOARD != HAL_BOARD_F4LIGHT // most boards requires external baro 606 if (instance ==
nullptr) {
641 if (!
is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
662 if (
_hil.have_last_update) {
724 return _num_sensors > 0;
#define HAL_BARO_MS5611_NAME
AP_Float _user_ground_temperature
float get_climb_rate(void)
static AP_Baro_Backend * probe(AP_Baro &baro)
#define HAL_BARO_MS5607_I2C_ADDR
#define HAL_BARO_FILTER_DEFAULT
#define HAL_BARO_MS5611_I2C_BUS
#define HAL_BARO_MS5611_SPI_EXT_NAME
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
void update_calibration(void)
static enum px4_board_type get_board_type(void)
float safe_sqrt(const T v)
#define HAL_BARO_BMP280_I2C_ADDR_ALT
static AP_Baro * _instance
float _external_temperature
float get_temperature(void) const
uint8_t register_sensor(void)
Interface definition for the various Ground Control System.
bool should_df_log() const
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
DerivativeFilterFloat_Size7 _climb_rate_filter
bool should_log(uint32_t mask) const
bool _add_backend(AP_Baro_Backend *backend)
#define HAL_BARO_BMP280_I2C_ADDR
#define AP_GROUPINFO(name, idx, clazz, element, def)
AP_Float _specific_gravity
static AP_Baro * get_instance(void)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611)
void set_pressure_correction(uint8_t instance, float p_correction)
void update(T sample, uint32_t timestamp)
uint32_t _last_external_temperature_ms
bool is_positive(const T fVal1)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual void accumulate(void)
struct AP_Baro::sensor sensors[BARO_MAX_INSTANCES]
#define BARO_MAX_INSTANCES
float get_external_temperature(void) const
float get_altitude_difference(float base_pressure, float pressure) const
#define INTERNAL_TEMPERATURE_CLAMP
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_imu)
float get_air_density_ratio(void)
void calibrate(bool save=true)
virtual void delay(uint16_t ms)=0
virtual OwnPtr< SPIDevice > get_device(const char *name)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define HAL_INS_MPU60x0_NAME
#define HAL_BARO_MS5607_I2C_BUS
bool is_zero(const T fVal1)
#define HAL_BARO_MS5611_I2C_ADDR
#define HAL_BARO_BMP280_BUS
#define HAL_BARO_LPS25H_I2C_ADDR
#define ADD_BACKEND(backend)
static DataFlash_Class * instance(void)
AP_Baro_Backend * drivers[BARO_MAX_DRIVERS]
friend class AP_Baro_SITL
#define HAL_BARO_LPS22H_NAME
void send_text(MAV_SEVERITY severity, const char *fmt,...)
AP_HAL::SPIDeviceManager * spi
float get_pressure(void) const
void backend_update(uint8_t instance)
AP_HAL::I2CDeviceManager * i2c_mgr
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Common definitions and utility routines for the ArduPilot libraries.
float _guessed_ground_temperature
#define HAL_BARO_MS5611_SPI_IMU_NAME
float get_altitude(void) const
static const struct AP_Param::GroupInfo var_info[]
float get_ground_temperature(void) const
#define HAL_BARO_BMP280_NAME
#define HAL_BARO_LPS25H_I2C_BUS
float _last_altitude_EAS2TAS
static AP_Baro_Backend * probe_InvensenseIMU(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, uint8_t imu_address)
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
#define AP_PARAM_FRAME_SUB
#define HAL_BARO_MS5837_I2C_ADDR
void set_external_temperature(float temperature)
uint32_t get_last_update(void) const
bool all_healthy(void) const
void Log_Write_Baro(uint64_t time_us=0)
AP_HAL::Scheduler * scheduler
#define HAL_BARO_BMP085_I2C_ADDR
#define HAL_BARO_MS5611_SPI_INT_NAME
#define HAL_BARO_BMP085_BUS
#define BOARD_I2C_BUS_EXT
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
#define HAL_BARO_KELLERLD_I2C_ADDR
static void sensor_config_error(const char *reason)