11 #define AIRSPEED_MAX_SENSORS 2 20 void init(
float initial_ratio);
50 void calibrate(
bool in_startup);
54 return state[i].airspeed;
60 return state[i].raw_airspeed;
66 return param[i].ratio;
76 param[i].ratio.set(ratio);
81 bool use(uint8_t i)
const;
82 bool use(
void)
const {
return use(primary); }
87 return param[i].type.get() != TYPE_NONE;
100 return state[i].last_pressure;
106 return param[i].offset;
112 return state[i].corrected_pressure;
124 return state[i].EAS2TAS;
129 void update_calibration(
const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
132 void log_mavlink_send(mavlink_channel_t
chan,
const Vector3f &vground);
136 return state[i].healthy && (fabsf(param[i].offset) > 0 ||
state[i].use_zero_offset) && enabled(i);
141 bool all_healthy(
void)
const;
149 void setHIL(
float airspeed,
float diff_pressure,
float temperature);
154 PITOT_TUBE_ORDER_NEGATIVE = 1,
155 PITOT_TUBE_ORDER_AUTO = 2 };
162 TYPE_I2C_MS5525_ADDRESS_1=4,
163 TYPE_I2C_MS5525_ADDRESS_2=5,
219 void read(uint8_t i);
222 float get_pressure(uint8_t i);
223 void update_calibration(uint8_t i,
float raw_pressure);
224 void update_calibration(uint8_t i,
const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
void set_HIL(float airspeed)
uint32_t last_update_ms(uint8_t i) const
float get_corrected_pressure(void) const
uint8_t get_primary(void) const
void setHIL(float pressure)
bool enabled(uint8_t i) const
void set_EAS2TAS(uint8_t i, float v)
float get_airspeed_ratio(uint8_t i) const
Airspeed_Calibration calibration
float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
float get_differential_pressure(void) const
float get_airspeed(uint8_t i) const
float get_offset(uint8_t i) const
float get_raw_airspeed(void) const
virtual bool get_temperature(float &temperature)=0
void init(float initial_ratio)
void set_airspeed_ratio(uint8_t i, float ratio)
float get_EAS2TAS(void) const
A system for managing and storing variables that are of general interest to the system.
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
float get_offset(void) const
uint32_t last_update_ms(void) const
void set_airspeed_ratio(float ratio)
float get_airspeed_ratio(void) const
float get_raw_airspeed(uint8_t i) const
float get_corrected_pressure(uint8_t i) const
bool get_temperature(float &temperature)
float get_differential_pressure(uint8_t i) const
#define AIRSPEED_MAX_SENSORS
static AP_Airspeed * get_singleton()
Common definitions and utility routines for the ArduPilot libraries.
float get_airspeed(void) const
float get_EAS2TAS(uint8_t i) const
static AP_Airspeed * _singleton
AP_HAL::AnalogSource * chan
bool healthy(uint8_t i) const
void set_EAS2TAS(float v)