Variometer.h 996 B

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. /* Variometer class by Samuel Tabor
  2. Manages the estimation of aircraft total energy, drag and vertical air velocity.
  3. */
  4. #pragma once
  5. #include <AP_AHRS/AP_AHRS.h>
  6. #include <AP_Param/AP_Param.h>
  7. #include <AP_SpdHgtControl/AP_SpdHgtControl.h>
  8. #define ASPD_FILT 0.05
  9. #define TE_FILT 0.03
  10. #define TE_FILT_DISPLAYED 0.15
  11. class Variometer {
  12. AP_AHRS &_ahrs;
  13. const AP_Vehicle::FixedWing &_aparm;
  14. // store time of last update
  15. unsigned long _prev_update_time;
  16. float _last_alt;
  17. float _aspd_filt;
  18. float _last_aspd;
  19. float _last_roll;
  20. float _last_total_E;
  21. public:
  22. Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms);
  23. float alt;
  24. float reading;
  25. float filtered_reading;
  26. float displayed_reading;
  27. bool new_data;
  28. void update(const float polar_K, const float polar_CD0, const float polar_B);
  29. float correct_netto_rate(float climb_rate, float phi, float aspd, const float polar_K, const float polar_CD0, const float polar_B);
  30. };