AP_TECS.h 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377
  1. /// @file AP_TECS.h
  2. /// @brief Combined Total Energy Speed & Height Control. This is a instance of an
  3. /// AP_SpdHgtControl class
  4. /*
  5. * Written by Paul Riseborough 2013 to provide:
  6. * - Combined control of speed and height using throttle to control
  7. * total energy and pitch angle to control exchange of energy between
  8. * potential and kinetic.
  9. * Selectable speed or height priority modes when calculating pitch angle
  10. * - Fallback mode when no airspeed measurement is available that
  11. * sets throttle based on height rate demand and switches pitch angle control to
  12. * height priority
  13. * - Underspeed protection that demands maximum throttle switches pitch angle control
  14. * to speed priority mode
  15. * - Relative ease of tuning through use of intuitive time constant, trim rate and damping parameters and the use
  16. * of easy to measure aircraft performance data
  17. */
  18. #pragma once
  19. #include <AP_Math/AP_Math.h>
  20. #include <AP_AHRS/AP_AHRS.h>
  21. #include <AP_Param/AP_Param.h>
  22. #include <AP_Vehicle/AP_Vehicle.h>
  23. #include <AP_SpdHgtControl/AP_SpdHgtControl.h>
  24. #include <AP_Landing/AP_Landing.h>
  25. class AP_TECS : public AP_SpdHgtControl {
  26. public:
  27. AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing)
  28. : _ahrs(ahrs)
  29. , aparm(parms)
  30. , _landing(landing)
  31. {
  32. AP_Param::setup_object_defaults(this, var_info);
  33. }
  34. /* Do not allow copies */
  35. AP_TECS(const AP_TECS &other) = delete;
  36. AP_TECS &operator=(const AP_TECS&) = delete;
  37. // Update of the estimated height and height rate internal state
  38. // Update of the inertial speed rate internal state
  39. // Should be called at 50Hz or greater
  40. void update_50hz(void) override;
  41. // Update the control loop calculations
  42. void update_pitch_throttle(int32_t hgt_dem_cm,
  43. int32_t EAS_dem_cm,
  44. enum AP_Vehicle::FixedWing::FlightStage flight_stage,
  45. float distance_beyond_land_wp,
  46. int32_t ptchMinCO_cd,
  47. int16_t throttle_nudge,
  48. float hgt_afe,
  49. float load_factor,
  50. bool soaring_active) override;
  51. // demanded throttle in percentage
  52. // should return -100 to 100, usually positive unless reverse thrust is enabled via _THRminf < 0
  53. int32_t get_throttle_demand(void) override {
  54. return int32_t(_throttle_dem * 100.0f);
  55. }
  56. // demanded pitch angle in centi-degrees
  57. // should return between -9000 to +9000
  58. int32_t get_pitch_demand(void) override {
  59. return int32_t(_pitch_dem * 5729.5781f);
  60. }
  61. // Rate of change of velocity along X body axis in m/s^2
  62. float get_VXdot(void) override {
  63. return _vel_dot;
  64. }
  65. // return current target airspeed
  66. float get_target_airspeed(void) const override {
  67. return _TAS_dem / _ahrs.get_EAS2TAS();
  68. }
  69. // return maximum climb rate
  70. float get_max_climbrate(void) const override {
  71. return _maxClimbRate;
  72. }
  73. // added to let SoaringContoller reset pitch integrator to zero
  74. void reset_pitch_I(void) override {
  75. _integSEB_state = 0.0f;
  76. }
  77. // return landing sink rate
  78. float get_land_sinkrate(void) const override {
  79. return _land_sink;
  80. }
  81. // return landing airspeed
  82. float get_land_airspeed(void) const override {
  83. return _landAirspeed;
  84. }
  85. // return height rate demand, in m/s
  86. float get_height_rate_demand(void) const {
  87. return _hgt_rate_dem;
  88. }
  89. // set path_proportion
  90. void set_path_proportion(float path_proportion) override {
  91. _path_proportion = constrain_float(path_proportion, 0.0f, 1.0f);
  92. }
  93. // set pitch max limit in degrees
  94. void set_pitch_max_limit(int8_t pitch_limit) {
  95. _pitch_max_limit = pitch_limit;
  96. }
  97. // force use of synthetic airspeed for one loop
  98. void use_synthetic_airspeed(void) {
  99. _use_synthetic_airspeed_once = true;
  100. }
  101. // this supports the TECS_* user settable parameters
  102. static const struct AP_Param::GroupInfo var_info[];
  103. private:
  104. // Last time update_50Hz was called
  105. uint64_t _update_50hz_last_usec;
  106. // Last time update_speed was called
  107. uint64_t _update_speed_last_usec;
  108. // Last time update_pitch_throttle was called
  109. uint64_t _update_pitch_throttle_last_usec;
  110. // reference to the AHRS object
  111. AP_AHRS &_ahrs;
  112. const AP_Vehicle::FixedWing &aparm;
  113. // reference to const AP_Landing to access it's params
  114. const AP_Landing &_landing;
  115. // TECS tuning parameters
  116. AP_Float _hgtCompFiltOmega;
  117. AP_Float _spdCompFiltOmega;
  118. AP_Float _maxClimbRate;
  119. AP_Float _minSinkRate;
  120. AP_Float _maxSinkRate;
  121. AP_Float _timeConst;
  122. AP_Float _landTimeConst;
  123. AP_Float _ptchDamp;
  124. AP_Float _land_pitch_damp;
  125. AP_Float _landDamp;
  126. AP_Float _thrDamp;
  127. AP_Float _land_throttle_damp;
  128. AP_Float _integGain;
  129. AP_Float _integGain_takeoff;
  130. AP_Float _integGain_land;
  131. AP_Float _vertAccLim;
  132. AP_Float _rollComp;
  133. AP_Float _spdWeight;
  134. AP_Float _spdWeightLand;
  135. AP_Float _landThrottle;
  136. AP_Float _landAirspeed;
  137. AP_Float _land_sink;
  138. AP_Float _land_sink_rate_change;
  139. AP_Int8 _pitch_max;
  140. AP_Int8 _pitch_min;
  141. AP_Int8 _land_pitch_max;
  142. AP_Float _maxSinkRate_approach;
  143. AP_Int32 _options;
  144. enum {
  145. OPTION_GLIDER_ONLY=(1<<0),
  146. };
  147. // temporary _pitch_max_limit. Cleared on each loop. Clear when >= 90
  148. int8_t _pitch_max_limit = 90;
  149. // current height estimate (above field elevation)
  150. float _height;
  151. // throttle demand in the range from -1.0 to 1.0, usually positive unless reverse thrust is enabled via _THRminf < 0
  152. float _throttle_dem;
  153. // pitch angle demand in radians
  154. float _pitch_dem;
  155. // estimated climb rate (m/s)
  156. float _climb_rate;
  157. /*
  158. a filter to estimate climb rate if we don't have it from the EKF
  159. */
  160. struct {
  161. // height filter second derivative
  162. float dd_height;
  163. // height integration
  164. float height;
  165. } _height_filter;
  166. // Integrator state 4 - airspeed filter first derivative
  167. float _integDTAS_state;
  168. // Integrator state 5 - true airspeed
  169. float _TAS_state;
  170. // Integrator state 6 - throttle integrator
  171. float _integTHR_state;
  172. // Integrator state 6 - pitch integrator
  173. float _integSEB_state;
  174. // throttle demand rate limiter state
  175. float _last_throttle_dem;
  176. // pitch demand rate limiter state
  177. float _last_pitch_dem;
  178. // Rate of change of speed along X axis
  179. float _vel_dot;
  180. // Equivalent airspeed
  181. float _EAS;
  182. // True airspeed limits
  183. float _TASmax;
  184. float _TASmin;
  185. // Current true airspeed demand
  186. float _TAS_dem;
  187. // Equivalent airspeed demand
  188. float _EAS_dem;
  189. // height demands
  190. float _hgt_dem;
  191. float _hgt_dem_in_old;
  192. float _hgt_dem_adj;
  193. float _hgt_dem_adj_last;
  194. float _hgt_rate_dem;
  195. float _hgt_dem_prev;
  196. float _land_hgt_dem;
  197. // Speed demand after application of rate limiting
  198. // This is the demand tracked by the TECS control loops
  199. float _TAS_dem_adj;
  200. // Speed rate demand after application of rate limiting
  201. // This is the demand tracked by the TECS control loops
  202. float _TAS_rate_dem;
  203. // Total energy rate filter state
  204. float _STEdotErrLast;
  205. struct flags {
  206. // Underspeed condition
  207. bool underspeed:1;
  208. // Bad descent condition caused by unachievable airspeed demand
  209. bool badDescent:1;
  210. // true when plane is in auto mode and executing a land mission item
  211. bool is_doing_auto_land:1;
  212. // true when we have reached target speed in takeoff
  213. bool reached_speed_takeoff:1;
  214. };
  215. union {
  216. struct flags _flags;
  217. uint8_t _flags_byte;
  218. };
  219. // time when underspeed started
  220. uint32_t _underspeed_start_ms;
  221. // auto mode flightstage
  222. enum AP_Vehicle::FixedWing::FlightStage _flight_stage;
  223. // pitch demand before limiting
  224. float _pitch_dem_unc;
  225. // Maximum and minimum specific total energy rate limits
  226. float _STEdot_max;
  227. float _STEdot_min;
  228. // Maximum and minimum floating point throttle limits
  229. float _THRmaxf;
  230. float _THRminf;
  231. // Maximum and minimum floating point pitch limits
  232. float _PITCHmaxf;
  233. float _PITCHminf;
  234. // Specific energy quantities
  235. float _SPE_dem;
  236. float _SKE_dem;
  237. float _SPEdot_dem;
  238. float _SKEdot_dem;
  239. float _SPE_est;
  240. float _SKE_est;
  241. float _SPEdot;
  242. float _SKEdot;
  243. // Specific energy error quantities
  244. float _STE_error;
  245. // Time since last update of main TECS loop (seconds)
  246. float _DT;
  247. // counter for demanded sink rate on land final
  248. uint8_t _flare_counter;
  249. // slew height demand lag filter value when transition to land
  250. float hgt_dem_lag_filter_slew;
  251. // percent traveled along the previous and next waypoints
  252. float _path_proportion;
  253. float _distance_beyond_land_wp;
  254. float _land_pitch_min = -90;
  255. // internal variables to be logged
  256. struct {
  257. float SKE_weighting;
  258. float SPE_error;
  259. float SKE_error;
  260. float SEB_delta;
  261. } logging;
  262. AP_Int8 _use_synthetic_airspeed;
  263. // use synthetic airspeed for next loop
  264. bool _use_synthetic_airspeed_once;
  265. // Update the airspeed internal state using a second order complementary filter
  266. void _update_speed(float load_factor);
  267. // Update the demanded airspeed
  268. void _update_speed_demand(void);
  269. // Update the demanded height
  270. void _update_height_demand(void);
  271. // Detect an underspeed condition
  272. void _detect_underspeed(void);
  273. // Update Specific Energy Quantities
  274. void _update_energies(void);
  275. // Update Demanded Throttle
  276. void _update_throttle_with_airspeed(void);
  277. // Update Demanded Throttle Non-Airspeed
  278. void _update_throttle_without_airspeed(int16_t throttle_nudge);
  279. // get integral gain which is flight_stage dependent
  280. float _get_i_gain(void);
  281. // Detect Bad Descent
  282. void _detect_bad_descent(void);
  283. // Update Demanded Pitch Angle
  284. void _update_pitch(void);
  285. // Initialise states and variables
  286. void _initialise_states(int32_t ptchMinCO_cd, float hgt_afe);
  287. // Calculate specific total energy rate limits
  288. void _update_STE_rate_lim(void);
  289. // declares a 5point average filter using floats
  290. AverageFilterFloat_Size5 _vdot_filter;
  291. // current time constant
  292. float timeConstant(void) const;
  293. };