2015-12-01 12:07:15 -04:00
|
|
|
#pragma once
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2022-10-26 09:02:23 -03:00
|
|
|
#include "AP_Baro_config.h"
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2022-11-24 18:16:20 -04:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <Filter/DerivativeFilter.h>
|
2020-09-03 19:09:52 -03:00
|
|
|
#include <AP_MSP/msp.h>
|
2020-12-27 22:05:33 -04:00
|
|
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
2020-09-03 19:09:52 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// maximum number of sensor instances
|
2021-04-29 02:13:47 -03:00
|
|
|
#ifndef BARO_MAX_INSTANCES
|
2015-09-10 07:24:59 -03:00
|
|
|
#define BARO_MAX_INSTANCES 3
|
2021-04-29 02:13:47 -03:00
|
|
|
#endif
|
2014-10-19 16:22:51 -03:00
|
|
|
|
|
|
|
// maximum number of drivers. Note that a single driver can provide
|
|
|
|
// multiple sensor instances
|
2016-11-24 20:59:14 -04:00
|
|
|
#define BARO_MAX_DRIVERS 3
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2017-07-06 08:58:13 -03:00
|
|
|
// timeouts for health reporting
|
|
|
|
#define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
|
|
|
|
#define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
class AP_Baro_Backend;
|
|
|
|
|
2011-11-05 22:11:25 -03:00
|
|
|
class AP_Baro
|
|
|
|
{
|
2014-10-19 16:22:51 -03:00
|
|
|
friend class AP_Baro_Backend;
|
2017-07-12 02:03:33 -03:00
|
|
|
friend class AP_Baro_SITL; // for access to sensors[]
|
2023-04-08 01:09:10 -03:00
|
|
|
friend class AP_Baro_DroneCAN; // for access to sensors[]
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2012-08-17 03:09:24 -03:00
|
|
|
public:
|
2017-12-12 21:06:11 -04:00
|
|
|
AP_Baro();
|
2017-08-08 04:43:16 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_Baro);
|
2012-12-12 17:43:00 -04:00
|
|
|
|
2017-11-03 01:43:44 -03:00
|
|
|
// get singleton
|
2019-02-10 14:33:05 -04:00
|
|
|
static AP_Baro *get_singleton(void) {
|
|
|
|
return _singleton;
|
2017-11-03 01:43:44 -03:00
|
|
|
}
|
|
|
|
|
2017-02-03 00:18:25 -04:00
|
|
|
// barometer types
|
|
|
|
typedef enum {
|
|
|
|
BARO_TYPE_AIR,
|
|
|
|
BARO_TYPE_WATER
|
|
|
|
} baro_type_t;
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// initialise the barometer object, loading backend drivers
|
|
|
|
void init(void);
|
2014-08-13 09:42:14 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// update the barometer object, asking backends to push data to
|
|
|
|
// the frontend
|
|
|
|
void update(void);
|
|
|
|
|
|
|
|
// healthy - returns true if sensor and derived altitude are good
|
|
|
|
bool healthy(void) const { return healthy(_primary); }
|
2021-05-06 19:38:27 -03:00
|
|
|
#ifdef HAL_BUILD_AP_PERIPH
|
|
|
|
// calibration and alt check not valid for AP_Periph
|
2023-05-21 23:52:51 -03:00
|
|
|
bool healthy(uint8_t instance) const;
|
2021-05-06 19:38:27 -03:00
|
|
|
#else
|
2023-05-21 23:52:51 -03:00
|
|
|
bool healthy(uint8_t instance) const;
|
2021-05-06 19:38:27 -03:00
|
|
|
#endif
|
2013-09-21 08:30:41 -03:00
|
|
|
|
2015-01-06 21:45:01 -04:00
|
|
|
// check if all baros are healthy - used for SYS_STATUS report
|
|
|
|
bool all_healthy(void) const;
|
|
|
|
|
2022-10-16 07:52:18 -03:00
|
|
|
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
|
|
|
|
bool arming_checks(size_t buflen, char *buffer) const;
|
|
|
|
|
2019-05-03 08:23:45 -03:00
|
|
|
// get primary sensor
|
|
|
|
uint8_t get_primary(void) const { return _primary; }
|
|
|
|
|
2013-09-21 08:30:41 -03:00
|
|
|
// pressure in Pascal. Divide by 100 for millibars or hectopascals
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_pressure(void) const { return get_pressure(_primary); }
|
|
|
|
float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
|
2022-11-24 18:16:20 -04:00
|
|
|
#if HAL_BARO_WIND_COMP_ENABLED
|
|
|
|
// dynamic pressure in Pascal. Divide by 100 for millibars or hectopascals
|
|
|
|
const Vector3f& get_dynamic_pressure(uint8_t instance) const { return sensors[instance].dynamic_pressure; }
|
|
|
|
#endif
|
2012-08-17 03:09:24 -03:00
|
|
|
|
2013-09-21 08:30:41 -03:00
|
|
|
// temperature in degrees C
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_temperature(void) const { return get_temperature(_primary); }
|
|
|
|
float get_temperature(uint8_t instance) const { return sensors[instance].temperature; }
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2018-01-05 20:48:40 -04:00
|
|
|
// get pressure correction in Pascal. Divide by 100 for millibars or hectopascals
|
|
|
|
float get_pressure_correction(void) const { return get_pressure_correction(_primary); }
|
|
|
|
float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; }
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// accumulate a reading on sensors. Some backends without their
|
|
|
|
// own thread or a timer may need this.
|
|
|
|
void accumulate(void);
|
2013-01-09 08:05:17 -04:00
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
// calibrate the barometer. This must be called on startup if the
|
|
|
|
// altitude/climb_rate/acceleration interfaces are ever used
|
2017-02-03 00:18:25 -04:00
|
|
|
void calibrate(bool save=true);
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2013-10-05 05:44:00 -03:00
|
|
|
// update the barometer calibration to the current pressure. Can
|
|
|
|
// be used for incremental preflight update of baro
|
2014-10-19 16:22:51 -03:00
|
|
|
void update_calibration(void);
|
2013-10-05 05:44:00 -03:00
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
// get current altitude in meters relative to altitude at the time
|
|
|
|
// of the last calibrate() call
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_altitude(void) const { return get_altitude(_primary); }
|
|
|
|
float get_altitude(uint8_t instance) const { return sensors[instance].altitude; }
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2020-12-02 06:15:09 -04:00
|
|
|
// returns which i2c bus is considered "the" external bus
|
|
|
|
uint8_t external_bus() const { return _ext_bus; }
|
|
|
|
|
2014-04-11 03:34:02 -03:00
|
|
|
// get altitude difference in meters relative given a base
|
|
|
|
// pressure in Pascal
|
2014-08-13 03:21:52 -03:00
|
|
|
float get_altitude_difference(float base_pressure, float pressure) const;
|
2014-04-11 03:34:02 -03:00
|
|
|
|
2022-01-27 15:02:53 -04:00
|
|
|
// get sea level pressure relative to 1976 standard atmosphere model
|
|
|
|
// pressure in Pascal
|
|
|
|
float get_sealevel_pressure(float pressure) const;
|
|
|
|
|
2013-06-26 05:32:37 -03:00
|
|
|
// get scale factor required to convert equivalent to true airspeed
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_EAS2TAS(void);
|
2012-07-05 03:26:56 -03:00
|
|
|
|
2015-04-29 02:12:41 -03:00
|
|
|
// get air density / sea level density - decreases as altitude climbs
|
2015-04-28 15:15:49 -03:00
|
|
|
float get_air_density_ratio(void);
|
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
// get current climb rate in meters/s. A positive number means
|
|
|
|
// going up
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_climb_rate(void);
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2013-09-21 08:30:41 -03:00
|
|
|
// ground temperature in degrees C
|
2012-06-19 23:25:19 -03:00
|
|
|
// the ground values are only valid after calibration
|
2017-03-24 01:58:53 -03:00
|
|
|
float get_ground_temperature(void) const;
|
2013-09-21 08:30:41 -03:00
|
|
|
|
|
|
|
// ground pressure in Pascal
|
|
|
|
// the ground values are only valid after calibration
|
2014-10-19 16:22:51 -03:00
|
|
|
float get_ground_pressure(void) const { return get_ground_pressure(_primary); }
|
|
|
|
float get_ground_pressure(uint8_t i) const { return sensors[i].ground_pressure.get(); }
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2014-11-11 20:26:28 -04:00
|
|
|
// set the temperature to be used for altitude calibration. This
|
|
|
|
// allows an external temperature source (such as a digital
|
|
|
|
// airspeed sensor) to be used as the temperature source
|
|
|
|
void set_external_temperature(float temperature);
|
|
|
|
|
2013-08-08 10:33:53 -03:00
|
|
|
// get last time sample was taken (in ms)
|
2014-10-19 16:22:51 -03:00
|
|
|
uint32_t get_last_update(void) const { return get_last_update(_primary); }
|
2017-01-04 10:08:26 -04:00
|
|
|
uint32_t get_last_update(uint8_t instance) const { return sensors[instance].last_update_ms; }
|
2012-11-07 05:58:36 -04:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// settable parameters
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-06-27 02:59:52 -03:00
|
|
|
|
2017-03-24 01:58:53 -03:00
|
|
|
float get_external_temperature(void) const { return get_external_temperature(_primary); };
|
|
|
|
float get_external_temperature(const uint8_t instance) const;
|
2014-08-13 09:42:14 -03:00
|
|
|
|
2017-02-03 00:18:25 -04:00
|
|
|
// Set the primary baro
|
|
|
|
void set_primary_baro(uint8_t primary) { _primary_baro.set_and_save(primary); };
|
|
|
|
|
|
|
|
// Set the type (Air or Water) of a particular instance
|
|
|
|
void set_type(uint8_t instance, baro_type_t type) { sensors[instance].type = type; };
|
|
|
|
|
|
|
|
// Get the type (Air or Water) of a particular instance
|
|
|
|
baro_type_t get_type(uint8_t instance) { return sensors[instance].type; };
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// register a new sensor, claiming a sensor slot. If we are out of
|
|
|
|
// slots it will panic
|
|
|
|
uint8_t register_sensor(void);
|
2014-11-11 20:26:28 -04:00
|
|
|
|
2015-01-05 07:29:01 -04:00
|
|
|
// return number of registered sensors
|
|
|
|
uint8_t num_instances(void) const { return _num_sensors; }
|
|
|
|
|
2016-01-06 19:48:31 -04:00
|
|
|
// set baro drift amount
|
2022-07-05 00:08:56 -03:00
|
|
|
void set_baro_drift_altitude(float alt) { _alt_offset.set(alt); }
|
2016-01-06 19:48:31 -04:00
|
|
|
|
2016-05-13 17:01:11 -03:00
|
|
|
// get baro drift amount
|
2021-02-01 12:26:26 -04:00
|
|
|
float get_baro_drift_offset(void) const { return _alt_offset_active; }
|
2016-05-13 17:01:11 -03:00
|
|
|
|
2017-04-12 08:17:19 -03:00
|
|
|
// simple atmospheric model
|
|
|
|
static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
|
|
|
|
|
2018-05-07 16:23:37 -03:00
|
|
|
// simple underwater atmospheric model
|
|
|
|
static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta);
|
|
|
|
|
2017-03-31 06:08:52 -03:00
|
|
|
// set a pressure correction from AP_TempCalibration
|
|
|
|
void set_pressure_correction(uint8_t instance, float p_correction);
|
2017-08-08 04:43:16 -03:00
|
|
|
|
2018-03-12 04:58:10 -03:00
|
|
|
uint8_t get_filter_range() const { return _filter_range; }
|
|
|
|
|
2018-04-11 09:46:46 -03:00
|
|
|
// indicate which bit in LOG_BITMASK indicates baro logging enabled
|
|
|
|
void set_log_baro_bit(uint32_t bit) { _log_baro_bit = bit; }
|
2019-02-11 04:16:31 -04:00
|
|
|
bool should_log() const;
|
2018-04-11 09:46:46 -03:00
|
|
|
|
2019-04-25 19:43:11 -03:00
|
|
|
// allow threads to lock against baro update
|
|
|
|
HAL_Semaphore &get_semaphore(void) {
|
|
|
|
return _rsem;
|
|
|
|
}
|
2020-09-03 19:09:52 -03:00
|
|
|
|
2022-01-26 23:58:56 -04:00
|
|
|
#if AP_BARO_MSP_ENABLED
|
2020-09-03 19:09:52 -03:00
|
|
|
void handle_msp(const MSP::msp_baro_data_message_t &pkt);
|
|
|
|
#endif
|
2022-01-26 23:58:56 -04:00
|
|
|
#if AP_BARO_EXTERNALAHRS_ENABLED
|
2020-12-27 22:05:33 -04:00
|
|
|
void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt);
|
|
|
|
#endif
|
2022-01-26 23:58:56 -04:00
|
|
|
|
2022-10-16 07:52:18 -03:00
|
|
|
enum Options : uint16_t {
|
|
|
|
TreatMS5611AsMS5607 = (1U << 0U),
|
|
|
|
};
|
|
|
|
|
|
|
|
// check if an option is set
|
|
|
|
bool option_enabled(const Options option) const
|
|
|
|
{
|
|
|
|
return (uint16_t(_options.get()) & uint16_t(option)) != 0;
|
|
|
|
}
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
private:
|
2017-11-03 01:43:44 -03:00
|
|
|
// singleton
|
2019-02-10 14:33:05 -04:00
|
|
|
static AP_Baro *_singleton;
|
2017-11-03 01:43:44 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// how many drivers do we have?
|
2016-07-12 02:02:41 -03:00
|
|
|
uint8_t _num_drivers;
|
2014-10-19 16:22:51 -03:00
|
|
|
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
|
|
|
|
|
|
|
// how many sensors do we have?
|
2016-07-12 02:02:41 -03:00
|
|
|
uint8_t _num_sensors;
|
2014-10-19 16:22:51 -03:00
|
|
|
|
|
|
|
// what is the primary sensor at the moment?
|
2016-07-12 02:02:41 -03:00
|
|
|
uint8_t _primary;
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2018-04-11 09:46:46 -03:00
|
|
|
uint32_t _log_baro_bit = -1;
|
|
|
|
|
2020-09-03 19:09:52 -03:00
|
|
|
bool init_done;
|
|
|
|
|
|
|
|
uint8_t msp_instance_mask;
|
|
|
|
|
2018-08-22 21:42:06 -03:00
|
|
|
// bitmask values for GND_PROBE_EXT
|
|
|
|
enum {
|
|
|
|
PROBE_BMP085=(1<<0),
|
|
|
|
PROBE_BMP280=(1<<1),
|
|
|
|
PROBE_MS5611=(1<<2),
|
|
|
|
PROBE_MS5607=(1<<3),
|
|
|
|
PROBE_MS5637=(1<<4),
|
|
|
|
PROBE_FBM320=(1<<5),
|
|
|
|
PROBE_DPS280=(1<<6),
|
|
|
|
PROBE_LPS25H=(1<<7),
|
|
|
|
PROBE_KELLER=(1<<8),
|
|
|
|
PROBE_MS5837=(1<<9),
|
2019-07-26 03:55:30 -03:00
|
|
|
PROBE_BMP388=(1<<10),
|
2020-09-03 19:09:52 -03:00
|
|
|
PROBE_SPL06 =(1<<11),
|
|
|
|
PROBE_MSP =(1<<12),
|
2018-08-22 21:42:06 -03:00
|
|
|
};
|
|
|
|
|
2020-11-23 03:58:27 -04:00
|
|
|
#if HAL_BARO_WIND_COMP_ENABLED
|
|
|
|
class WindCoeff {
|
|
|
|
public:
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
AP_Int8 enable; // enable compensation for this barometer
|
|
|
|
AP_Float xp; // ratio of static pressure rise to dynamic pressure when flying forwards
|
|
|
|
AP_Float xn; // ratio of static pressure rise to dynamic pressure when flying backwards
|
|
|
|
AP_Float yp; // ratio of static pressure rise to dynamic pressure when flying to the right
|
|
|
|
AP_Float yn; // ratio of static pressure rise to dynamic pressure when flying to the left
|
2022-11-22 16:57:25 -04:00
|
|
|
AP_Float zp; // ratio of static pressure rise to dynamic pressure when flying up
|
|
|
|
AP_Float zn; // ratio of static pressure rise to dynamic pressure when flying down
|
2020-11-23 03:58:27 -04:00
|
|
|
};
|
|
|
|
#endif
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
struct sensor {
|
|
|
|
uint32_t last_update_ms; // last update time in ms
|
2017-07-06 08:58:13 -03:00
|
|
|
uint32_t last_change_ms; // last update time in ms that included a change in reading from previous readings
|
2014-10-19 16:22:51 -03:00
|
|
|
float pressure; // pressure in Pascal
|
|
|
|
float temperature; // temperature in degrees C
|
|
|
|
float altitude; // calculated altitude
|
|
|
|
AP_Float ground_pressure;
|
2017-03-31 06:08:52 -03:00
|
|
|
float p_correction;
|
2019-07-30 23:31:16 -03:00
|
|
|
baro_type_t type; // 0 for air pressure (default), 1 for water pressure
|
|
|
|
bool healthy; // true if sensor is healthy
|
|
|
|
bool alt_ok; // true if calculated altitude is ok
|
|
|
|
bool calibrated; // true if calculated calibrated successfully
|
2020-07-18 04:12:41 -03:00
|
|
|
AP_Int32 bus_id;
|
2020-11-23 03:58:27 -04:00
|
|
|
#if HAL_BARO_WIND_COMP_ENABLED
|
|
|
|
WindCoeff wind_coeff;
|
2022-11-24 18:16:20 -04:00
|
|
|
Vector3f dynamic_pressure; // calculated dynamic pressure
|
2020-11-23 03:58:27 -04:00
|
|
|
#endif
|
2014-10-19 16:22:51 -03:00
|
|
|
} sensors[BARO_MAX_INSTANCES];
|
2014-11-11 20:26:28 -04:00
|
|
|
|
2015-08-25 15:36:58 -03:00
|
|
|
AP_Float _alt_offset;
|
2016-07-12 02:02:41 -03:00
|
|
|
float _alt_offset_active;
|
2022-01-27 15:02:53 -04:00
|
|
|
AP_Float _field_elevation; // field elevation in meters
|
|
|
|
float _field_elevation_active;
|
|
|
|
uint32_t _field_elevation_last_ms;
|
2015-09-10 07:24:59 -03:00
|
|
|
AP_Int8 _primary_baro; // primary chosen by user
|
2016-12-01 05:59:50 -04:00
|
|
|
AP_Int8 _ext_bus; // bus number for external barometer
|
2016-07-12 02:02:41 -03:00
|
|
|
float _last_altitude_EAS2TAS;
|
|
|
|
float _EAS2TAS;
|
|
|
|
float _external_temperature;
|
|
|
|
uint32_t _last_external_temperature_ms;
|
2012-08-17 03:09:24 -03:00
|
|
|
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
2017-02-03 00:18:25 -04:00
|
|
|
AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water
|
2017-03-24 01:58:53 -03:00
|
|
|
AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS
|
|
|
|
float _guessed_ground_temperature; // currently ground temperature estimate using our best abailable source
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2015-11-08 23:34:07 -04:00
|
|
|
// when did we last notify the GCS of new pressure reference?
|
2016-07-12 02:02:41 -03:00
|
|
|
uint32_t _last_notify_ms;
|
2015-12-01 12:07:15 -04:00
|
|
|
|
2022-06-11 22:59:54 -03:00
|
|
|
// see if we already have probed a i2c driver by bus number and address
|
|
|
|
bool _have_i2c_driver(uint8_t bus_num, uint8_t address) const;
|
2016-11-24 20:59:14 -04:00
|
|
|
bool _add_backend(AP_Baro_Backend *backend);
|
2018-08-22 21:42:06 -03:00
|
|
|
void _probe_i2c_barometers(void);
|
2018-03-12 04:58:10 -03:00
|
|
|
AP_Int8 _filter_range; // valid value range from mean value
|
2018-08-22 21:42:06 -03:00
|
|
|
AP_Int32 _baro_probe_ext;
|
2019-04-25 19:43:11 -03:00
|
|
|
|
2022-10-16 07:52:18 -03:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
|
|
|
AP_Float _alt_error_max;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
AP_Int16 _options;
|
|
|
|
|
2019-04-25 19:43:11 -03:00
|
|
|
// semaphore for API access from threads
|
2020-01-18 17:57:22 -04:00
|
|
|
HAL_Semaphore _rsem;
|
2020-11-23 03:58:27 -04:00
|
|
|
|
|
|
|
#if HAL_BARO_WIND_COMP_ENABLED
|
|
|
|
/*
|
|
|
|
return pressure correction for wind based on GND_WCOEF parameters
|
|
|
|
*/
|
|
|
|
float wind_pressure_correction(uint8_t instance);
|
|
|
|
#endif
|
2021-01-23 00:26:33 -04:00
|
|
|
|
|
|
|
// Logging function
|
|
|
|
void Write_Baro(void);
|
|
|
|
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance);
|
2022-05-28 21:03:39 -03:00
|
|
|
|
|
|
|
void update_field_elevation();
|
2011-11-05 22:11:25 -03:00
|
|
|
};
|
2018-03-08 17:14:58 -04:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Baro &baro();
|
|
|
|
};
|