2016-01-29 07:38:33 -04:00
|
|
|
#pragma once
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2022-10-17 05:35:08 -03:00
|
|
|
#include "AP_Airspeed_config.h"
|
|
|
|
|
2023-06-09 02:58:29 -03:00
|
|
|
#if AP_AIRSPEED_ENABLED
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2019-06-26 23:38:33 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2022-01-03 17:16:22 -04:00
|
|
|
|
2023-06-09 02:58:29 -03:00
|
|
|
#if AP_AIRSPEED_MSP_ENABLED
|
|
|
|
#include <AP_MSP/msp.h>
|
|
|
|
#endif
|
2023-11-30 22:57:44 -04:00
|
|
|
#if AP_AIRSPEED_EXTERNAL_ENABLED
|
|
|
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
|
|
|
#endif
|
2023-06-09 02:58:29 -03:00
|
|
|
|
2017-11-03 01:47:32 -03:00
|
|
|
class AP_Airspeed_Backend;
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2022-04-07 23:45:58 -03:00
|
|
|
class AP_Airspeed_Params {
|
|
|
|
public:
|
|
|
|
// Constructor
|
|
|
|
AP_Airspeed_Params(void);
|
|
|
|
|
|
|
|
// parameters for each instance
|
|
|
|
AP_Int32 bus_id;
|
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
|
|
|
AP_Float offset;
|
|
|
|
AP_Float ratio;
|
|
|
|
#endif
|
|
|
|
AP_Float psi_range;
|
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
|
|
|
AP_Int8 use;
|
|
|
|
AP_Int8 pin;
|
|
|
|
AP_Int8 skip_cal;
|
|
|
|
AP_Int8 tube_order;
|
|
|
|
#endif
|
|
|
|
AP_Int8 type;
|
|
|
|
AP_Int8 bus;
|
|
|
|
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
|
|
|
AP_Int8 autocal;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
class Airspeed_Calibration {
|
|
|
|
public:
|
2013-08-28 09:35:50 -03:00
|
|
|
friend class AP_Airspeed;
|
2013-07-19 19:14:58 -03:00
|
|
|
// constructor
|
2016-08-08 00:29:50 -03:00
|
|
|
Airspeed_Calibration();
|
2013-07-19 19:14:58 -03:00
|
|
|
|
|
|
|
// initialise the calibration
|
|
|
|
void init(float initial_ratio);
|
|
|
|
|
|
|
|
// take current airspeed in m/s and ground speed vector and return
|
|
|
|
// new scaling factor
|
2016-08-08 00:28:24 -03:00
|
|
|
float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal);
|
2013-07-19 19:14:58 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
// state of kalman filter for airspeed ratio estimation
|
2023-10-11 04:41:50 -03:00
|
|
|
Matrix3f P; // covariance matrix
|
2013-07-19 19:14:58 -03:00
|
|
|
const float Q0; // process noise matrix top left and middle element
|
|
|
|
const float Q1; // process noise matrix bottom right element
|
|
|
|
Vector3f state; // state vector
|
|
|
|
const float DT; // time delta
|
|
|
|
};
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
class AP_Airspeed
|
|
|
|
{
|
|
|
|
public:
|
2016-11-30 00:49:19 -04:00
|
|
|
friend class AP_Airspeed_Backend;
|
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// constructor
|
2016-08-08 00:29:50 -03:00
|
|
|
AP_Airspeed();
|
2012-10-09 21:01:22 -03:00
|
|
|
|
2022-12-06 16:36:30 -04:00
|
|
|
void set_fixedwing_parameters(const class AP_FixedWing *_fixed_wing_parameters);
|
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
void init(void);
|
2022-12-30 15:41:16 -04:00
|
|
|
void allocate();
|
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
|
2022-01-03 17:16:22 -04:00
|
|
|
// indicate which bit in LOG_BITMASK indicates we should log airspeed readings
|
|
|
|
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
|
|
|
|
|
2020-11-24 10:13:10 -04:00
|
|
|
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
|
|
|
// inflight ratio calibration
|
|
|
|
void set_calibration_enabled(bool enable) {calibration_enabled = enable;}
|
|
|
|
#endif //AP_AIRSPEED_AUTOCAL_ENABLE
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
// read the analog source and update airspeed
|
2022-01-03 17:16:22 -04:00
|
|
|
void update(void);
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// calibrate the airspeed. This must be called on startup if the
|
|
|
|
// altitude/climb_rate/acceleration interfaces are ever used
|
2017-11-03 03:17:34 -03:00
|
|
|
void calibrate(bool in_startup);
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// return the current airspeed in m/s
|
2022-04-20 06:09:12 -03:00
|
|
|
float get_airspeed(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
float get_airspeed(void) const { return get_airspeed(primary); }
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
// return the unfiltered airspeed in m/s
|
2022-04-20 06:09:12 -03:00
|
|
|
float get_raw_airspeed(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
float get_raw_airspeed(void) const { return get_raw_airspeed(primary); }
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-07-13 08:53:38 -03:00
|
|
|
// return the current airspeed ratio (dimensionless)
|
2017-11-03 03:17:34 -03:00
|
|
|
float get_airspeed_ratio(uint8_t i) const {
|
2022-12-15 07:41:30 -04:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2017-11-03 03:17:34 -03:00
|
|
|
return param[i].ratio;
|
2022-12-15 07:41:30 -04:00
|
|
|
#else
|
|
|
|
return 0.0;
|
|
|
|
#endif
|
2013-07-13 08:53:38 -03:00
|
|
|
}
|
2018-03-09 17:12:05 -04:00
|
|
|
float get_airspeed_ratio(void) const { return get_airspeed_ratio(primary); }
|
2013-07-13 08:53:38 -03:00
|
|
|
|
2014-01-27 19:35:35 -04:00
|
|
|
// get temperature if available
|
2017-11-03 03:17:34 -03:00
|
|
|
bool get_temperature(uint8_t i, float &temperature);
|
2018-03-09 17:12:05 -04:00
|
|
|
bool get_temperature(float &temperature) { return get_temperature(primary, temperature); }
|
2014-01-27 19:35:35 -04:00
|
|
|
|
2013-07-13 08:53:38 -03:00
|
|
|
// set the airspeed ratio (dimensionless)
|
2022-12-15 07:41:30 -04:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2017-11-03 03:17:34 -03:00
|
|
|
void set_airspeed_ratio(uint8_t i, float ratio) {
|
|
|
|
param[i].ratio.set(ratio);
|
2013-07-13 08:53:38 -03:00
|
|
|
}
|
2018-03-09 17:12:05 -04:00
|
|
|
void set_airspeed_ratio(float ratio) { set_airspeed_ratio(primary, ratio); }
|
2022-12-15 07:41:30 -04:00
|
|
|
#endif
|
2013-07-13 08:53:38 -03:00
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
// return true if airspeed is enabled, and airspeed use is set
|
2017-11-03 03:17:34 -03:00
|
|
|
bool use(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
bool use(void) const { return use(primary); }
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2021-06-17 03:03:35 -03:00
|
|
|
// force disabling of all airspeed sensors
|
|
|
|
void force_disable_use(bool value) {
|
|
|
|
_force_disable_use = value;
|
|
|
|
}
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
// return true if airspeed is enabled
|
2022-04-20 06:06:58 -03:00
|
|
|
bool enabled(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
bool enabled(void) const { return enabled(primary); }
|
2013-06-02 22:40:06 -03:00
|
|
|
|
2018-05-28 17:12:26 -03:00
|
|
|
// return the differential pressure in Pascal for the last airspeed reading
|
2022-04-20 06:09:12 -03:00
|
|
|
float get_differential_pressure(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
float get_differential_pressure(void) const { return get_differential_pressure(primary); }
|
2014-11-13 02:49:04 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// update airspeed ratio calibration
|
2016-08-08 00:28:24 -03:00
|
|
|
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
2013-08-28 09:35:50 -03:00
|
|
|
|
2013-10-29 19:03:35 -03:00
|
|
|
// return health status of sensor
|
2022-04-20 06:06:58 -03:00
|
|
|
bool healthy(uint8_t i) const;
|
2018-03-09 17:12:05 -04:00
|
|
|
bool healthy(void) const { return healthy(primary); }
|
2013-10-29 19:03:35 -03:00
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
// return true if all enabled sensors are healthy
|
|
|
|
bool all_healthy(void) const;
|
|
|
|
|
2013-12-30 06:23:58 -04:00
|
|
|
// return time in ms of last update
|
2017-11-03 03:17:34 -03:00
|
|
|
uint32_t last_update_ms(uint8_t i) const { return state[i].last_update_ms; }
|
|
|
|
uint32_t last_update_ms(void) const { return last_update_ms(primary); }
|
2013-12-30 06:23:58 -04:00
|
|
|
|
2022-10-17 05:35:08 -03:00
|
|
|
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
|
|
|
bool get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const;
|
|
|
|
#endif
|
|
|
|
|
2012-10-09 21:01:22 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2016-01-29 07:38:33 -04:00
|
|
|
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0,
|
|
|
|
PITOT_TUBE_ORDER_NEGATIVE = 1,
|
|
|
|
PITOT_TUBE_ORDER_AUTO = 2 };
|
2013-08-28 09:35:50 -03:00
|
|
|
|
2019-01-29 22:02:40 -04:00
|
|
|
enum OptionsMask {
|
2019-02-03 07:55:38 -04:00
|
|
|
ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE = (1<<0), // If set then use airspeed failure check
|
|
|
|
ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE = (1<<1), // If set then automatically enable the airspeed sensor use when healthy again.
|
2021-06-29 23:44:58 -03:00
|
|
|
DISABLE_VOLTAGE_CORRECTION = (1<<2),
|
2022-06-25 20:21:18 -03:00
|
|
|
USE_EKF_CONSISTENCY = (1<<3),
|
2019-01-29 22:02:40 -04:00
|
|
|
};
|
|
|
|
|
2016-11-30 00:49:19 -04:00
|
|
|
enum airspeed_type {
|
|
|
|
TYPE_NONE=0,
|
|
|
|
TYPE_I2C_MS4525=1,
|
|
|
|
TYPE_ANALOG=2,
|
2016-11-30 02:21:48 -04:00
|
|
|
TYPE_I2C_MS5525=3,
|
2017-11-28 15:25:19 -04:00
|
|
|
TYPE_I2C_MS5525_ADDRESS_1=4,
|
|
|
|
TYPE_I2C_MS5525_ADDRESS_2=5,
|
2017-11-03 01:47:32 -03:00
|
|
|
TYPE_I2C_SDP3X=6,
|
2019-07-18 02:19:09 -03:00
|
|
|
TYPE_I2C_DLVR_5IN=7,
|
2018-09-05 03:45:01 -03:00
|
|
|
TYPE_UAVCAN=8,
|
2019-07-18 02:19:09 -03:00
|
|
|
TYPE_I2C_DLVR_10IN=9,
|
2020-08-04 18:53:27 -03:00
|
|
|
TYPE_I2C_DLVR_20IN=10,
|
|
|
|
TYPE_I2C_DLVR_30IN=11,
|
|
|
|
TYPE_I2C_DLVR_60IN=12,
|
2020-07-18 16:49:08 -03:00
|
|
|
TYPE_NMEA_WATER=13,
|
2020-11-16 06:35:15 -04:00
|
|
|
TYPE_MSP=14,
|
2021-03-23 11:18:41 -03:00
|
|
|
TYPE_I2C_ASP5033=15,
|
2023-11-30 22:57:44 -04:00
|
|
|
TYPE_EXTERNAL=16,
|
2022-05-24 01:14:25 -03:00
|
|
|
TYPE_SITL=100,
|
2016-11-30 00:49:19 -04:00
|
|
|
};
|
2017-11-03 03:17:34 -03:00
|
|
|
|
|
|
|
// get current primary sensor
|
|
|
|
uint8_t get_primary(void) const { return primary; }
|
2018-03-04 20:13:48 -04:00
|
|
|
|
2019-05-03 08:23:58 -03:00
|
|
|
// get number of sensors
|
|
|
|
uint8_t get_num_sensors(void) const { return num_sensors; }
|
|
|
|
|
2018-03-04 20:13:48 -04:00
|
|
|
static AP_Airspeed *get_singleton() { return _singleton; }
|
2020-03-16 02:09:10 -03:00
|
|
|
|
|
|
|
// return the current corrected pressure, public for AP_Periph
|
2022-04-20 06:09:12 -03:00
|
|
|
float get_corrected_pressure(uint8_t i) const;
|
2020-03-16 02:09:10 -03:00
|
|
|
float get_corrected_pressure(void) const {
|
|
|
|
return get_corrected_pressure(primary);
|
|
|
|
}
|
2020-11-16 06:35:15 -04:00
|
|
|
|
2022-05-04 05:13:29 -03:00
|
|
|
#if AP_AIRSPEED_MSP_ENABLED
|
2020-11-16 06:35:15 -04:00
|
|
|
void handle_msp(const MSP::msp_airspeed_data_message_t &pkt);
|
|
|
|
#endif
|
2022-12-08 02:47:13 -04:00
|
|
|
|
2023-11-30 22:57:44 -04:00
|
|
|
#if AP_AIRSPEED_EXTERNAL_ENABLED
|
|
|
|
void handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt);
|
|
|
|
#endif
|
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
enum class CalibrationState {
|
|
|
|
NOT_STARTED,
|
|
|
|
IN_PROGRESS,
|
|
|
|
SUCCESS,
|
|
|
|
FAILED
|
|
|
|
};
|
|
|
|
// get aggregate calibration state for the Airspeed library:
|
|
|
|
CalibrationState get_calibration_state() const;
|
|
|
|
|
2018-03-09 04:07:34 -04:00
|
|
|
private:
|
2018-03-04 20:13:48 -04:00
|
|
|
static AP_Airspeed *_singleton;
|
2018-03-09 17:12:05 -04:00
|
|
|
|
2022-11-26 11:53:55 -04:00
|
|
|
AP_Int8 _enable;
|
|
|
|
bool lib_enabled() const;
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
AP_Int8 primary_sensor;
|
2022-12-06 16:36:30 -04:00
|
|
|
AP_Int8 max_speed_pcnt;
|
2019-01-29 19:03:35 -04:00
|
|
|
AP_Int32 _options; // bitmask options for airspeed
|
2020-10-09 09:38:25 -03:00
|
|
|
AP_Float _wind_max;
|
|
|
|
AP_Float _wind_warn;
|
2022-06-25 20:21:18 -03:00
|
|
|
AP_Float _wind_gate;
|
2020-10-09 09:38:25 -03:00
|
|
|
|
2022-04-07 23:45:58 -03:00
|
|
|
AP_Airspeed_Params param[AIRSPEED_MAX_SENSORS];
|
2018-03-09 17:12:05 -04:00
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
CalibrationState calibration_state[AIRSPEED_MAX_SENSORS];
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
struct airspeed_state {
|
|
|
|
float raw_airspeed;
|
|
|
|
float airspeed;
|
|
|
|
float last_pressure;
|
|
|
|
float filtered_pressure;
|
|
|
|
float corrected_pressure;
|
|
|
|
uint32_t last_update_ms;
|
|
|
|
bool use_zero_offset;
|
2020-05-06 02:07:59 -03:00
|
|
|
bool healthy;
|
2019-10-03 08:02:07 -03:00
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
// state of runtime calibration
|
|
|
|
struct {
|
|
|
|
uint32_t start_ms;
|
|
|
|
float sum;
|
2020-05-06 02:07:59 -03:00
|
|
|
uint16_t count;
|
2017-11-03 03:17:34 -03:00
|
|
|
uint16_t read_count;
|
|
|
|
} cal;
|
|
|
|
|
2019-10-03 08:02:07 -03:00
|
|
|
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
2017-11-03 03:17:34 -03:00
|
|
|
Airspeed_Calibration calibration;
|
|
|
|
float last_saved_ratio;
|
|
|
|
uint8_t counter;
|
2019-10-03 08:02:07 -03:00
|
|
|
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
2019-01-29 19:03:35 -04:00
|
|
|
|
|
|
|
struct {
|
|
|
|
uint32_t last_check_ms;
|
|
|
|
float health_probability;
|
2022-06-25 20:21:18 -03:00
|
|
|
float test_ratio;
|
2019-01-29 19:03:35 -04:00
|
|
|
int8_t param_use_backup;
|
2020-10-09 09:38:25 -03:00
|
|
|
uint32_t last_warn_ms;
|
2019-01-29 19:03:35 -04:00
|
|
|
} failures;
|
2022-10-17 05:35:08 -03:00
|
|
|
|
|
|
|
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
|
|
|
uint32_t last_hygrometer_log_ms;
|
|
|
|
#endif
|
2017-11-03 03:17:34 -03:00
|
|
|
} state[AIRSPEED_MAX_SENSORS];
|
2018-03-09 17:12:05 -04:00
|
|
|
|
2021-06-17 14:59:42 -03:00
|
|
|
bool calibration_enabled;
|
2020-11-24 10:13:10 -04:00
|
|
|
|
2021-06-17 03:03:35 -03:00
|
|
|
// can be set to true to disable the use of the airspeed sensor
|
|
|
|
bool _force_disable_use;
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
// current primary sensor
|
|
|
|
uint8_t primary;
|
2019-05-03 08:23:58 -03:00
|
|
|
uint8_t num_sensors;
|
|
|
|
|
2022-01-03 17:16:22 -04:00
|
|
|
uint32_t _log_bit = -1; // stores which bit in LOG_BITMASK is used to indicate we should log airspeed readings
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
void read(uint8_t i);
|
2018-05-28 17:12:26 -03:00
|
|
|
// return the differential pressure in Pascal for the last airspeed reading for the requested instance
|
|
|
|
// returns 0 if the sensor is not enabled
|
2017-11-03 03:17:34 -03:00
|
|
|
float get_pressure(uint8_t i);
|
2020-03-16 02:09:10 -03:00
|
|
|
|
2022-03-01 13:44:43 -04:00
|
|
|
// get the health probability
|
|
|
|
float get_health_probability(uint8_t i) const {
|
2019-04-05 23:48:44 -03:00
|
|
|
return state[i].failures.health_probability;
|
|
|
|
}
|
2022-03-01 13:44:43 -04:00
|
|
|
float get_health_probability(void) const {
|
|
|
|
return get_health_probability(primary);
|
2019-04-05 23:48:44 -03:00
|
|
|
}
|
|
|
|
|
2022-06-25 20:21:18 -03:00
|
|
|
// get the consistency test ratio
|
|
|
|
float get_test_ratio(uint8_t i) const {
|
|
|
|
return state[i].failures.test_ratio;
|
|
|
|
}
|
|
|
|
float get_test_ratio(void) const {
|
|
|
|
return get_test_ratio(primary);
|
|
|
|
}
|
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
void update_calibration(uint8_t i, float raw_pressure);
|
|
|
|
void update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
2018-11-22 19:43:22 -04:00
|
|
|
void send_airspeed_calibration(const Vector3f &vg);
|
2019-04-05 23:48:44 -03:00
|
|
|
// return the current calibration offset
|
|
|
|
float get_offset(uint8_t i) const {
|
2022-12-15 07:41:30 -04:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2019-04-05 23:48:44 -03:00
|
|
|
return param[i].offset;
|
2022-12-15 07:41:30 -04:00
|
|
|
#else
|
|
|
|
return 0.0;
|
|
|
|
#endif
|
2019-04-05 23:48:44 -03:00
|
|
|
}
|
|
|
|
float get_offset(void) const { return get_offset(primary); }
|
2019-01-29 22:02:40 -04:00
|
|
|
|
|
|
|
void check_sensor_failures();
|
2019-02-03 07:55:38 -04:00
|
|
|
void check_sensor_ahrs_wind_max_failures(uint8_t i);
|
2018-03-09 17:12:05 -04:00
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
AP_Airspeed_Backend *sensor[AIRSPEED_MAX_SENSORS];
|
2018-11-22 19:43:22 -04:00
|
|
|
|
2019-04-05 23:48:44 -03:00
|
|
|
void Log_Airspeed();
|
2021-09-03 20:56:09 -03:00
|
|
|
|
|
|
|
bool add_backend(AP_Airspeed_Backend *backend);
|
2022-12-06 16:36:30 -04:00
|
|
|
|
|
|
|
const AP_FixedWing *fixed_wing_parameters;
|
2022-11-26 11:19:22 -04:00
|
|
|
|
|
|
|
void convert_per_instance();
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
};
|
2019-04-05 22:10:17 -03:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Airspeed *airspeed();
|
|
|
|
};
|
2023-06-09 02:58:29 -03:00
|
|
|
|
|
|
|
#endif // AP_AIRSPEED_ENABLED
|