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