APM:Libraries
AP_TECS.cpp
Go to the documentation of this file.
1 #include "AP_TECS.h"
2 #include <AP_HAL/AP_HAL.h>
3 
4 extern const AP_HAL::HAL& hal;
5 
6 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
7 #include <stdio.h>
8 # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
9 #else
10 # define Debug(fmt, args ...)
11 #endif
12 //Debug("%.2f %.2f %.2f %.2f \n", var1, var2, var3, var4);
13 
14 // table of user settable parameters
16 
17  // @Param: CLMB_MAX
18  // @DisplayName: Maximum Climb Rate (metres/sec)
19  // @Description: This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand require to climb and maintain speed is noticeably less than THR_MAX, then either CLMB_MAX should be increased or THR_MAX reduced.
20  // @Increment: 0.1
21  // @Range: 0.1 20.0
22  // @User: Standard
23  AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f),
24 
25  // @Param: SINK_MIN
26  // @DisplayName: Minimum Sink Rate (metres/sec)
27  // @Description: This is the sink rate of the aircraft with the throttle set to THR_MIN and the same airspeed as used to measure CLMB_MAX.
28  // @Increment: 0.1
29  // @Range: 0.1 10.0
30  // @User: Standard
31  AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f),
32 
33  // @Param: TIME_CONST
34  // @DisplayName: Controller time constant (sec)
35  // @Description: This is the time constant of the TECS control algorithm. Smaller values make it faster to respond, large values make it slower to respond.
36  // @Range: 3.0 10.0
37  // @Increment: 0.2
38  // @User: Advanced
39  AP_GROUPINFO("TIME_CONST", 2, AP_TECS, _timeConst, 5.0f),
40 
41  // @Param: THR_DAMP
42  // @DisplayName: Controller throttle damping
43  // @Description: This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height.
44  // @Range: 0.1 1.0
45  // @Increment: 0.1
46  // @User: Advanced
47  AP_GROUPINFO("THR_DAMP", 3, AP_TECS, _thrDamp, 0.5f),
48 
49  // @Param: INTEG_GAIN
50  // @DisplayName: Controller integrator
51  // @Description: This is the integrator gain on the control loop. Increase to increase the rate at which speed and height offsets are trimmed out
52  // @Range: 0.0 0.5
53  // @Increment: 0.02
54  // @User: Advanced
55  AP_GROUPINFO("INTEG_GAIN", 4, AP_TECS, _integGain, 0.1f),
56 
57  // @Param: VERT_ACC
58  // @DisplayName: Vertical Acceleration Limit (metres/sec^2)
59  // @Description: This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.
60  // @Range: 1.0 10.0
61  // @Increment: 0.5
62  // @User: Advanced
63  AP_GROUPINFO("VERT_ACC", 5, AP_TECS, _vertAccLim, 7.0f),
64 
65  // @Param: HGT_OMEGA
66  // @DisplayName: Height complementary filter frequency (radians/sec)
67  // @Description: This is the cross-over frequency of the complementary filter used to fuse vertical acceleration and baro alt to obtain an estimate of height rate and height.
68  // @Range: 1.0 5.0
69  // @Increment: 0.05
70  // @User: Advanced
71  AP_GROUPINFO("HGT_OMEGA", 6, AP_TECS, _hgtCompFiltOmega, 3.0f),
72 
73  // @Param: SPD_OMEGA
74  // @DisplayName: Speed complementary filter frequency (radians/sec)
75  // @Description: This is the cross-over frequency of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain a lower noise and lag estimate of airspeed.
76  // @Range: 0.5 2.0
77  // @Increment: 0.05
78  // @User: Advanced
79  AP_GROUPINFO("SPD_OMEGA", 7, AP_TECS, _spdCompFiltOmega, 2.0f),
80 
81  // @Param: RLL2THR
82  // @DisplayName: Bank angle compensation gain
83  // @Description: Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value.
84  // @Range: 5.0 30.0
85  // @Increment: 1.0
86  // @User: Advanced
87  AP_GROUPINFO("RLL2THR", 8, AP_TECS, _rollComp, 10.0f),
88 
89  // @Param: SPDWEIGHT
90  // @DisplayName: Weighting applied to speed control
91  // @Description: This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airsped errors, but give larger height errors. A value of 1.0 gives a balanced response and is the default.
92  // @Range: 0.0 2.0
93  // @Increment: 0.1
94  // @User: Advanced
95  AP_GROUPINFO("SPDWEIGHT", 9, AP_TECS, _spdWeight, 1.0f),
96 
97  // @Param: PTCH_DAMP
98  // @DisplayName: Controller pitch damping
99  // @Description: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in speed and height.
100  // @Range: 0.1 1.0
101  // @Increment: 0.1
102  // @User: Advanced
103  AP_GROUPINFO("PTCH_DAMP", 10, AP_TECS, _ptchDamp, 0.0f),
104 
105  // @Param: SINK_MAX
106  // @DisplayName: Maximum Descent Rate (metres/sec)
107  // @Description: This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft will reach the pitch angle limit first and be unable to achieve the descent rate. This should be set to a value that can be achieved at the lower pitch angle limit.
108  // @Increment: 0.1
109  // @Range: 0.0 20.0
110  // @User: User
111  AP_GROUPINFO("SINK_MAX", 11, AP_TECS, _maxSinkRate, 5.0f),
112 
113  // @Param: LAND_ARSPD
114  // @DisplayName: Airspeed during landing approach (m/s)
115  // @Description: When performing an autonomus landing, this value is used as the goal airspeed during approach. Note that this parameter is not useful if your platform does not have an airspeed sensor (use TECS_LAND_THR instead). If negative then this value is not used during landing.
116  // @Range: -1 127
117  // @Increment: 1
118  // @User: User
119  AP_GROUPINFO("LAND_ARSPD", 12, AP_TECS, _landAirspeed, -1),
120 
121  // @Param: LAND_THR
122  // @DisplayName: Cruise throttle during landing approach (percentage)
123  // @Description: Use this parameter instead of LAND_ARSPD if your platform does not have an airspeed sensor. It is the cruise throttle during landing approach. If this value is negative then it is disabled and TECS_LAND_ARSPD is used instead.
124  // @Range: -1 100
125  // @Increment: 0.1
126  // @User: User
127  AP_GROUPINFO("LAND_THR", 13, AP_TECS, _landThrottle, -1),
128 
129  // @Param: LAND_SPDWGT
130  // @DisplayName: Weighting applied to speed control during landing.
131  // @Description: Same as SPDWEIGHT parameter, with the exception that this parameter is applied during landing flight stages. A value closer to 2 will result in the plane ignoring height error during landing and our experience has been that the plane will therefore keep the nose up -- sometimes good for a glider landing (with the side effect that you will likely glide a ways past the landing point). A value closer to 0 results in the plane ignoring speed error -- use caution when lowering the value below 1 -- ignoring speed could result in a stall. Values between 0 and 2 are valid values for a fixed landing weight. When using -1 the weight will be scaled during the landing. At the start of the landing approach it starts with TECS_SPDWEIGHT and scales down to 0 by the time you reach the land point. Example: Halfway down the landing approach you'll effectively have a weight of TECS_SPDWEIGHT/2.
132  // @Range: -1.0 2.0
133  // @Increment: 0.1
134  // @User: Advanced
135  AP_GROUPINFO("LAND_SPDWGT", 14, AP_TECS, _spdWeightLand, -1.0f),
136 
137  // @Param: PITCH_MAX
138  // @DisplayName: Maximum pitch in auto flight
139  // @Description: This controls maximum pitch up in automatic throttle modes. If this is set to zero then LIM_PITCH_MAX is used instead. The purpose of this parameter is to allow the use of a smaller pitch range when in automatic flight than what is used in FBWA mode.
140  // @Range: 0 45
141  // @Increment: 1
142  // @User: Advanced
143  AP_GROUPINFO("PITCH_MAX", 15, AP_TECS, _pitch_max, 0),
144 
145  // @Param: PITCH_MIN
146  // @DisplayName: Minimum pitch in auto flight
147  // @Description: This controls minimum pitch in automatic throttle modes. If this is set to zero then LIM_PITCH_MIN is used instead. The purpose of this parameter is to allow the use of a smaller pitch range when in automatic flight than what is used in FBWA mode. Note that TECS_PITCH_MIN should be a negative number.
148  // @Range: -45 0
149  // @Increment: 1
150  // @User: Advanced
151  AP_GROUPINFO("PITCH_MIN", 16, AP_TECS, _pitch_min, 0),
152 
153  // @Param: LAND_SINK
154  // @DisplayName: Sink rate for final landing stage
155  // @Description: The sink rate in meters/second for the final stage of landing.
156  // @Range: 0.0 2.0
157  // @Increment: 0.1
158  // @User: Advanced
159  AP_GROUPINFO("LAND_SINK", 17, AP_TECS, _land_sink, 0.25f),
160 
161  // @Param: LAND_TCONST
162  // @DisplayName: Land controller time constant (sec)
163  // @Description: This is the time constant of the TECS control algorithm when in final landing stage of flight. It should be smaller than TECS_TIME_CONST to allow for faster flare
164  // @Range: 1.0 5.0
165  // @Increment: 0.2
166  // @User: Advanced
167  AP_GROUPINFO("LAND_TCONST", 18, AP_TECS, _landTimeConst, 2.0f),
168 
169  // @Param: LAND_DAMP
170  // @DisplayName: Controller sink rate to pitch gain during flare
171  // @Description: This is the sink rate gain for the pitch demand loop when in final landing stage of flight. It should be larger than TECS_PTCH_DAMP to allow for better sink rate control during flare.
172  // @Range: 0.1 1.0
173  // @Increment: 0.1
174  // @User: Advanced
175  AP_GROUPINFO("LAND_DAMP", 19, AP_TECS, _landDamp, 0.5f),
176 
177  // @Param: LAND_PMAX
178  // @DisplayName: Maximum pitch during final stage of landing
179  // @Description: This limits the pitch used during the final stage of automatic landing. During the final landing stage most planes need to keep their pitch small to avoid stalling. A maximum of 10 degrees is usually good. A value of zero means to use the normal pitch limits.
180  // @Range: -5 40
181  // @Increment: 1
182  // @User: Advanced
183  AP_GROUPINFO("LAND_PMAX", 20, AP_TECS, _land_pitch_max, 10),
184 
185  // @Param: APPR_SMAX
186  // @DisplayName: Sink rate max for landing approach stage
187  // @Description: The sink rate max for the landing approach stage of landing. This will need to be large for steep landing approaches especially when using reverse thrust. If 0, then use TECS_SINK_MAX.
188  // @Range: 0.0 20.0
189  // @Units: m/s
190  // @Increment: 0.1
191  // @User: Advanced
192  AP_GROUPINFO("APPR_SMAX", 21, AP_TECS, _maxSinkRate_approach, 0),
193 
194  // @Param: LAND_SRC
195  // @DisplayName: Land sink rate change
196  // @Description: When zero, the flare sink rate (TECS_LAND_SINK) is a fixed sink demand. With this enabled the flare sinkrate will increase/decrease the flare sink demand as you get further beyond the LAND waypoint. Has no effect before the waypoint. This value is added to TECS_LAND_SINK proportional to distance traveled after wp. With an increasing sink rate you can still land in a given distance if you're traveling too fast and cruise passed the land point. A positive value will force the plane to land sooner proportional to distance passed land point. A negative number will tell the plane to slowly climb allowing for a pitched-up stall landing. Recommend 0.2 as initial value.
197  // @Range: -2.0 2.0
198  // @Units: m/s/m
199  // @Increment: 0.1
200  // @User: Advanced
201  AP_GROUPINFO("LAND_SRC", 22, AP_TECS, _land_sink_rate_change, 0),
202 
203  // @Param: LAND_TDAMP
204  // @DisplayName: Controller throttle damping when landing
205  // @Description: This is the damping gain for the throttle demand loop during and auto-landing. Same as TECS_THR_DAMP but only in effect during an auto-land. Increase to add damping to correct for oscillations in speed and height. When set to 0 landing throttle damp is controlled by TECS_THR_DAMP.
206  // @Range: 0.1 1.0
207  // @Increment: 0.1
208  // @User: Advanced
209  AP_GROUPINFO("LAND_TDAMP", 23, AP_TECS, _land_throttle_damp, 0),
210 
211  // @Param: LAND_IGAIN
212  // @DisplayName: Controller integrator during landing
213  // @Description: This is the integrator gain on the control loop during landing. When set to 0 then TECS_INTEG_GAIN is used. Increase to increase the rate at which speed and height offsets are trimmed out. Typically values lower than TECS_INTEG_GAIN work best
214  // @Range: 0.0 0.5
215  // @Increment: 0.02
216  // @User: Advanced
217  AP_GROUPINFO("LAND_IGAIN", 24, AP_TECS, _integGain_land, 0),
218 
219  // @Param: TKOFF_IGAIN
220  // @DisplayName: Controller integrator during takeoff
221  // @Description: This is the integrator gain on the control loop during takeoff. When set to 0 then TECS_INTEG_GAIN is used. Increase to increase the rate at which speed and height offsets are trimmed out. Typically values higher than TECS_INTEG_GAIN work best
222  // @Range: 0.0 0.5
223  // @Increment: 0.02
224  // @User: Advanced
225  AP_GROUPINFO("TKOFF_IGAIN", 25, AP_TECS, _integGain_takeoff, 0),
226 
227  // @Param: LAND_PDAMP
228  // @DisplayName: Pitch damping gain when landing
229  // @Description: This is the damping gain for the pitch demand loop during landing. Increase to add damping to correct for oscillations in speed and height. If set to 0 then TECS_PTCH_DAMP will be used instead.
230  // @Range: 0.1 1.0
231  // @Increment: 0.1
232  // @User: Advanced
233  AP_GROUPINFO("LAND_PDAMP", 26, AP_TECS, _land_pitch_damp, 0),
234 
235  // @Param: SYNAIRSPEED
236  // @DisplayName: Enable the use of synthetic airspeed
237  // @Description: This enable the use of synthetic airspeed for aircraft that don't have a real airspeed sensor. This is useful for development testing where the user is aware of the considerable limitations of the synthetic airspeed system, such as very poor estimates when a wind estimate is not accurate. Do not enable this option unless you fully understand the limitations of a synthetic airspeed estimate.
238  // @Values: 0:Disable,1:Enable
239  // @User: Advanced
240  AP_GROUPINFO("SYNAIRSPEED", 27, AP_TECS, _use_synthetic_airspeed, 0),
241 
243 };
244 
245 /*
246  * Written by Paul Riseborough 2013 to provide:
247  * - Combined control of speed and height using throttle to control
248  * total energy and pitch angle to control exchange of energy between
249  * potential and kinetic.
250  * Selectable speed or height priority modes when calculating pitch angle
251  * - Fallback mode when no airspeed measurement is available that
252  * sets throttle based on height rate demand and switches pitch angle control to
253  * height priority
254  * - Underspeed protection that demands maximum throttle and switches pitch angle control
255  * to speed priority mode
256  * - Relative ease of tuning through use of intuitive time constant, integrator and damping gains and the use
257  * of easy to measure aircraft performance data
258  *
259  */
260 
262 {
263  // Implement third order complementary filter for height and height rate
264  // estimated height rate = _climb_rate
265  // estimated height above field elevation = _height
266  // Reference Paper :
267  // Optimizing the Gains of the Baro-Inertial Vertical Channel
268  // Widnall W.S, Sinha P.K,
269  // AIAA Journal of Guidance and Control, 78-1307R
270 
271  /*
272  if we have a vertical position estimate from the EKF then use
273  it, otherwise use barometric altitude
274  */
276  _height *= -1.0f;
277 
278  // Calculate time in seconds since last update
279  uint64_t now = AP_HAL::micros64();
280  float DT = (now - _update_50hz_last_usec) * 1.0e-6f;
281  if (DT > 1.0f) {
282  _climb_rate = 0.0f;
283  _height_filter.dd_height = 0.0f;
284  DT = 0.02f; // when first starting TECS, use a
285  // small time constant
286  }
288 
289  // Use inertial nav verical velocity and height if available
290  Vector3f velned;
291  if (_ahrs.get_velocity_NED(velned)) {
292  // if possible use the EKF vertical velocity
293  _climb_rate = -velned.z;
294  } else {
295  /*
296  use a complimentary filter to calculate climb_rate. This is
297  designed to minimise lag
298  */
299  const float baro_alt = AP::baro().get_altitude();
300  // Get height acceleration
301  float hgt_ddot_mea = -(_ahrs.get_accel_ef().z + GRAVITY_MSS);
302  // Perform filter calculation using backwards Euler integration
303  // Coefficients selected to place all three filter poles at omega
304  float omega2 = _hgtCompFiltOmega*_hgtCompFiltOmega;
305  float hgt_err = baro_alt - _height_filter.height;
306  float integ1_input = hgt_err * omega2 * _hgtCompFiltOmega;
307 
308  _height_filter.dd_height += integ1_input * DT;
309 
310  float integ2_input = _height_filter.dd_height + hgt_ddot_mea + hgt_err * omega2 * 3.0f;
311 
312  _climb_rate += integ2_input * DT;
313 
314  float integ3_input = _climb_rate + hgt_err * _hgtCompFiltOmega * 3.0f;
315  // If more than 1 second has elapsed since last update then reset the integrator state
316  // to the measured height
317  if (DT > 1.0f) {
318  _height_filter.height = _height;
319  } else {
320  _height_filter.height += integ3_input*DT;
321  }
322  }
323 
324  // Update and average speed rate of change
325  // Get DCM
326  const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
327  // Calculate speed rate of change
328  float temp = rotMat.c.x * GRAVITY_MSS + AP::ins().get_accel().x;
329  // take 5 point moving average
330  _vel_dot = _vdot_filter.apply(temp);
331 
332 }
333 
334 void AP_TECS::_update_speed(float load_factor)
335 {
336  // Calculate time in seconds since last update
337  uint64_t now = AP_HAL::micros64();
338  float DT = (now - _update_speed_last_usec) * 1.0e-6f;
340 
341  // Convert equivalent airspeeds to true airspeeds
342 
343  float EAS2TAS = _ahrs.get_EAS2TAS();
344  _TAS_dem = _EAS_dem * EAS2TAS;
345  _TASmax = aparm.airspeed_max * EAS2TAS;
346  _TASmin = aparm.airspeed_min * EAS2TAS;
347 
348  if (aparm.stall_prevention) {
349  // when stall prevention is active we raise the mimimum
350  // airspeed based on aerodynamic load factor
351  _TASmin *= load_factor;
352  }
353 
354  if (_TASmax < _TASmin) {
355  _TASmax = _TASmin;
356  }
357  if (_TASmin > _TAS_dem) {
358  _TASmin = _TAS_dem;
359  }
360 
361  // Reset states of time since last update is too large
362  if (DT > 1.0f) {
363  _TAS_state = (_EAS * EAS2TAS);
364  _integDTAS_state = 0.0f;
365  DT = 0.1f; // when first starting TECS, use a
366  // small time constant
367  }
368 
369  // Get airspeed or default to halfway between min and max if
370  // airspeed is not being used and set speed rate to zero
372  if (!use_airspeed || !_ahrs.airspeed_estimate(&_EAS)) {
373  // If no airspeed available use average of min and max
374  _EAS = 0.5f * (aparm.airspeed_min.get() + (float)aparm.airspeed_max.get());
375  }
376 
377  // Implement a second order complementary filter to obtain a
378  // smoothed airspeed estimate
379  // airspeed estimate is held in _TAS_state
380  float aspdErr = (_EAS * EAS2TAS) - _TAS_state;
381  float integDTAS_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega;
382  // Prevent state from winding up
383  if (_TAS_state < 3.1f) {
384  integDTAS_input = MAX(integDTAS_input , 0.0f);
385  }
386  _integDTAS_state = _integDTAS_state + integDTAS_input * DT;
387  float TAS_input = _integDTAS_state + _vel_dot + aspdErr * _spdCompFiltOmega * 1.4142f;
388  _TAS_state = _TAS_state + TAS_input * DT;
389  // limit the airspeed to a minimum of 3 m/s
390  _TAS_state = MAX(_TAS_state, 3.0f);
391 
392 }
393 
395 {
396  // Set the airspeed demand to the minimum value if an underspeed condition exists
397  // or a bad descent condition exists
398  // This will minimise the rate of descent resulting from an engine failure,
399  // enable the maximum climb rate to be achieved and prevent continued full power descent
400  // into the ground due to an unachievable airspeed value
401  if ((_flags.badDescent) || (_flags.underspeed))
402  {
403  _TAS_dem = _TASmin;
404  }
405 
406  // Constrain speed demand, taking into account the load factor
408 
409  // calculate velocity rate limits based on physical performance limits
410  // provision to use a different rate limit if bad descent or underspeed condition exists
411  // Use 50% of maximum energy rate to allow margin for total energy contgroller
412  float velRateMax = 0.5f * _STEdot_max / _TAS_state;
413  float velRateMin = 0.5f * _STEdot_min / _TAS_state;
414 
415  // Apply rate limit
416  if ((_TAS_dem - _TAS_dem_adj) > (velRateMax * 0.1f))
417  {
418  _TAS_dem_adj = _TAS_dem_adj + velRateMax * 0.1f;
419  _TAS_rate_dem = velRateMax;
420  }
421  else if ((_TAS_dem - _TAS_dem_adj) < (velRateMin * 0.1f))
422  {
423  _TAS_dem_adj = _TAS_dem_adj + velRateMin * 0.1f;
424  _TAS_rate_dem = velRateMin;
425  }
426  else
427  {
429  _TAS_rate_dem = (_TAS_dem - _TAS_dem_last) / 0.1f;
430  }
431  // Constrain speed demand again to protect against bad values on initialisation.
434 }
435 
437 {
438  // Apply 2 point moving average to demanded height
439  _hgt_dem = 0.5f * (_hgt_dem + _hgt_dem_in_old);
441 
442  float max_sink_rate = _maxSinkRate;
444  // special sink rate for approach to accommodate steep slopes and reverse thrust.
445  // A special check must be done to see if we're LANDing on approach but also if
446  // we're in that tiny window just starting NAV_LAND but still in NORMAL mode. If
447  // we have a steep slope with a short approach we'll want to allow acquiring the
448  // glide slope right away.
449  max_sink_rate = _maxSinkRate_approach;
450  }
451 
452  // Limit height rate of change
453  if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f))
454  {
456  }
457  else if ((_hgt_dem - _hgt_dem_prev) < (-max_sink_rate * 0.1f))
458  {
459  _hgt_dem = _hgt_dem_prev - max_sink_rate * 0.1f;
460  }
462 
463  // Apply first order lag to height demand
464  _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
465 
466  // when flaring force height rate demand to the
467  // configured sink rate and adjust the demanded height to
468  // be kinematically consistent with the height rate.
469  if (_landing.is_flaring()) {
470  _integSEB_state = 0;
471  if (_flare_counter == 0) {
474  }
475 
476  // adjust the flare sink rate to increase/decrease as your travel further beyond the land wp
477  float land_sink_rate_adj = _land_sink + _land_sink_rate_change*_distance_beyond_land_wp;
478 
479  // bring it in over 1s to prevent overshoot
480  if (_flare_counter < 10) {
481  _hgt_rate_dem = _hgt_rate_dem * 0.8f - 0.2f * land_sink_rate_adj;
482  _flare_counter++;
483  } else {
484  _hgt_rate_dem = - land_sink_rate_adj;
485  }
486  _land_hgt_dem += 0.1f * _hgt_rate_dem;
488  } else {
490  _flare_counter = 0;
491  }
492 
493  // for landing approach we will predict ahead by the time constant
494  // plus the lag produced by the first order filter. This avoids a
495  // lagged height demand while constantly descending which causes
496  // us to consistently be above the desired glide slope. This will
497  // be replaced with a better zero-lag filter in the future.
498  float new_hgt_dem = _hgt_dem_adj;
500  if (hgt_dem_lag_filter_slew < 1) {
501  hgt_dem_lag_filter_slew += 0.1f; // increment at 10Hz to gradually apply the compensation at first
502  } else {
504  }
506  } else {
508  }
510  _hgt_dem_adj = new_hgt_dem;
511 }
512 
514 {
515  // see if we can clear a previous underspeed condition. We clear
516  // it if we are now more than 15% above min speed, and haven't
517  // been below min speed for at least 3 seconds.
518  if (_flags.underspeed &&
519  _TAS_state >= _TASmin * 1.15f &&
520  AP_HAL::millis() - _underspeed_start_ms > 3000U) {
521  _flags.underspeed = false;
522  }
523 
525  _flags.underspeed = false;
526  } else if (((_TAS_state < _TASmin * 0.9f) &&
527  (_throttle_dem >= _THRmaxf * 0.95f) &&
528  !_landing.is_flaring()) ||
530  {
531  _flags.underspeed = true;
532  if (_TAS_state < _TASmin * 0.9f) {
533  // reset start time as we are still underspeed
535  }
536  }
537  else
538  {
539  // this clears underspeed if we reach our demanded height and
540  // we are either below 95% throttle or we above 90% of min
541  // airspeed
542  _flags.underspeed = false;
543  }
544 }
545 
547 {
548  // Calculate specific energy demands
551 
552  // Calculate specific energy rate demands
555 
556  // Calculate specific energy
558  _SKE_est = 0.5f * _TAS_state * _TAS_state;
559 
560  // Calculate specific energy rate
562  _SKEdot = _TAS_state * _vel_dot;
563 
564 }
565 
566 /*
567  current time constant. It is lower in landing to try to give a precise approach
568  */
569 float AP_TECS::timeConstant(void) const
570 {
572  if (_landTimeConst < 0.1f) {
573  return 0.1f;
574  }
575  return _landTimeConst;
576  }
577  if (_timeConst < 0.1f) {
578  return 0.1f;
579  }
580  return _timeConst;
581 }
582 
583 /*
584  calculate throttle demand - airspeed enabled case
585  */
587 {
588  // Calculate limits to be applied to potential energy error to prevent over or underspeed occurring due to large height errors
589  float SPE_err_max = 0.5f * _TASmax * _TASmax - _SKE_dem;
590  float SPE_err_min = 0.5f * _TASmin * _TASmin - _SKE_dem;
591 
593  /*
594  when we are in a VTOL state then we ignore potential energy
595  errors as we have vertical motors that interfere with the
596  total energy calculation.
597  */
598  SPE_err_max = SPE_err_min = 0;
599  }
600 
601  // Calculate total energy error
602  _STE_error = constrain_float((_SPE_dem - _SPE_est), SPE_err_min, SPE_err_max) + _SKE_dem - _SKE_est;
604  float STEdot_error = STEdot_dem - _SPEdot - _SKEdot;
605 
606  // Apply 0.5 second first order filter to STEdot_error
607  // This is required to remove accelerometer noise from the measurement
608  STEdot_error = 0.2f*STEdot_error + 0.8f*_STEdotErrLast;
609  _STEdotErrLast = STEdot_error;
610 
611  // Calculate throttle demand
612  // If underspeed condition is set, then demand full throttle
613  if (_flags.underspeed)
614  {
615  _throttle_dem = 1.0f;
616  }
617  else
618  {
619  // Calculate gain scaler from specific energy error to throttle
620  // (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf) is the derivative of STEdot wrt throttle measured across the max allowed throttle range.
621  float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf));
622 
623  // Calculate feed-forward throttle
624  float ff_throttle = 0;
625  float nomThr = aparm.throttle_cruise * 0.01f;
626  const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
627  // Use the demanded rate of change of total energy as the feed-forward demand, but add
628  // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
629  // drag increase during turns.
630  float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
631  STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
632  ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
633 
634  // Calculate PD + FF throttle
635  float throttle_damp = _thrDamp;
637  throttle_damp = _land_throttle_damp;
638  }
639  _throttle_dem = (_STE_error + STEdot_error * throttle_damp) * K_STE2Thr + ff_throttle;
640 
641  // Constrain throttle demand
643 
644  float THRminf_clipped_to_zero = constrain_float(_THRminf, 0, _THRmaxf);
645 
646  // Rate limit PD + FF throttle
647  // Calculate the throttle increment from the specified slew time
648  if (aparm.throttle_slewrate != 0) {
649  float thrRateIncr = _DT * (_THRmaxf - THRminf_clipped_to_zero) * aparm.throttle_slewrate * 0.01f;
650 
652  _last_throttle_dem - thrRateIncr,
653  _last_throttle_dem + thrRateIncr);
655  }
656 
657  // Calculate integrator state upper and lower limits
658  // Set to a value that will allow 0.1 (10%) throttle saturation to allow for noise on the demand
659  // Additionally constrain the integrator state amplitude so that the integrator comes off limits faster.
660  float maxAmp = 0.5f*(_THRmaxf - THRminf_clipped_to_zero);
661  float integ_max = constrain_float((_THRmaxf - _throttle_dem + 0.1f),-maxAmp,maxAmp);
662  float integ_min = constrain_float((_THRminf - _throttle_dem - 0.1f),-maxAmp,maxAmp);
663 
664  // Calculate integrator state, constraining state
665  // Set integrator to a max throttle value during climbout
666  _integTHR_state = _integTHR_state + (_STE_error * _get_i_gain()) * _DT * K_STE2Thr;
668  {
670  // ensure we run at full throttle until we reach the target airspeed
672  }
673  _integTHR_state = integ_max;
674  }
675  else
676  {
677  _integTHR_state = constrain_float(_integTHR_state, integ_min, integ_max);
678  }
679 
680  // Sum the components.
682  }
683 
684  // Constrain throttle demand
686 }
687 
689 {
690  float i_gain = _integGain;
692  if (!is_zero(_integGain_takeoff)) {
693  i_gain = _integGain_takeoff;
694  }
695  } else if (_flags.is_doing_auto_land) {
696  if (!is_zero(_integGain_land)) {
697  i_gain = _integGain_land;
698  }
699  }
700  return i_gain;
701 }
702 
703 /*
704  calculate throttle, non-airspeed case
705  */
706 void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
707 {
708  // Calculate throttle demand by interpolating between pitch and throttle limits
709  float nomThr;
710  //If landing and we don't have an airspeed sensor and we have a non-zero
711  //TECS_LAND_THR param then use it
713  nomThr = (_landThrottle + throttle_nudge) * 0.01f;
714  } else { //not landing or not using TECS_LAND_THR parameter
715  nomThr = (aparm.throttle_cruise + throttle_nudge)* 0.01f;
716  }
717 
718  if (_pitch_dem > 0.0f && _PITCHmaxf > 0.0f)
719  {
720  _throttle_dem = nomThr + (_THRmaxf - nomThr) * _pitch_dem / _PITCHmaxf;
721  }
722  else if (_pitch_dem < 0.0f && _PITCHminf < 0.0f)
723  {
724  _throttle_dem = nomThr + (_THRminf - nomThr) * _pitch_dem / _PITCHminf;
725  }
726  else
727  {
728  _throttle_dem = nomThr;
729  }
730 
731  // Calculate additional throttle for turn drag compensation including throttle nudging
732  const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
733  // Use the demanded rate of change of total energy as the feed-forward demand, but add
734  // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
735  // drag increase during turns.
736  float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
737  float STEdot_dem = _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
738  _throttle_dem = _throttle_dem + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
739 }
740 
742 {
743  // Detect a demanded airspeed too high for the aircraft to achieve. This will be
744  // evident by the the following conditions:
745  // 1) Underspeed protection not active
746  // 2) Specific total energy error > 200 (greater than ~20m height error)
747  // 3) Specific total energy reducing
748  // 4) throttle demand > 90%
749  // If these four conditions exist simultaneously, then the protection
750  // mode will be activated.
751  // Once active, the following condition are required to stay in the mode
752  // 1) Underspeed protection not active
753  // 2) Specific total energy error > 0
754  // This mode will produce an undulating speed and height response as it cuts in and out but will prevent the aircraft from descending into the ground if an unachievable speed demand is set
755  float STEdot = _SPEdot + _SKEdot;
756  if ((!_flags.underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_flags.badDescent && !_flags.underspeed && (_STE_error > 0.0f)))
757  {
758  _flags.badDescent = true;
759  }
760  else
761  {
762  _flags.badDescent = false;
763  }
764 
765  // when soaring is active we never trigger a bad descent
767  _flags.badDescent = false;
768  }
769 }
770 
772 {
773  // Calculate Speed/Height Control Weighting
774  // This is used to determine how the pitch control prioritises speed and height control
775  // A weighting of 1 provides equal priority (this is the normal mode of operation)
776  // A SKE_weighting of 0 provides 100% priority to height control. This is used when no airspeed measurement is available
777  // A SKE_weighting of 2 provides 100% priority to speed control. This is used when an underspeed condition is detected. In this instance, if airspeed
778  // rises above the demanded value, the pitch angle will be increased by the TECS controller.
779  float SKE_weighting = constrain_float(_spdWeight, 0.0f, 2.0f);
781  SKE_weighting = 0.0f;
783  // if we are in VTOL mode then control pitch without regard to
784  // speed. Speed is also taken care of independently of
785  // height. This is needed as the usual relationship of speed
786  // and height is broken by the VTOL motors
787  SKE_weighting = 0.0f;
789  SKE_weighting = 2.0f;
790  } else if (_flags.is_doing_auto_land) {
791  if (_spdWeightLand < 0) {
792  // use sliding scale from normal weight down to zero at landing
793  float scaled_weight = _spdWeight * (1.0f - constrain_float(_path_proportion,0,1));
794  SKE_weighting = constrain_float(scaled_weight, 0.0f, 2.0f);
795  } else {
796  SKE_weighting = constrain_float(_spdWeightLand, 0.0f, 2.0f);
797  }
798  }
799 
800  logging.SKE_weighting = SKE_weighting;
801 
802  float SPE_weighting = 2.0f - SKE_weighting;
803 
804  // Calculate Specific Energy Balance demand, and error
805  float SEB_dem = _SPE_dem * SPE_weighting - _SKE_dem * SKE_weighting;
806  float SEBdot_dem = _SPEdot_dem * SPE_weighting - _SKEdot_dem * SKE_weighting;
807  float SEB_error = SEB_dem - (_SPE_est * SPE_weighting - _SKE_est * SKE_weighting);
808  float SEBdot_error = SEBdot_dem - (_SPEdot * SPE_weighting - _SKEdot * SKE_weighting);
809 
810  logging.SKE_error = _SKE_dem - _SKE_est;
811  logging.SPE_error = _SPE_dem - _SPE_est;
812 
813  // Calculate integrator state, constraining input if pitch limits are exceeded
814  float integSEB_input = SEB_error * _get_i_gain();
815  if (_pitch_dem > _PITCHmaxf)
816  {
817  integSEB_input = MIN(integSEB_input, _PITCHmaxf - _pitch_dem);
818  }
819  else if (_pitch_dem < _PITCHminf)
820  {
821  integSEB_input = MAX(integSEB_input, _PITCHminf - _pitch_dem);
822  }
823  float integSEB_delta = integSEB_input * _DT;
824 
825 #if 0
826  if (_landing.is_flaring() && fabsf(_climb_rate) > 0.2f) {
827  ::printf("_hgt_rate_dem=%.1f _hgt_dem_adj=%.1f climb=%.1f _flare_counter=%u _pitch_dem=%.1f SEB_dem=%.2f SEBdot_dem=%.2f SEB_error=%.2f SEBdot_error=%.2f\n",
829  SEB_dem, SEBdot_dem, SEB_error, SEBdot_error);
830  }
831 #endif
832 
833 
834  // Apply max and min values for integrator state that will allow for no more than
835  // 5deg of saturation. This allows for some pitch variation due to gusts before the
836  // integrator is clipped. Otherwise the effectiveness of the integrator will be reduced in turbulence
837  // During climbout/takeoff, bias the demanded pitch angle so that zero speed error produces a pitch angle
838  // demand equal to the minimum value (which is )set by the mission plan during this mode). Otherwise the
839  // integrator has to catch up before the nose can be raised to reduce speed during climbout.
840  // During flare a different damping gain is used
841  float gainInv = (_TAS_state * timeConstant() * GRAVITY_MSS);
842  float temp = SEB_error + SEBdot_dem * timeConstant();
843 
844  float pitch_damp = _ptchDamp;
845  if (_landing.is_flaring()) {
846  pitch_damp = _landDamp;
848  pitch_damp = _land_pitch_damp;
849  }
850  temp += SEBdot_error * pitch_damp;
851 
853  temp += _PITCHminf * gainInv;
854  }
855  float integSEB_min = (gainInv * (_PITCHminf - 0.0783f)) - temp;
856  float integSEB_max = (gainInv * (_PITCHmaxf + 0.0783f)) - temp;
857  float integSEB_range = integSEB_max - integSEB_min;
858 
859  logging.SEB_delta = integSEB_delta;
860 
861  // don't allow the integrator to rise by more than 20% of its full
862  // range in one step. This prevents single value glitches from
863  // causing massive integrator changes. See Issue#4066
864  integSEB_delta = constrain_float(integSEB_delta, -integSEB_range*0.1f, integSEB_range*0.1f);
865 
866  // integrate
867  _integSEB_state = constrain_float(_integSEB_state + integSEB_delta, integSEB_min, integSEB_max);
868 
869  // Calculate pitch demand from specific energy balance signals
870  _pitch_dem_unc = (temp + _integSEB_state) / gainInv;
871 
872  // Constrain pitch demand
874 
875  // Rate limit the pitch demand to comply with specified vertical
876  // acceleration limit
877  float ptchRateIncr = _DT * _vertAccLim / _TAS_state;
878 
879  if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr)
880  {
881  _pitch_dem = _last_pitch_dem + ptchRateIncr;
882  }
883  else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr)
884  {
885  _pitch_dem = _last_pitch_dem - ptchRateIncr;
886  }
887 
888  // re-constrain pitch demand
890 
892 }
893 
894 void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe)
895 {
896  // Initialise states and variables if DT > 1 second or in climbout
897  if (_DT > 1.0f)
898  {
899  _integTHR_state = 0.0f;
900  _integSEB_state = 0.0f;
903  _hgt_dem_adj_last = hgt_afe;
909  _flags.underspeed = false;
910  _flags.badDescent = false;
912  _DT = 0.1f; // when first starting TECS, use a
913  // small time constant
914  }
916  {
917  _PITCHminf = 0.000174533f * ptchMinCO_cd;
918  _hgt_dem_adj_last = hgt_afe;
923  _flags.underspeed = false;
924  _flags.badDescent = false;
925  }
926 
928  // reset takeoff speed flag when not in takeoff
929  _flags.reached_speed_takeoff = false;
930  }
931 }
932 
934 {
935  // Calculate Specific Total Energy Rate Limits
936  // This is a trivial calculation at the moment but will get bigger once we start adding altitude effects
939 }
940 
941 
942 void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
943  int32_t EAS_dem_cm,
944  enum AP_Vehicle::FixedWing::FlightStage flight_stage,
945  float distance_beyond_land_wp,
946  int32_t ptchMinCO_cd,
947  int16_t throttle_nudge,
948  float hgt_afe,
949  float load_factor)
950 {
951  // Calculate time in seconds since last update
952  uint64_t now = AP_HAL::micros64();
953  _DT = (now - _update_pitch_throttle_last_usec) * 1.0e-6f;
955 
957  _distance_beyond_land_wp = distance_beyond_land_wp;
958  _flight_stage = flight_stage;
959 
960  // Convert inputs
961  _hgt_dem = hgt_dem_cm * 0.01f;
962  _EAS_dem = EAS_dem_cm * 0.01f;
963 
964  // Update the speed estimate using a 2nd order complementary filter
965  _update_speed(load_factor);
966 
967  if (aparm.takeoff_throttle_max != 0 &&
970  } else {
971  _THRmaxf = aparm.throttle_max * 0.01f;
972  }
973  _THRminf = aparm.throttle_min * 0.01f;
974 
975  // work out the maximum and minimum pitch
976  // if TECS_PITCH_{MAX,MIN} isn't set then use
977  // LIM_PITCH_{MAX,MIN}. Don't allow TECS_PITCH_{MAX,MIN} to be
978  // larger than LIM_PITCH_{MAX,MIN}
979  if (_pitch_max <= 0) {
981  } else {
983  }
984 
985  if (_pitch_min >= 0) {
987  } else {
989  }
990 
991  // apply temporary pitch limit and clear
992  if (_pitch_max_limit < 90) {
995  _pitch_max_limit = 90;
996  }
997 
998  if (_landing.is_flaring()) {
999  // in flare use min pitch from LAND_PITCH_CD
1001 
1002  // and use max pitch from TECS_LAND_PMAX
1003  if (_land_pitch_max != 0) {
1005  }
1006 
1007  // and allow zero throttle
1008  _THRminf = 0;
1009  } else if (_landing.is_on_approach() && (-_climb_rate) > _land_sink) {
1010  // constrain the pitch in landing as we get close to the flare
1011  // point. Use a simple linear limit from 15 meters after the
1012  // landing point
1013  float time_to_flare = (- hgt_afe / _climb_rate) - _landing.get_flare_sec();
1014  if (time_to_flare < 0) {
1015  // we should be flaring already
1017  } else if (time_to_flare < timeConstant()*2) {
1018  // smoothly move the min pitch to the flare min pitch over
1019  // twice the time constant
1020  float p = time_to_flare/(2*timeConstant());
1021  float pitch_limit_cd = p*aparm.pitch_limit_min_cd + (1-p)*_landing.get_pitch_cd();
1022 #if 0
1023  ::printf("ttf=%.1f hgt_afe=%.1f _PITCHminf=%.1f pitch_limit=%.1f climb=%.1f\n",
1024  time_to_flare, hgt_afe, _PITCHminf, pitch_limit_cd*0.01f, _climb_rate);
1025 #endif
1026  _PITCHminf = MAX(_PITCHminf, pitch_limit_cd*0.01f);
1027  }
1028  }
1029 
1032  // we have reached our target speed in takeoff, allow for
1033  // normal throttle control
1035  }
1036  }
1037 
1038  // convert to radians
1041 
1042  // initialise selected states and variables if DT > 1 second or in climbout
1043  _initialise_states(ptchMinCO_cd, hgt_afe);
1044 
1045  // Calculate Specific Total Energy Rate Limits
1047 
1048  // Calculate the speed demand
1050 
1051  // Calculate the height demand
1053 
1054  // Detect underspeed condition
1056 
1057  // Calculate specific energy quantitiues
1058  _update_energies();
1059 
1060  // Calculate throttle demand - use simple pitch to throttle if no
1061  // airspeed sensor.
1062  // Note that caller can demand the use of
1063  // synthetic airspeed for one loop if needed. This is required
1064  // during QuadPlane transition when pitch is constrained
1068  } else {
1069  _update_throttle_without_airspeed(throttle_nudge);
1070  }
1071 
1072  // Detect bad descent due to demanded airspeed being too high
1074 
1075  // Calculate pitch demand
1076  _update_pitch();
1077 
1078  // log to DataFlash
1080  "TECS",
1081  "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f",
1082  "smnmnnnn----o--",
1083  "F0000000----0--",
1084  "QfffffffffffffB",
1085  now,
1086  (double)_height,
1087  (double)_climb_rate,
1088  (double)_hgt_dem_adj,
1089  (double)_hgt_rate_dem,
1090  (double)_TAS_dem_adj,
1091  (double)_TAS_state,
1092  (double)_vel_dot,
1093  (double)_integTHR_state,
1094  (double)_integSEB_state,
1095  (double)_throttle_dem,
1096  (double)_pitch_dem,
1097  (double)_TAS_rate_dem,
1098  (double)logging.SKE_weighting,
1099  _flags_byte);
1100  DataFlash_Class::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
1101  now,
1102  (double)logging.SKE_error,
1103  (double)logging.SPE_error,
1104  (double)logging.SEB_delta,
1105  (double)load_factor);
1106 }
uint32_t _underspeed_start_ms
Definition: AP_TECS.h:275
float _STEdot_min
Definition: AP_TECS.h:285
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_Float _minSinkRate
Definition: AP_TECS.h:150
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
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
int16_t get_pitch_cd(void) const
Definition: AP_Landing.h:92
float timeConstant(void) const
Definition: AP_TECS.cpp:569
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
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
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
Combined Total Energy Speed & Height Control. This is a instance of an AP_SpdHgtControl class...
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
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float pitch
Definition: AP_AHRS.h:225
float _integDTAS_state
Definition: AP_TECS.h:202
void _update_STE_rate_lim(void)
Definition: AP_TECS.cpp:933
virtual T apply(T sample)
Definition: AverageFilter.h:79
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
AP_Float _ptchDamp
Definition: AP_TECS.h:154
uint64_t _update_50hz_last_usec
Definition: AP_TECS.h:127
float _integSEB_state
Definition: AP_TECS.h:211
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
virtual const Matrix3f & get_rotation_body_to_ned(void) const =0
void _update_speed(float load_factor)
Definition: AP_TECS.cpp:334
float _height
Definition: AP_TECS.h:179
#define MIN(a, b)
Definition: usb_conf.h:215
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
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void _update_height_demand(void)
Definition: AP_TECS.cpp:436
AP_Int16 pitch_limit_min_cd
Definition: AP_Vehicle.h:43
uint64_t _update_speed_last_usec
Definition: AP_TECS.h:130
const Vector3f & get_accel(uint8_t i) const
AP_Int8 takeoff_throttle_max
Definition: AP_Vehicle.h:35
float _EAS_dem
Definition: AP_TECS.h:234
AP_Float _integGain_land
Definition: AP_TECS.h:161
float _SPEdot
Definition: AP_TECS.h:302
bool _use_synthetic_airspeed_once
Definition: AP_TECS.h:333
bool is_doing_auto_land
Definition: AP_TECS.h:264
AP_Float _vertAccLim
Definition: AP_TECS.h:162
AP_Float _thrDamp
Definition: AP_TECS.h:157
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
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
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
AP_Float _integGain
Definition: AP_TECS.h:159
float _EAS
Definition: AP_TECS.h:223
virtual const Vector3f & get_accel_ef(uint8_t i) const
Definition: AP_AHRS.h:193
uint8_t _flags_byte
Definition: AP_TECS.h:271
AP_Int8 throttle_slewrate
Definition: AP_Vehicle.h:33
T y
Definition: vector3.h:67
float _vel_dot
Definition: AP_TECS.h:220
bool get_throttle_suppressed() const
Definition: AP_Soaring.h:85
Vector3< T > c
Definition: matrix3.h:48
uint32_t millis()
Definition: system.cpp:157
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
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
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
AP_Int8 _use_synthetic_airspeed
Definition: AP_TECS.h:330
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
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 get_altitude(void) const
Definition: AP_Baro.h:84
float _STE_error
Definition: AP_TECS.h:306
uint8_t _flare_counter
Definition: AP_TECS.h:312
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void _update_pitch(void)
Definition: AP_TECS.cpp:771
bool is_flaring(void) const
Definition: AP_Landing.cpp:281
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
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
float get_flare_sec(void) const
Definition: AP_Landing.h:93
AP_Int8 stall_prevention
Definition: AP_Vehicle.h:45
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
AP_InertialSensor & ins()
bool is_active() const
Definition: AP_Soaring.cpp:324
Vector3< T > b
Definition: matrix3.h:48
const AP_Vehicle::FixedWing & aparm
Definition: AP_TECS.h:138
bool airspeed_sensor_enabled(void) const
Definition: AP_AHRS.h:299
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
#define degrees(x)
Definition: moduletest.c:23
AP_Baro & baro()
Definition: AP_Baro.cpp:737
float _SKE_est
Definition: AP_TECS.h:301
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
Vector3< T > a
Definition: matrix3.h:48
const SoaringController & _soaring_controller
Definition: AP_TECS.h:144
float _TAS_dem_last
Definition: AP_TECS.h:231
virtual void get_relative_position_D_home(float &posD) const =0
AP_Int16 pitch_limit_max_cd
Definition: AP_Vehicle.h:42
#define AP_GROUPEND
Definition: AP_Param.h:121
bool is_on_approach(void) const
Definition: AP_Landing.cpp:301
void _detect_bad_descent(void)
Definition: AP_TECS.cpp:741
void _update_speed_demand(void)
Definition: AP_TECS.cpp:394
T x
Definition: vector3.h:67
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
float _PITCHminf
Definition: AP_TECS.h:293