Variometer.cpp 3.6 KB

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