57 const float polar_CD0,
66 CL0 = polar_K / (aspd * aspd);
70 cosphi = (1 - phi * phi / 2);
71 netto_rate = climb_rate + aspd * (C1 + C2 / (cosphi * cosphi));
const AP_Vehicle::FixedWing & _aparm
virtual bool airspeed_estimate(float *airspeed_ret) const
#define TE_FILT_DISPLAYED
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
static DataFlash_Class * instance(void)
float correct_netto_rate(float climb_rate, float phi, float aspd, const float polar_K, const float polar_CD0, const float polar_B)
unsigned long _prev_update_time
virtual void get_relative_position_D_home(float &posD) const =0
void update(const float polar_K, const float polar_CD0, const float polar_B)
AP_Int32 airspeed_cruise_cm