AP_Soaring.h 2.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798
  1. /*
  2. Soaring Controller class by Samuel Tabor
  3. Provides a layer between the thermal centring algorithm and the main
  4. code for managing navigation targets, data logging, tuning parameters,
  5. algorithm inputs and eventually other soaring strategies such as
  6. speed-to-fly. AP_TECS libary used for reference.
  7. */
  8. #pragma once
  9. #include <AP_AHRS/AP_AHRS.h>
  10. #include <AP_Param/AP_Param.h>
  11. #include <AP_Math/AP_Math.h>
  12. #include "ExtendedKalmanFilter.h"
  13. #include "Variometer.h"
  14. #include <AP_SpdHgtControl/AP_SpdHgtControl.h>
  15. #define EXPECTED_THERMALLING_SINK 0.7
  16. #define INITIAL_THERMAL_STRENGTH 2.0
  17. #define INITIAL_THERMAL_RADIUS 30.0 //150.0
  18. #define INITIAL_STRENGTH_COVARIANCE 0.0049
  19. #define INITIAL_RADIUS_COVARIANCE 2500.0
  20. #define INITIAL_POSITION_COVARIANCE 300.0
  21. class SoaringController {
  22. ExtendedKalmanFilter _ekf{};
  23. AP_AHRS &_ahrs;
  24. AP_SpdHgtControl &_spdHgt;
  25. Variometer _vario;
  26. // store aircraft location at last update
  27. struct Location _prev_update_location;
  28. // store time thermal was entered for hysteresis
  29. unsigned long _thermal_start_time_us;
  30. // store time cruise was entered for hysteresis
  31. unsigned long _cruise_start_time_us;
  32. // store time of last update
  33. unsigned long _prev_update_time;
  34. float _loiter_rad;
  35. bool _throttle_suppressed;
  36. float McCready(float alt);
  37. void get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy);
  38. void get_altitude_wrt_home(float *alt);
  39. protected:
  40. AP_Int8 soar_active;
  41. AP_Int8 soar_active_ch;
  42. AP_Float thermal_vspeed;
  43. AP_Float thermal_q1;
  44. AP_Float thermal_q2;
  45. AP_Float thermal_r;
  46. AP_Float thermal_distance_ahead;
  47. AP_Int16 min_thermal_s;
  48. AP_Int16 min_cruise_s;
  49. AP_Float polar_CD0;
  50. AP_Float polar_B;
  51. AP_Float polar_K;
  52. AP_Float alt_max;
  53. AP_Float alt_min;
  54. AP_Float alt_cutoff;
  55. public:
  56. SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms);
  57. // this supports the TECS_* user settable parameters
  58. static const struct AP_Param::GroupInfo var_info[];
  59. void get_target(Location & wp);
  60. bool suppress_throttle();
  61. bool check_thermal_criteria();
  62. bool check_cruise_criteria();
  63. bool check_init_thermal_criteria();
  64. void init_thermalling();
  65. void init_cruising();
  66. void update_thermalling();
  67. void update_cruising();
  68. bool is_active() const;
  69. bool get_throttle_suppressed() const
  70. {
  71. return _throttle_suppressed;
  72. }
  73. void set_throttle_suppressed(bool suppressed)
  74. {
  75. _throttle_suppressed = suppressed;
  76. }
  77. float get_vario_reading() const
  78. {
  79. return _vario.displayed_reading;
  80. }
  81. void update_vario();
  82. };