APM:Libraries
Variometer.cpp
Go to the documentation of this file.
1 /* Variometer class by Samuel Tabor
2 
3 Manages the estimation of aircraft total energy, drag and vertical air velocity.
4 */
5 #include "Variometer.h"
6 
8  _ahrs(ahrs),
9  _aparm(parms),
10  new_data(false)
11 {
12 }
13 
14 void Variometer::update(const float polar_K, const float polar_B, const float polar_Cd0)
15 {
17  alt = -alt;
18 
19  if (fabsf(alt - _last_alt) > 0.0001f) { // if no change in altitude then there will be no update of ekf buffer
20  // Both filtered total energy rates and unfiltered are computed for the thermal switching logic and the EKF
21  float aspd = 0;
22  float roll = _ahrs.roll;
23  if (!_ahrs.airspeed_estimate(&aspd)) {
24  aspd = _aparm.airspeed_cruise_cm / 100.0f;
25  }
26  _aspd_filt = ASPD_FILT * aspd + (1 - ASPD_FILT) * _aspd_filt;
27  float total_E = alt + 0.5f *_aspd_filt * _aspd_filt / GRAVITY_MSS; // Work out total energy
28  float sinkrate = correct_netto_rate(0.0f, (roll + _last_roll) / 2, _aspd_filt, polar_K, polar_Cd0, polar_B); // Compute still-air sinkrate
29  reading = (total_E - _last_total_E) / ((AP_HAL::micros64() - _prev_update_time) * 1e-6) + sinkrate; // Unfiltered netto rate
30  filtered_reading = TE_FILT * reading + (1 - TE_FILT) * filtered_reading; // Apply low pass timeconst filter for noise
31  displayed_reading = TE_FILT_DISPLAYED * reading + (1 - TE_FILT_DISPLAYED) * displayed_reading;
32 
33 
34  _last_alt = alt; // Store variables
35  _last_roll = roll;
36  _last_aspd = aspd;
37  _last_total_E = total_E;
39  new_data = true;
40 
41  DataFlash_Class::instance()->Log_Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt", "Qffffff",
43  (double)aspd,
44  (double)_aspd_filt,
45  (double)alt,
46  (double)roll,
47  (double)reading,
48  (double)filtered_reading);
49  }
50 }
51 
52 
53 float Variometer::correct_netto_rate(float climb_rate,
54  float phi,
55  float aspd,
56  const float polar_K,
57  const float polar_CD0,
58  const float polar_B)
59 {
60  // Remove aircraft sink rate
61  float CL0; // CL0 = 2*W/(rho*S*V^2)
62  float C1; // C1 = CD0/CL0
63  float C2; // C2 = CDi0/CL0 = B*CL0
64  float netto_rate;
65  float cosphi;
66  CL0 = polar_K / (aspd * aspd);
67  C1 = polar_CD0 / CL0; // constant describing expected angle to overcome zero-lift drag
68  C2 = polar_B * CL0; // constant describing expected angle to overcome lift induced drag at zero bank
69 
70  cosphi = (1 - phi * phi / 2); // first two terms of mclaurin series for cos(phi)
71  netto_rate = climb_rate + aspd * (C1 + C2 / (cosphi * cosphi)); // effect of aircraft drag removed
72 
73  // Remove acceleration effect - needs to be tested.
74  //float temp_netto = netto_rate;
75  //float dVdt = SpdHgt_Controller->get_VXdot();
76  //netto_rate = netto_rate + aspd*dVdt/GRAVITY_MSS;
77  //gcs().send_text(MAV_SEVERITY_INFO, "%f %f %f %f",temp_netto,dVdt,netto_rate,barometer.get_altitude());
78  return netto_rate;
79 }
AP_AHRS & _ahrs
Definition: Variometer.h:19
float roll
Definition: AP_AHRS.h:224
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float displayed_reading
Definition: Variometer.h:37
float alt
Definition: Variometer.h:34
const AP_Vehicle::FixedWing & _aparm
Definition: Variometer.h:20
#define ASPD_FILT
Definition: Variometer.h:13
#define TE_FILT
Definition: Variometer.h:14
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
float filtered_reading
Definition: Variometer.h:36
float _aspd_filt
Definition: Variometer.h:27
#define TE_FILT_DISPLAYED
Definition: Variometer.h:15
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
float _last_total_E
Definition: Variometer.h:30
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
Definition: Variometer.cpp:7
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
float _last_alt
Definition: Variometer.h:25
float correct_netto_rate(float climb_rate, float phi, float aspd, const float polar_K, const float polar_CD0, const float polar_B)
Definition: Variometer.cpp:53
bool new_data
Definition: Variometer.h:38
float _last_aspd
Definition: Variometer.h:28
float reading
Definition: Variometer.h:35
unsigned long _prev_update_time
Definition: Variometer.h:23
virtual void get_relative_position_D_home(float &posD) const =0
float _last_roll
Definition: Variometer.h:29
void update(const float polar_K, const float polar_CD0, const float polar_B)
Definition: Variometer.cpp:14
AP_Int32 airspeed_cruise_cm
Definition: AP_Vehicle.h:38