AP_TECS.cpp 50 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159
  1. #include "AP_TECS.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Baro/AP_Baro.h>
  4. #include <AP_Logger/AP_Logger.h>
  5. extern const AP_HAL::HAL& hal;
  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. // table of user settable parameters
  14. const AP_Param::GroupInfo AP_TECS::var_info[] = {
  15. // @Param: CLMB_MAX
  16. // @DisplayName: Maximum Climb Rate (metres/sec)
  17. // @Description: Maximum demanded climb rate. Do not set higher than the climb speed at THR_MAX at TRIM_ARSPD_CM when the battery is at low voltage. Reduce value if airspeed cannot be maintained on ascent. Increase value if throttle does not increase significantly to ascend.
  18. // @Increment: 0.1
  19. // @Range: 0.1 20.0
  20. // @User: Standard
  21. AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f),
  22. // @Param: SINK_MIN
  23. // @DisplayName: Minimum Sink Rate (metres/sec)
  24. // @Description: Minimum sink rate when at THR_MIN and TRIM_ARSPD_CM.
  25. // @Increment: 0.1
  26. // @Range: 0.1 10.0
  27. // @User: Standard
  28. AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f),
  29. // @Param: TIME_CONST
  30. // @DisplayName: Controller time constant (sec)
  31. // @Description: Time constant of the TECS control algorithm. Small values make faster altitude corrections but can cause overshoot and aggressive behavior.
  32. // @Range: 3.0 10.0
  33. // @Increment: 0.2
  34. // @User: Advanced
  35. AP_GROUPINFO("TIME_CONST", 2, AP_TECS, _timeConst, 5.0f),
  36. // @Param: THR_DAMP
  37. // @DisplayName: Controller throttle damping
  38. // @Description: Damping gain for throttle demand loop. Slows the throttle response to correct for speed and height oscillations.
  39. // @Range: 0.1 1.0
  40. // @Increment: 0.1
  41. // @User: Advanced
  42. AP_GROUPINFO("THR_DAMP", 3, AP_TECS, _thrDamp, 0.5f),
  43. // @Param: INTEG_GAIN
  44. // @DisplayName: Controller integrator
  45. // @Description: Integrator gain to trim out long-term speed and height errors.
  46. // @Range: 0.0 0.5
  47. // @Increment: 0.02
  48. // @User: Advanced
  49. AP_GROUPINFO("INTEG_GAIN", 4, AP_TECS, _integGain, 0.1f),
  50. // @Param: VERT_ACC
  51. // @DisplayName: Vertical Acceleration Limit (metres/sec^2)
  52. // @Description: Maximum vertical acceleration used to correct speed or height errors.
  53. // @Range: 1.0 10.0
  54. // @Increment: 0.5
  55. // @User: Advanced
  56. AP_GROUPINFO("VERT_ACC", 5, AP_TECS, _vertAccLim, 7.0f),
  57. // @Param: HGT_OMEGA
  58. // @DisplayName: Height complementary filter frequency (radians/sec)
  59. // @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.
  60. // @Range: 1.0 5.0
  61. // @Increment: 0.05
  62. // @User: Advanced
  63. AP_GROUPINFO("HGT_OMEGA", 6, AP_TECS, _hgtCompFiltOmega, 3.0f),
  64. // @Param: SPD_OMEGA
  65. // @DisplayName: Speed complementary filter frequency (radians/sec)
  66. // @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.
  67. // @Range: 0.5 2.0
  68. // @Increment: 0.05
  69. // @User: Advanced
  70. AP_GROUPINFO("SPD_OMEGA", 7, AP_TECS, _spdCompFiltOmega, 2.0f),
  71. // @Param: RLL2THR
  72. // @DisplayName: Bank angle compensation gain
  73. // @Description: Gain from bank angle to throttle to compensate for loss of airspeed from drag in turns. Set to approximately 10x the sink rate in m/s caused by a 45-degree turn. High efficiency models may need less while less efficient aircraft may need more. Should be tuned in an automatic mission with waypoints and turns greater than 90 degrees. Tune with PTCH2SV_RLL and KFF_RDDRMIX to achieve constant airspeed, constant altitude turns.
  74. // @Range: 5.0 30.0
  75. // @Increment: 1.0
  76. // @User: Advanced
  77. AP_GROUPINFO("RLL2THR", 8, AP_TECS, _rollComp, 10.0f),
  78. // @Param: SPDWEIGHT
  79. // @DisplayName: Weighting applied to speed control
  80. // @Description: Mixing of pitch and throttle correction for height and airspeed errors. Pitch controls altitude and throttle controls airspeed if set to 0. Pitch controls airspeed and throttle controls altitude if set to 2 (good for gliders). Blended if set to 1.
  81. // @Range: 0.0 2.0
  82. // @Increment: 0.1
  83. // @User: Advanced
  84. AP_GROUPINFO("SPDWEIGHT", 9, AP_TECS, _spdWeight, 1.0f),
  85. // @Param: PTCH_DAMP
  86. // @DisplayName: Controller pitch damping
  87. // @Description: Damping gain for pitch control from TECS control. Increasing may correct for oscillations in speed and height, but too much may cause additional oscillation and degraded control.
  88. // @Range: 0.1 1.0
  89. // @Increment: 0.1
  90. // @User: Advanced
  91. AP_GROUPINFO("PTCH_DAMP", 10, AP_TECS, _ptchDamp, 0.0f),
  92. // @Param: SINK_MAX
  93. // @DisplayName: Maximum Descent Rate (metres/sec)
  94. // @Description: Maximum demanded descent rate. Do not set higher than the vertical speed the aircraft can maintain at THR_MIN, TECS_PITCH_MIN, and ARSPD_FBW_MAX.
  95. // @Increment: 0.1
  96. // @Range: 0.0 20.0
  97. // @User: User
  98. AP_GROUPINFO("SINK_MAX", 11, AP_TECS, _maxSinkRate, 5.0f),
  99. // @Param: LAND_ARSPD
  100. // @DisplayName: Airspeed during landing approach (m/s)
  101. // @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.
  102. // @Range: -1 127
  103. // @Increment: 1
  104. // @User: User
  105. AP_GROUPINFO("LAND_ARSPD", 12, AP_TECS, _landAirspeed, -1),
  106. // @Param: LAND_THR
  107. // @DisplayName: Cruise throttle during landing approach (percentage)
  108. // @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.
  109. // @Range: -1 100
  110. // @Increment: 0.1
  111. // @User: User
  112. AP_GROUPINFO("LAND_THR", 13, AP_TECS, _landThrottle, -1),
  113. // @Param: LAND_SPDWGT
  114. // @DisplayName: Weighting applied to speed control during landing.
  115. // @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.
  116. // @Range: -1.0 2.0
  117. // @Increment: 0.1
  118. // @User: Advanced
  119. AP_GROUPINFO("LAND_SPDWGT", 14, AP_TECS, _spdWeightLand, -1.0f),
  120. // @Param: PITCH_MAX
  121. // @DisplayName: Maximum pitch in auto flight
  122. // @Description: Overrides LIM_PITCH_MAX in automatic throttle modes to reduce climb rates. Uses LIM_PITCH_MAX if set to 0. For proper TECS tuning, set to the angle that the aircraft can climb at TRIM_ARSPD_CM and THR_MAX.
  123. // @Range: 0 45
  124. // @Increment: 1
  125. // @User: Advanced
  126. AP_GROUPINFO("PITCH_MAX", 15, AP_TECS, _pitch_max, 15),
  127. // @Param: PITCH_MIN
  128. // @DisplayName: Minimum pitch in auto flight
  129. // @Description: Overrides LIM_PITCH_MIN in automatic throttle modes to reduce descent rates. Uses LIM_PITCH_MIN if set to 0. For proper TECS tuning, set to the angle that the aircraft can descend at without overspeeding.
  130. // @Range: -45 0
  131. // @Increment: 1
  132. // @User: Advanced
  133. AP_GROUPINFO("PITCH_MIN", 16, AP_TECS, _pitch_min, 0),
  134. // @Param: LAND_SINK
  135. // @DisplayName: Sink rate for final landing stage
  136. // @Description: The sink rate in meters/second for the final stage of landing.
  137. // @Range: 0.0 2.0
  138. // @Increment: 0.1
  139. // @User: Advanced
  140. AP_GROUPINFO("LAND_SINK", 17, AP_TECS, _land_sink, 0.25f),
  141. // @Param: LAND_TCONST
  142. // @DisplayName: Land controller time constant (sec)
  143. // @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
  144. // @Range: 1.0 5.0
  145. // @Increment: 0.2
  146. // @User: Advanced
  147. AP_GROUPINFO("LAND_TCONST", 18, AP_TECS, _landTimeConst, 2.0f),
  148. // @Param: LAND_DAMP
  149. // @DisplayName: Controller sink rate to pitch gain during flare
  150. // @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.
  151. // @Range: 0.1 1.0
  152. // @Increment: 0.1
  153. // @User: Advanced
  154. AP_GROUPINFO("LAND_DAMP", 19, AP_TECS, _landDamp, 0.5f),
  155. // @Param: LAND_PMAX
  156. // @DisplayName: Maximum pitch during final stage of landing
  157. // @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.
  158. // @Range: -5 40
  159. // @Increment: 1
  160. // @User: Advanced
  161. AP_GROUPINFO("LAND_PMAX", 20, AP_TECS, _land_pitch_max, 10),
  162. // @Param: APPR_SMAX
  163. // @DisplayName: Sink rate max for landing approach stage
  164. // @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.
  165. // @Range: 0.0 20.0
  166. // @Units: m/s
  167. // @Increment: 0.1
  168. // @User: Advanced
  169. AP_GROUPINFO("APPR_SMAX", 21, AP_TECS, _maxSinkRate_approach, 0),
  170. // @Param: LAND_SRC
  171. // @DisplayName: Land sink rate change
  172. // @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.
  173. // @Range: -2.0 2.0
  174. // @Units: m/s/m
  175. // @Increment: 0.1
  176. // @User: Advanced
  177. AP_GROUPINFO("LAND_SRC", 22, AP_TECS, _land_sink_rate_change, 0),
  178. // @Param: LAND_TDAMP
  179. // @DisplayName: Controller throttle damping when landing
  180. // @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.
  181. // @Range: 0.1 1.0
  182. // @Increment: 0.1
  183. // @User: Advanced
  184. AP_GROUPINFO("LAND_TDAMP", 23, AP_TECS, _land_throttle_damp, 0),
  185. // @Param: LAND_IGAIN
  186. // @DisplayName: Controller integrator during landing
  187. // @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
  188. // @Range: 0.0 0.5
  189. // @Increment: 0.02
  190. // @User: Advanced
  191. AP_GROUPINFO("LAND_IGAIN", 24, AP_TECS, _integGain_land, 0),
  192. // @Param: TKOFF_IGAIN
  193. // @DisplayName: Controller integrator during takeoff
  194. // @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
  195. // @Range: 0.0 0.5
  196. // @Increment: 0.02
  197. // @User: Advanced
  198. AP_GROUPINFO("TKOFF_IGAIN", 25, AP_TECS, _integGain_takeoff, 0),
  199. // @Param: LAND_PDAMP
  200. // @DisplayName: Pitch damping gain when landing
  201. // @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.
  202. // @Range: 0.1 1.0
  203. // @Increment: 0.1
  204. // @User: Advanced
  205. AP_GROUPINFO("LAND_PDAMP", 26, AP_TECS, _land_pitch_damp, 0),
  206. // @Param: SYNAIRSPEED
  207. // @DisplayName: Enable the use of synthetic airspeed
  208. // @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.
  209. // @Values: 0:Disable,1:Enable
  210. // @User: Advanced
  211. AP_GROUPINFO("SYNAIRSPEED", 27, AP_TECS, _use_synthetic_airspeed, 0),
  212. // @Param: OPTIONS
  213. // @DisplayName: Extra TECS options
  214. // @Description: This allows the enabling of special features in the speed/height controller
  215. // @Bitmask: 0:GliderOnly
  216. // @User: Advanced
  217. AP_GROUPINFO("OPTIONS", 28, AP_TECS, _options, 0),
  218. AP_GROUPEND
  219. };
  220. /*
  221. * Written by Paul Riseborough 2013 to provide:
  222. * - Combined control of speed and height using throttle to control
  223. * total energy and pitch angle to control exchange of energy between
  224. * potential and kinetic.
  225. * Selectable speed or height priority modes when calculating pitch angle
  226. * - Fallback mode when no airspeed measurement is available that
  227. * sets throttle based on height rate demand and switches pitch angle control to
  228. * height priority
  229. * - Underspeed protection that demands maximum throttle and switches pitch angle control
  230. * to speed priority mode
  231. * - Relative ease of tuning through use of intuitive time constant, integrator and damping gains and the use
  232. * of easy to measure aircraft performance data
  233. *
  234. */
  235. void AP_TECS::update_50hz(void)
  236. {
  237. // Implement third order complementary filter for height and height rate
  238. // estimated height rate = _climb_rate
  239. // estimated height above field elevation = _height
  240. // Reference Paper :
  241. // Optimizing the Gains of the Baro-Inertial Vertical Channel
  242. // Widnall W.S, Sinha P.K,
  243. // AIAA Journal of Guidance and Control, 78-1307R
  244. /*
  245. if we have a vertical position estimate from the EKF then use
  246. it, otherwise use barometric altitude
  247. */
  248. _ahrs.get_relative_position_D_home(_height);
  249. _height *= -1.0f;
  250. // Calculate time in seconds since last update
  251. uint64_t now = AP_HAL::micros64();
  252. float DT = (now - _update_50hz_last_usec) * 1.0e-6f;
  253. if (DT > 1.0f) {
  254. _climb_rate = 0.0f;
  255. _height_filter.dd_height = 0.0f;
  256. DT = 0.02f; // when first starting TECS, use a
  257. // small time constant
  258. }
  259. _update_50hz_last_usec = now;
  260. // Use inertial nav verical velocity and height if available
  261. Vector3f velned;
  262. if (_ahrs.get_velocity_NED(velned)) {
  263. // if possible use the EKF vertical velocity
  264. _climb_rate = -velned.z;
  265. } else {
  266. /*
  267. use a complimentary filter to calculate climb_rate. This is
  268. designed to minimise lag
  269. */
  270. const float baro_alt = AP::baro().get_altitude();
  271. // Get height acceleration
  272. float hgt_ddot_mea = -(_ahrs.get_accel_ef().z + GRAVITY_MSS);
  273. // Perform filter calculation using backwards Euler integration
  274. // Coefficients selected to place all three filter poles at omega
  275. float omega2 = _hgtCompFiltOmega*_hgtCompFiltOmega;
  276. float hgt_err = baro_alt - _height_filter.height;
  277. float integ1_input = hgt_err * omega2 * _hgtCompFiltOmega;
  278. _height_filter.dd_height += integ1_input * DT;
  279. float integ2_input = _height_filter.dd_height + hgt_ddot_mea + hgt_err * omega2 * 3.0f;
  280. _climb_rate += integ2_input * DT;
  281. float integ3_input = _climb_rate + hgt_err * _hgtCompFiltOmega * 3.0f;
  282. // If more than 1 second has elapsed since last update then reset the integrator state
  283. // to the measured height
  284. if (DT > 1.0f) {
  285. _height_filter.height = _height;
  286. } else {
  287. _height_filter.height += integ3_input*DT;
  288. }
  289. }
  290. // Update and average speed rate of change
  291. // Get DCM
  292. const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
  293. // Calculate speed rate of change
  294. float temp = rotMat.c.x * GRAVITY_MSS + AP::ins().get_accel().x;
  295. // take 5 point moving average
  296. _vel_dot = _vdot_filter.apply(temp);
  297. }
  298. void AP_TECS::_update_speed(float load_factor)
  299. {
  300. // Calculate time in seconds since last update
  301. uint64_t now = AP_HAL::micros64();
  302. float DT = (now - _update_speed_last_usec) * 1.0e-6f;
  303. _update_speed_last_usec = now;
  304. // Convert equivalent airspeeds to true airspeeds
  305. float EAS2TAS = _ahrs.get_EAS2TAS();
  306. _TAS_dem = _EAS_dem * EAS2TAS;
  307. _TASmax = aparm.airspeed_max * EAS2TAS;
  308. _TASmin = aparm.airspeed_min * EAS2TAS;
  309. if (aparm.stall_prevention) {
  310. // when stall prevention is active we raise the mimimum
  311. // airspeed based on aerodynamic load factor
  312. _TASmin *= load_factor;
  313. }
  314. if (_TASmax < _TASmin) {
  315. _TASmax = _TASmin;
  316. }
  317. if (_TASmin > _TAS_dem) {
  318. _TASmin = _TAS_dem;
  319. }
  320. // Reset states of time since last update is too large
  321. if (DT > 1.0f) {
  322. _TAS_state = (_EAS * EAS2TAS);
  323. _integDTAS_state = 0.0f;
  324. DT = 0.1f; // when first starting TECS, use a
  325. // small time constant
  326. }
  327. // Get airspeed or default to halfway between min and max if
  328. // airspeed is not being used and set speed rate to zero
  329. bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.airspeed_sensor_enabled();
  330. if (!use_airspeed || !_ahrs.airspeed_estimate(&_EAS)) {
  331. // If no airspeed available use average of min and max
  332. _EAS = 0.5f * (aparm.airspeed_min.get() + (float)aparm.airspeed_max.get());
  333. }
  334. // Implement a second order complementary filter to obtain a
  335. // smoothed airspeed estimate
  336. // airspeed estimate is held in _TAS_state
  337. float aspdErr = (_EAS * EAS2TAS) - _TAS_state;
  338. float integDTAS_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega;
  339. // Prevent state from winding up
  340. if (_TAS_state < 3.1f) {
  341. integDTAS_input = MAX(integDTAS_input , 0.0f);
  342. }
  343. _integDTAS_state = _integDTAS_state + integDTAS_input * DT;
  344. float TAS_input = _integDTAS_state + _vel_dot + aspdErr * _spdCompFiltOmega * 1.4142f;
  345. _TAS_state = _TAS_state + TAS_input * DT;
  346. // limit the airspeed to a minimum of 3 m/s
  347. _TAS_state = MAX(_TAS_state, 3.0f);
  348. }
  349. void AP_TECS::_update_speed_demand(void)
  350. {
  351. // Set the airspeed demand to the minimum value if an underspeed condition exists
  352. // or a bad descent condition exists
  353. // This will minimise the rate of descent resulting from an engine failure,
  354. // enable the maximum climb rate to be achieved and prevent continued full power descent
  355. // into the ground due to an unachievable airspeed value
  356. if ((_flags.badDescent) || (_flags.underspeed))
  357. {
  358. _TAS_dem = _TASmin;
  359. }
  360. // Constrain speed demand, taking into account the load factor
  361. _TAS_dem = constrain_float(_TAS_dem, _TASmin, _TASmax);
  362. // calculate velocity rate limits based on physical performance limits
  363. // provision to use a different rate limit if bad descent or underspeed condition exists
  364. // Use 50% of maximum energy rate to allow margin for total energy contgroller
  365. const float velRateMax = 0.5f * _STEdot_max / _TAS_state;
  366. const float velRateMin = 0.5f * _STEdot_min / _TAS_state;
  367. const float TAS_dem_previous = _TAS_dem_adj;
  368. // assume fixed 10Hz call rate
  369. const float dt = 0.1;
  370. // Apply rate limit
  371. if ((_TAS_dem - TAS_dem_previous) > (velRateMax * dt))
  372. {
  373. _TAS_dem_adj = TAS_dem_previous + velRateMax * dt;
  374. _TAS_rate_dem = velRateMax;
  375. }
  376. else if ((_TAS_dem - TAS_dem_previous) < (velRateMin * dt))
  377. {
  378. _TAS_dem_adj = TAS_dem_previous + velRateMin * dt;
  379. _TAS_rate_dem = velRateMin;
  380. }
  381. else
  382. {
  383. _TAS_rate_dem = (_TAS_dem - TAS_dem_previous) / dt;
  384. _TAS_dem_adj = _TAS_dem;
  385. }
  386. // Constrain speed demand again to protect against bad values on initialisation.
  387. _TAS_dem_adj = constrain_float(_TAS_dem_adj, _TASmin, _TASmax);
  388. }
  389. void AP_TECS::_update_height_demand(void)
  390. {
  391. // Apply 2 point moving average to demanded height
  392. _hgt_dem = 0.5f * (_hgt_dem + _hgt_dem_in_old);
  393. _hgt_dem_in_old = _hgt_dem;
  394. float max_sink_rate = _maxSinkRate;
  395. if (_maxSinkRate_approach > 0 && _flags.is_doing_auto_land) {
  396. // special sink rate for approach to accommodate steep slopes and reverse thrust.
  397. // A special check must be done to see if we're LANDing on approach but also if
  398. // we're in that tiny window just starting NAV_LAND but still in NORMAL mode. If
  399. // we have a steep slope with a short approach we'll want to allow acquiring the
  400. // glide slope right away.
  401. max_sink_rate = _maxSinkRate_approach;
  402. }
  403. // Limit height rate of change
  404. if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f))
  405. {
  406. _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
  407. }
  408. else if ((_hgt_dem - _hgt_dem_prev) < (-max_sink_rate * 0.1f))
  409. {
  410. _hgt_dem = _hgt_dem_prev - max_sink_rate * 0.1f;
  411. }
  412. _hgt_dem_prev = _hgt_dem;
  413. // Apply first order lag to height demand
  414. _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
  415. // when flaring force height rate demand to the
  416. // configured sink rate and adjust the demanded height to
  417. // be kinematically consistent with the height rate.
  418. if (_landing.is_flaring()) {
  419. _integSEB_state = 0;
  420. if (_flare_counter == 0) {
  421. _hgt_rate_dem = _climb_rate;
  422. _land_hgt_dem = _hgt_dem_adj;
  423. }
  424. // adjust the flare sink rate to increase/decrease as your travel further beyond the land wp
  425. float land_sink_rate_adj = _land_sink + _land_sink_rate_change*_distance_beyond_land_wp;
  426. // bring it in over 1s to prevent overshoot
  427. if (_flare_counter < 10) {
  428. _hgt_rate_dem = _hgt_rate_dem * 0.8f - 0.2f * land_sink_rate_adj;
  429. _flare_counter++;
  430. } else {
  431. _hgt_rate_dem = - land_sink_rate_adj;
  432. }
  433. _land_hgt_dem += 0.1f * _hgt_rate_dem;
  434. _hgt_dem_adj = _land_hgt_dem;
  435. } else {
  436. _hgt_rate_dem = (_hgt_dem_adj - _hgt_dem_adj_last) / 0.1f;
  437. _flare_counter = 0;
  438. }
  439. // for landing approach we will predict ahead by the time constant
  440. // plus the lag produced by the first order filter. This avoids a
  441. // lagged height demand while constantly descending which causes
  442. // us to consistently be above the desired glide slope. This will
  443. // be replaced with a better zero-lag filter in the future.
  444. float new_hgt_dem = _hgt_dem_adj;
  445. if (_flags.is_doing_auto_land) {
  446. if (hgt_dem_lag_filter_slew < 1) {
  447. hgt_dem_lag_filter_slew += 0.1f; // increment at 10Hz to gradually apply the compensation at first
  448. } else {
  449. hgt_dem_lag_filter_slew = 1;
  450. }
  451. new_hgt_dem += hgt_dem_lag_filter_slew*(_hgt_dem_adj - _hgt_dem_adj_last)*10.0f*(timeConstant()+1);
  452. } else {
  453. hgt_dem_lag_filter_slew = 0;
  454. }
  455. _hgt_dem_adj_last = _hgt_dem_adj;
  456. _hgt_dem_adj = new_hgt_dem;
  457. }
  458. void AP_TECS::_detect_underspeed(void)
  459. {
  460. // see if we can clear a previous underspeed condition. We clear
  461. // it if we are now more than 15% above min speed, and haven't
  462. // been below min speed for at least 3 seconds.
  463. if (_flags.underspeed &&
  464. _TAS_state >= _TASmin * 1.15f &&
  465. AP_HAL::millis() - _underspeed_start_ms > 3000U) {
  466. _flags.underspeed = false;
  467. }
  468. if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
  469. _flags.underspeed = false;
  470. } else if (((_TAS_state < _TASmin * 0.9f) &&
  471. (_throttle_dem >= _THRmaxf * 0.95f) &&
  472. !_landing.is_flaring()) ||
  473. ((_height < _hgt_dem_adj) && _flags.underspeed))
  474. {
  475. _flags.underspeed = true;
  476. if (_TAS_state < _TASmin * 0.9f) {
  477. // reset start time as we are still underspeed
  478. _underspeed_start_ms = AP_HAL::millis();
  479. }
  480. }
  481. else
  482. {
  483. // this clears underspeed if we reach our demanded height and
  484. // we are either below 95% throttle or we above 90% of min
  485. // airspeed
  486. _flags.underspeed = false;
  487. }
  488. }
  489. void AP_TECS::_update_energies(void)
  490. {
  491. // Calculate specific energy demands
  492. _SPE_dem = _hgt_dem_adj * GRAVITY_MSS;
  493. _SKE_dem = 0.5f * _TAS_dem_adj * _TAS_dem_adj;
  494. // Calculate specific energy rate demands
  495. _SPEdot_dem = _hgt_rate_dem * GRAVITY_MSS;
  496. _SKEdot_dem = _TAS_state * _TAS_rate_dem;
  497. // Calculate specific energy
  498. _SPE_est = _height * GRAVITY_MSS;
  499. _SKE_est = 0.5f * _TAS_state * _TAS_state;
  500. // Calculate specific energy rate
  501. _SPEdot = _climb_rate * GRAVITY_MSS;
  502. _SKEdot = _TAS_state * _vel_dot;
  503. }
  504. /*
  505. current time constant. It is lower in landing to try to give a precise approach
  506. */
  507. float AP_TECS::timeConstant(void) const
  508. {
  509. if (_flags.is_doing_auto_land) {
  510. if (_landTimeConst < 0.1f) {
  511. return 0.1f;
  512. }
  513. return _landTimeConst;
  514. }
  515. if (_timeConst < 0.1f) {
  516. return 0.1f;
  517. }
  518. return _timeConst;
  519. }
  520. /*
  521. calculate throttle demand - airspeed enabled case
  522. */
  523. void AP_TECS::_update_throttle_with_airspeed(void)
  524. {
  525. // Calculate limits to be applied to potential energy error to prevent over or underspeed occurring due to large height errors
  526. float SPE_err_max = 0.5f * _TASmax * _TASmax - _SKE_dem;
  527. float SPE_err_min = 0.5f * _TASmin * _TASmin - _SKE_dem;
  528. if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
  529. /*
  530. when we are in a VTOL state then we ignore potential energy
  531. errors as we have vertical motors that interfere with the
  532. total energy calculation.
  533. */
  534. SPE_err_max = SPE_err_min = 0;
  535. }
  536. // Calculate total energy error
  537. _STE_error = constrain_float((_SPE_dem - _SPE_est), SPE_err_min, SPE_err_max) + _SKE_dem - _SKE_est;
  538. float STEdot_dem = constrain_float((_SPEdot_dem + _SKEdot_dem), _STEdot_min, _STEdot_max);
  539. float STEdot_error = STEdot_dem - _SPEdot - _SKEdot;
  540. // Apply 0.5 second first order filter to STEdot_error
  541. // This is required to remove accelerometer noise from the measurement
  542. STEdot_error = 0.2f*STEdot_error + 0.8f*_STEdotErrLast;
  543. _STEdotErrLast = STEdot_error;
  544. // Calculate throttle demand
  545. // If underspeed condition is set, then demand full throttle
  546. if (_flags.underspeed)
  547. {
  548. _throttle_dem = 1.0f;
  549. }
  550. else
  551. {
  552. // Calculate gain scaler from specific energy error to throttle
  553. // (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf) is the derivative of STEdot wrt throttle measured across the max allowed throttle range.
  554. float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf));
  555. // Calculate feed-forward throttle
  556. float ff_throttle = 0;
  557. float nomThr = aparm.throttle_cruise * 0.01f;
  558. const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
  559. // Use the demanded rate of change of total energy as the feed-forward demand, but add
  560. // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
  561. // drag increase during turns.
  562. float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
  563. STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
  564. ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
  565. // Calculate PD + FF throttle
  566. float throttle_damp = _thrDamp;
  567. if (_flags.is_doing_auto_land && !is_zero(_land_throttle_damp)) {
  568. throttle_damp = _land_throttle_damp;
  569. }
  570. _throttle_dem = (_STE_error + STEdot_error * throttle_damp) * K_STE2Thr + ff_throttle;
  571. // Constrain throttle demand
  572. _throttle_dem = constrain_float(_throttle_dem, _THRminf, _THRmaxf);
  573. float THRminf_clipped_to_zero = constrain_float(_THRminf, 0, _THRmaxf);
  574. // Rate limit PD + FF throttle
  575. // Calculate the throttle increment from the specified slew time
  576. if (aparm.throttle_slewrate != 0) {
  577. float thrRateIncr = _DT * (_THRmaxf - THRminf_clipped_to_zero) * aparm.throttle_slewrate * 0.01f;
  578. _throttle_dem = constrain_float(_throttle_dem,
  579. _last_throttle_dem - thrRateIncr,
  580. _last_throttle_dem + thrRateIncr);
  581. _last_throttle_dem = _throttle_dem;
  582. }
  583. // Calculate integrator state upper and lower limits
  584. // Set to a value that will allow 0.1 (10%) throttle saturation to allow for noise on the demand
  585. // Additionally constrain the integrator state amplitude so that the integrator comes off limits faster.
  586. float maxAmp = 0.5f*(_THRmaxf - THRminf_clipped_to_zero);
  587. float integ_max = constrain_float((_THRmaxf - _throttle_dem + 0.1f),-maxAmp,maxAmp);
  588. float integ_min = constrain_float((_THRminf - _throttle_dem - 0.1f),-maxAmp,maxAmp);
  589. // Calculate integrator state, constraining state
  590. // Set integrator to a max throttle value during climbout
  591. _integTHR_state = _integTHR_state + (_STE_error * _get_i_gain()) * _DT * K_STE2Thr;
  592. if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)
  593. {
  594. if (!_flags.reached_speed_takeoff) {
  595. // ensure we run at full throttle until we reach the target airspeed
  596. _throttle_dem = MAX(_throttle_dem, _THRmaxf - _integTHR_state);
  597. }
  598. _integTHR_state = integ_max;
  599. }
  600. else
  601. {
  602. _integTHR_state = constrain_float(_integTHR_state, integ_min, integ_max);
  603. }
  604. // Sum the components.
  605. _throttle_dem = _throttle_dem + _integTHR_state;
  606. }
  607. // Constrain throttle demand
  608. _throttle_dem = constrain_float(_throttle_dem, _THRminf, _THRmaxf);
  609. }
  610. float AP_TECS::_get_i_gain(void)
  611. {
  612. float i_gain = _integGain;
  613. if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
  614. if (!is_zero(_integGain_takeoff)) {
  615. i_gain = _integGain_takeoff;
  616. }
  617. } else if (_flags.is_doing_auto_land) {
  618. if (!is_zero(_integGain_land)) {
  619. i_gain = _integGain_land;
  620. }
  621. }
  622. return i_gain;
  623. }
  624. /*
  625. calculate throttle, non-airspeed case
  626. */
  627. void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
  628. {
  629. // Calculate throttle demand by interpolating between pitch and throttle limits
  630. float nomThr;
  631. //If landing and we don't have an airspeed sensor and we have a non-zero
  632. //TECS_LAND_THR param then use it
  633. if (_flags.is_doing_auto_land && _landThrottle >= 0) {
  634. nomThr = (_landThrottle + throttle_nudge) * 0.01f;
  635. } else { //not landing or not using TECS_LAND_THR parameter
  636. nomThr = (aparm.throttle_cruise + throttle_nudge)* 0.01f;
  637. }
  638. if (_pitch_dem > 0.0f && _PITCHmaxf > 0.0f)
  639. {
  640. _throttle_dem = nomThr + (_THRmaxf - nomThr) * _pitch_dem / _PITCHmaxf;
  641. }
  642. else if (_pitch_dem < 0.0f && _PITCHminf < 0.0f)
  643. {
  644. _throttle_dem = nomThr + (_THRminf - nomThr) * _pitch_dem / _PITCHminf;
  645. }
  646. else
  647. {
  648. _throttle_dem = nomThr;
  649. }
  650. // Calculate additional throttle for turn drag compensation including throttle nudging
  651. const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
  652. // Use the demanded rate of change of total energy as the feed-forward demand, but add
  653. // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
  654. // drag increase during turns.
  655. float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
  656. float STEdot_dem = _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
  657. _throttle_dem = _throttle_dem + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
  658. }
  659. void AP_TECS::_detect_bad_descent(void)
  660. {
  661. // Detect a demanded airspeed too high for the aircraft to achieve. This will be
  662. // evident by the the following conditions:
  663. // 1) Underspeed protection not active
  664. // 2) Specific total energy error > 200 (greater than ~20m height error)
  665. // 3) Specific total energy reducing
  666. // 4) throttle demand > 90%
  667. // If these four conditions exist simultaneously, then the protection
  668. // mode will be activated.
  669. // Once active, the following condition are required to stay in the mode
  670. // 1) Underspeed protection not active
  671. // 2) Specific total energy error > 0
  672. // 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
  673. float STEdot = _SPEdot + _SKEdot;
  674. if ((!_flags.underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_flags.badDescent && !_flags.underspeed && (_STE_error > 0.0f)))
  675. {
  676. _flags.badDescent = true;
  677. }
  678. else
  679. {
  680. _flags.badDescent = false;
  681. }
  682. }
  683. void AP_TECS::_update_pitch(void)
  684. {
  685. // Calculate Speed/Height Control Weighting
  686. // This is used to determine how the pitch control prioritises speed and height control
  687. // A weighting of 1 provides equal priority (this is the normal mode of operation)
  688. // A SKE_weighting of 0 provides 100% priority to height control. This is used when no airspeed measurement is available
  689. // 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
  690. // rises above the demanded value, the pitch angle will be increased by the TECS controller.
  691. float SKE_weighting = constrain_float(_spdWeight, 0.0f, 2.0f);
  692. if (!_ahrs.airspeed_sensor_enabled()) {
  693. SKE_weighting = 0.0f;
  694. } else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
  695. // if we are in VTOL mode then control pitch without regard to
  696. // speed. Speed is also taken care of independently of
  697. // height. This is needed as the usual relationship of speed
  698. // and height is broken by the VTOL motors
  699. SKE_weighting = 0.0f;
  700. } else if ( _flags.underspeed || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
  701. SKE_weighting = 2.0f;
  702. } else if (_flags.is_doing_auto_land) {
  703. if (_spdWeightLand < 0) {
  704. // use sliding scale from normal weight down to zero at landing
  705. float scaled_weight = _spdWeight * (1.0f - constrain_float(_path_proportion,0,1));
  706. SKE_weighting = constrain_float(scaled_weight, 0.0f, 2.0f);
  707. } else {
  708. SKE_weighting = constrain_float(_spdWeightLand, 0.0f, 2.0f);
  709. }
  710. }
  711. logging.SKE_weighting = SKE_weighting;
  712. float SPE_weighting = 2.0f - SKE_weighting;
  713. // Calculate Specific Energy Balance demand, and error
  714. float SEB_dem = _SPE_dem * SPE_weighting - _SKE_dem * SKE_weighting;
  715. float SEBdot_dem = _SPEdot_dem * SPE_weighting - _SKEdot_dem * SKE_weighting;
  716. float SEB_error = SEB_dem - (_SPE_est * SPE_weighting - _SKE_est * SKE_weighting);
  717. float SEBdot_error = SEBdot_dem - (_SPEdot * SPE_weighting - _SKEdot * SKE_weighting);
  718. logging.SKE_error = _SKE_dem - _SKE_est;
  719. logging.SPE_error = _SPE_dem - _SPE_est;
  720. // Calculate integrator state, constraining input if pitch limits are exceeded
  721. float integSEB_input = SEB_error * _get_i_gain();
  722. if (_pitch_dem > _PITCHmaxf)
  723. {
  724. integSEB_input = MIN(integSEB_input, _PITCHmaxf - _pitch_dem);
  725. }
  726. else if (_pitch_dem < _PITCHminf)
  727. {
  728. integSEB_input = MAX(integSEB_input, _PITCHminf - _pitch_dem);
  729. }
  730. float integSEB_delta = integSEB_input * _DT;
  731. #if 0
  732. if (_landing.is_flaring() && fabsf(_climb_rate) > 0.2f) {
  733. ::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",
  734. _hgt_rate_dem, _hgt_dem_adj, _climb_rate, _flare_counter, degrees(_pitch_dem),
  735. SEB_dem, SEBdot_dem, SEB_error, SEBdot_error);
  736. }
  737. #endif
  738. // Apply max and min values for integrator state that will allow for no more than
  739. // 5deg of saturation. This allows for some pitch variation due to gusts before the
  740. // integrator is clipped. Otherwise the effectiveness of the integrator will be reduced in turbulence
  741. // During climbout/takeoff, bias the demanded pitch angle so that zero speed error produces a pitch angle
  742. // demand equal to the minimum value (which is )set by the mission plan during this mode). Otherwise the
  743. // integrator has to catch up before the nose can be raised to reduce speed during climbout.
  744. // During flare a different damping gain is used
  745. float gainInv = (_TAS_state * timeConstant() * GRAVITY_MSS);
  746. float temp = SEB_error + SEBdot_dem * timeConstant();
  747. float pitch_damp = _ptchDamp;
  748. if (_landing.is_flaring()) {
  749. pitch_damp = _landDamp;
  750. } else if (!is_zero(_land_pitch_damp) && _flags.is_doing_auto_land) {
  751. pitch_damp = _land_pitch_damp;
  752. }
  753. temp += SEBdot_error * pitch_damp;
  754. if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
  755. temp += _PITCHminf * gainInv;
  756. }
  757. float integSEB_min = (gainInv * (_PITCHminf - 0.0783f)) - temp;
  758. float integSEB_max = (gainInv * (_PITCHmaxf + 0.0783f)) - temp;
  759. float integSEB_range = integSEB_max - integSEB_min;
  760. logging.SEB_delta = integSEB_delta;
  761. // don't allow the integrator to rise by more than 20% of its full
  762. // range in one step. This prevents single value glitches from
  763. // causing massive integrator changes. See Issue#4066
  764. integSEB_delta = constrain_float(integSEB_delta, -integSEB_range*0.1f, integSEB_range*0.1f);
  765. // prevent the constraint on pitch integrator _integSEB_state from
  766. // itself injecting step changes in the variable. We only want the
  767. // constraint to prevent large changes due to integSEB_delta, not
  768. // to cause step changes due to a change in the constrain
  769. // limits. Large steps in _integSEB_state can cause long term
  770. // pitch changes
  771. integSEB_min = MIN(integSEB_min, _integSEB_state);
  772. integSEB_max = MAX(integSEB_max, _integSEB_state);
  773. // integrate
  774. _integSEB_state = constrain_float(_integSEB_state + integSEB_delta, integSEB_min, integSEB_max);
  775. // Calculate pitch demand from specific energy balance signals
  776. _pitch_dem_unc = (temp + _integSEB_state) / gainInv;
  777. // Constrain pitch demand
  778. _pitch_dem = constrain_float(_pitch_dem_unc, _PITCHminf, _PITCHmaxf);
  779. // Rate limit the pitch demand to comply with specified vertical
  780. // acceleration limit
  781. float ptchRateIncr = _DT * _vertAccLim / _TAS_state;
  782. if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr)
  783. {
  784. _pitch_dem = _last_pitch_dem + ptchRateIncr;
  785. }
  786. else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr)
  787. {
  788. _pitch_dem = _last_pitch_dem - ptchRateIncr;
  789. }
  790. // re-constrain pitch demand
  791. _pitch_dem = constrain_float(_pitch_dem, _PITCHminf, _PITCHmaxf);
  792. _last_pitch_dem = _pitch_dem;
  793. }
  794. void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe)
  795. {
  796. // Initialise states and variables if DT > 1 second or in climbout
  797. if (_DT > 1.0f)
  798. {
  799. _integTHR_state = 0.0f;
  800. _integSEB_state = 0.0f;
  801. _last_throttle_dem = aparm.throttle_cruise * 0.01f;
  802. _last_pitch_dem = _ahrs.pitch;
  803. _hgt_dem_adj_last = hgt_afe;
  804. _hgt_dem_adj = _hgt_dem_adj_last;
  805. _hgt_dem_prev = _hgt_dem_adj_last;
  806. _hgt_dem_in_old = _hgt_dem_adj_last;
  807. _TAS_dem_adj = _TAS_dem;
  808. _flags.underspeed = false;
  809. _flags.badDescent = false;
  810. _flags.reached_speed_takeoff = false;
  811. _DT = 0.1f; // when first starting TECS, use a
  812. // small time constant
  813. }
  814. else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)
  815. {
  816. _PITCHminf = 0.000174533f * ptchMinCO_cd;
  817. _hgt_dem_adj_last = hgt_afe;
  818. _hgt_dem_adj = _hgt_dem_adj_last;
  819. _hgt_dem_prev = _hgt_dem_adj_last;
  820. _TAS_dem_adj = _TAS_dem;
  821. _flags.underspeed = false;
  822. _flags.badDescent = false;
  823. }
  824. if (_flight_stage != AP_Vehicle::FixedWing::FLIGHT_TAKEOFF && _flight_stage != AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
  825. // reset takeoff speed flag when not in takeoff
  826. _flags.reached_speed_takeoff = false;
  827. }
  828. }
  829. void AP_TECS::_update_STE_rate_lim(void)
  830. {
  831. // Calculate Specific Total Energy Rate Limits
  832. // This is a trivial calculation at the moment but will get bigger once we start adding altitude effects
  833. _STEdot_max = _maxClimbRate * GRAVITY_MSS;
  834. _STEdot_min = - _minSinkRate * GRAVITY_MSS;
  835. }
  836. void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
  837. int32_t EAS_dem_cm,
  838. enum AP_Vehicle::FixedWing::FlightStage flight_stage,
  839. float distance_beyond_land_wp,
  840. int32_t ptchMinCO_cd,
  841. int16_t throttle_nudge,
  842. float hgt_afe,
  843. float load_factor,
  844. bool soaring_active)
  845. {
  846. // Calculate time in seconds since last update
  847. uint64_t now = AP_HAL::micros64();
  848. _DT = (now - _update_pitch_throttle_last_usec) * 1.0e-6f;
  849. _update_pitch_throttle_last_usec = now;
  850. _flags.is_doing_auto_land = (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND);
  851. _distance_beyond_land_wp = distance_beyond_land_wp;
  852. _flight_stage = flight_stage;
  853. // Convert inputs
  854. _hgt_dem = hgt_dem_cm * 0.01f;
  855. _EAS_dem = EAS_dem_cm * 0.01f;
  856. // Update the speed estimate using a 2nd order complementary filter
  857. _update_speed(load_factor);
  858. if (aparm.takeoff_throttle_max != 0 &&
  859. (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)) {
  860. _THRmaxf = aparm.takeoff_throttle_max * 0.01f;
  861. } else {
  862. _THRmaxf = aparm.throttle_max * 0.01f;
  863. }
  864. _THRminf = aparm.throttle_min * 0.01f;
  865. // min of 1% throttle range to prevent a numerical error
  866. _THRmaxf = MAX(_THRmaxf, _THRminf+0.01);
  867. // work out the maximum and minimum pitch
  868. // if TECS_PITCH_{MAX,MIN} isn't set then use
  869. // LIM_PITCH_{MAX,MIN}. Don't allow TECS_PITCH_{MAX,MIN} to be
  870. // larger than LIM_PITCH_{MAX,MIN}
  871. if (_pitch_max == 0) {
  872. _PITCHmaxf = aparm.pitch_limit_max_cd * 0.01f;
  873. } else {
  874. _PITCHmaxf = MIN(_pitch_max, aparm.pitch_limit_max_cd * 0.01f);
  875. }
  876. if (_pitch_min >= 0) {
  877. _PITCHminf = aparm.pitch_limit_min_cd * 0.01f;
  878. } else {
  879. _PITCHminf = MAX(_pitch_min, aparm.pitch_limit_min_cd * 0.01f);
  880. }
  881. // apply temporary pitch limit and clear
  882. if (_pitch_max_limit < 90) {
  883. _PITCHmaxf = constrain_float(_PITCHmaxf, -90, _pitch_max_limit);
  884. _PITCHminf = constrain_float(_PITCHminf, -_pitch_max_limit, _PITCHmaxf);
  885. _pitch_max_limit = 90;
  886. }
  887. if (!_landing.is_on_approach()) {
  888. // reset land pitch min when not landing
  889. _land_pitch_min = _PITCHminf;
  890. }
  891. if (_landing.is_flaring()) {
  892. // in flare use min pitch from LAND_PITCH_CD
  893. _PITCHminf = MAX(_PITCHminf, _landing.get_pitch_cd() * 0.01f);
  894. // and use max pitch from TECS_LAND_PMAX
  895. if (_land_pitch_max != 0) {
  896. // note that this allows a flare pitch outside the normal TECS auto limits
  897. _PITCHmaxf = _land_pitch_max;
  898. }
  899. // and allow zero throttle
  900. _THRminf = 0;
  901. } else if (_landing.is_on_approach() && (-_climb_rate) > _land_sink) {
  902. // constrain the pitch in landing as we get close to the flare
  903. // point. Use a simple linear limit from 15 meters after the
  904. // landing point
  905. float time_to_flare = (- hgt_afe / _climb_rate) - _landing.get_flare_sec();
  906. if (time_to_flare < 0) {
  907. // we should be flaring already
  908. _PITCHminf = MAX(_PITCHminf, _landing.get_pitch_cd() * 0.01f);
  909. } else if (time_to_flare < timeConstant()*2) {
  910. // smoothly move the min pitch to the flare min pitch over
  911. // twice the time constant
  912. float p = time_to_flare/(2*timeConstant());
  913. float pitch_limit_cd = p*aparm.pitch_limit_min_cd + (1-p)*_landing.get_pitch_cd();
  914. #if 0
  915. ::printf("ttf=%.1f hgt_afe=%.1f _PITCHminf=%.1f pitch_limit=%.1f climb=%.1f\n",
  916. time_to_flare, hgt_afe, _PITCHminf, pitch_limit_cd*0.01f, _climb_rate);
  917. #endif
  918. _PITCHminf = MAX(_PITCHminf, pitch_limit_cd*0.01f);
  919. }
  920. }
  921. if (_landing.is_on_approach()) {
  922. // don't allow the lower bound of pitch to decrease, nor allow
  923. // it to increase rapidly. This prevents oscillation of pitch
  924. // demand while in landing approach based on rapidly changing
  925. // time to flare estimate
  926. if (_land_pitch_min <= -90) {
  927. _land_pitch_min = _PITCHminf;
  928. }
  929. const float flare_pitch_range = 20;
  930. const float delta_per_loop = (flare_pitch_range/_landTimeConst) * _DT;
  931. _PITCHminf = MIN(_PITCHminf, _land_pitch_min+delta_per_loop);
  932. _land_pitch_min = MAX(_land_pitch_min, _PITCHminf);
  933. _PITCHminf = MAX(_land_pitch_min, _PITCHminf);
  934. }
  935. if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
  936. if (!_flags.reached_speed_takeoff && _TAS_state >= _TAS_dem_adj) {
  937. // we have reached our target speed in takeoff, allow for
  938. // normal throttle control
  939. _flags.reached_speed_takeoff = true;
  940. }
  941. }
  942. // convert to radians
  943. _PITCHmaxf = radians(_PITCHmaxf);
  944. _PITCHminf = radians(_PITCHminf);
  945. // don't allow max pitch to go below min pitch
  946. _PITCHmaxf = MAX(_PITCHmaxf, _PITCHminf);
  947. // initialise selected states and variables if DT > 1 second or in climbout
  948. _initialise_states(ptchMinCO_cd, hgt_afe);
  949. // Calculate Specific Total Energy Rate Limits
  950. _update_STE_rate_lim();
  951. // Calculate the speed demand
  952. _update_speed_demand();
  953. // Calculate the height demand
  954. _update_height_demand();
  955. // Detect underspeed condition
  956. _detect_underspeed();
  957. // Calculate specific energy quantitiues
  958. _update_energies();
  959. // Calculate throttle demand - use simple pitch to throttle if no
  960. // airspeed sensor.
  961. // Note that caller can demand the use of
  962. // synthetic airspeed for one loop if needed. This is required
  963. // during QuadPlane transition when pitch is constrained
  964. if (_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) {
  965. _update_throttle_with_airspeed();
  966. _use_synthetic_airspeed_once = false;
  967. } else {
  968. _update_throttle_without_airspeed(throttle_nudge);
  969. }
  970. // Detect bad descent due to demanded airspeed being too high
  971. _detect_bad_descent();
  972. // when soaring is active we never trigger a bad descent
  973. if (soaring_active || (_options & OPTION_GLIDER_ONLY)) {
  974. _flags.badDescent = false;
  975. }
  976. // Calculate pitch demand
  977. _update_pitch();
  978. // log to AP_Logger
  979. AP::logger().Write(
  980. "TECS",
  981. "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f",
  982. "smnmnnnn----o--",
  983. "F0000000----0--",
  984. "QfffffffffffffB",
  985. now,
  986. (double)_height,
  987. (double)_climb_rate,
  988. (double)_hgt_dem_adj,
  989. (double)_hgt_rate_dem,
  990. (double)_TAS_dem_adj,
  991. (double)_TAS_state,
  992. (double)_vel_dot,
  993. (double)_integTHR_state,
  994. (double)_integSEB_state,
  995. (double)_throttle_dem,
  996. (double)_pitch_dem,
  997. (double)_TAS_rate_dem,
  998. (double)logging.SKE_weighting,
  999. _flags_byte);
  1000. AP::logger().Write("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF",
  1001. "s------",
  1002. "F------",
  1003. "Qffffff",
  1004. now,
  1005. (double)degrees(_PITCHmaxf),
  1006. (double)degrees(_PITCHminf),
  1007. (double)logging.SKE_error,
  1008. (double)logging.SPE_error,
  1009. (double)logging.SEB_delta,
  1010. (double)load_factor);
  1011. }