33     state.
z = 1.0f / sqrtf(initial_ratio);
    59     if (SH1 < 0.000001
f) {
    63     float SH2 = 1/sqrtf(SH1);
    75     float S = H_TAS * PH + 1.0f;
    82     state += KG*(TAS_mea - TAS_pred); 
    90     float P12 = 0.5f * (P.a.y + P.b.x);
    91     float P13 = 0.5f * (P.a.z + P.c.x);
    92     float P23 = 0.5f * (P.b.z + P.c.y);
    98     P.a.x = 
MAX(P.a.x, 0.0f);
    99     P.b.y = 
MAX(P.b.y, 0.0f);
   100     P.c.z = 
MAX(P.c.z, 0.0f);
   115     if (!param[i].autocal) {
   125     state[i].calibration.state.
z = 1.0f / sqrtf(ratio);
   128     float dpress = 
MAX(get_differential_pressure(), 0);
   129     float true_airspeed = sqrtf(dpress) * 
state[i].EAS2TAS;
   131     float zratio = 
state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
   133     if (isnan(zratio) || isinf(zratio)) {
   139     param[i].ratio.set(1/
sq(zratio));
   141         if (
state[i].last_saved_ratio > 1.05
f*param[i].ratio ||
   142             state[i].last_saved_ratio < 0.95
f*param[i].ratio) {
   143             param[i].ratio.save();
   144             state[i].last_saved_ratio = param[i].ratio;
   145             state[i].counter = 0;
   158         update_calibration(i, vground, max_airspeed_allowed_during_cal);
   165     mavlink_msg_airspeed_autocal_send(chan,
   169                                       get_differential_pressure(primary),
   170                                       state[primary].EAS2TAS,
   171                                       param[primary].ratio.get(),
   172                                       state[primary].calibration.state.
x,
   173                                       state[primary].calibration.state.
y,
   174                                       state[primary].calibration.state.
z,
   175                                       state[primary].calibration.P.a.
x,
   176                                       state[primary].calibration.P.b.
y,
   177                                       state[primary].calibration.P.c.
z);
 float norm(const T first, const U second, const Params... parameters)
 
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
 
float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
 
void init(float initial_ratio)
 
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
 
#define AIRSPEED_MAX_SENSORS
 
Common definitions and utility routines for the ArduPilot libraries. 
 
float constrain_float(const float amt, const float low, const float high)
 
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground)
 
AP_HAL::AnalogSource * chan
 
Matrix3< T > mul_rowcol(const Vector3< T > &v) const