AP_PitchController.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. // Initial Code by Jon Challinger
  14. // Modified by Paul Riseborough
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_PitchController.h"
  17. extern const AP_HAL::HAL& hal;
  18. const AP_Param::GroupInfo AP_PitchController::var_info[] = {
  19. // @Param: TCONST
  20. // @DisplayName: Pitch Time Constant
  21. // @Description: Time constant in seconds from demanded to achieved pitch angle. Most models respond well to 0.5. May be reduced for faster responses, but setting lower than a model can achieve will not help.
  22. // @Range: 0.4 1.0
  23. // @Units: s
  24. // @Increment: 0.1
  25. // @User: Advanced
  26. AP_GROUPINFO("TCONST", 0, AP_PitchController, gains.tau, 0.5f),
  27. // @Param: P
  28. // @DisplayName: Proportional Gain
  29. // @Description: Proportional gain from pitch angle demands to elevator. Higher values allow more servo response but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  30. // @Range: 0.1 3.0
  31. // @Increment: 0.1
  32. // @User: User
  33. AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 1.0f),
  34. // @Param: D
  35. // @DisplayName: Damping Gain
  36. // @Description: Damping gain from pitch acceleration to elevator. Higher values reduce pitching in turbulence, but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  37. // @Range: 0 0.2
  38. // @Increment: 0.01
  39. // @User: User
  40. AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.04f),
  41. // @Param: I
  42. // @DisplayName: Integrator Gain
  43. // @Description: Integrator gain from long-term pitch angle offsets to elevator. Higher values "trim" out offsets faster but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  44. // @Range: 0 0.5
  45. // @Increment: 0.05
  46. // @User: User
  47. AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.3f),
  48. // @Param: RMAX_UP
  49. // @DisplayName: Pitch up max rate
  50. // @Description: Maximum pitch up rate that the pitch controller demands (degrees/sec) in ACRO mode.
  51. // @Range: 0 100
  52. // @Units: deg/s
  53. // @Increment: 1
  54. // @User: Advanced
  55. AP_GROUPINFO("RMAX_UP", 4, AP_PitchController, gains.rmax, 0.0f),
  56. // @Param: RMAX_DN
  57. // @DisplayName: Pitch down max rate
  58. // @Description: This sets the maximum nose down pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit.
  59. // @Range: 0 100
  60. // @Units: deg/s
  61. // @Increment: 1
  62. // @User: Advanced
  63. AP_GROUPINFO("RMAX_DN", 5, AP_PitchController, _max_rate_neg, 0.0f),
  64. // @Param: RLL
  65. // @DisplayName: Roll compensation
  66. // @Description: Gain added to pitch to keep aircraft from descending or ascending in turns. Increase in increments of 0.05 to reduce altitude loss. Decrease for altitude gain.
  67. // @Range: 0.7 1.5
  68. // @Increment: 0.05
  69. // @User: User
  70. AP_GROUPINFO("RLL", 6, AP_PitchController, _roll_ff, 1.0f),
  71. // @Param: IMAX
  72. // @DisplayName: Integrator limit
  73. // @Description: Limit of pitch integrator gain in centi-degrees of servo travel. Servos are assumed to have +/- 4500 centi-degrees of travel, so a value of 3000 allows trim of up to 2/3 of servo travel range.
  74. // @Range: 0 4500
  75. // @Increment: 1
  76. // @User: Advanced
  77. AP_GROUPINFO("IMAX", 7, AP_PitchController, gains.imax, 3000),
  78. // @Param: FF
  79. // @DisplayName: Feed forward Gain
  80. // @Description: Gain from demanded rate to elevator output.
  81. // @Range: 0.1 4.0
  82. // @Increment: 0.1
  83. // @User: User
  84. AP_GROUPINFO("FF", 8, AP_PitchController, gains.FF, 0.0f),
  85. AP_GROUPEND
  86. };
  87. /*
  88. Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
  89. A positive demand is up
  90. Inputs are:
  91. 1) demanded pitch rate in degrees/second
  92. 2) control gain scaler = scaling_speed / aspeed
  93. 3) boolean which is true when stabilise mode is active
  94. 4) minimum FBW airspeed (metres/sec)
  95. 5) maximum FBW airspeed (metres/sec)
  96. */
  97. int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed)
  98. {
  99. uint32_t tnow = AP_HAL::millis();
  100. uint32_t dt = tnow - _last_t;
  101. if (_last_t == 0 || dt > 1000) {
  102. dt = 0;
  103. }
  104. _last_t = tnow;
  105. float delta_time = (float)dt * 0.001f;
  106. // Get body rate vector (radians/sec)
  107. float omega_y = _ahrs.get_gyro().y;
  108. // Calculate the pitch rate error (deg/sec) and scale
  109. float achieved_rate = ToDeg(omega_y);
  110. float rate_error = (desired_rate - achieved_rate) * scaler;
  111. // Multiply pitch rate error by _ki_rate and integrate
  112. // Scaler is applied before integrator so that integrator state relates directly to elevator deflection
  113. // This means elevator trim offset doesn't change as the value of scaler changes with airspeed
  114. // Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
  115. if (!disable_integrator && gains.I > 0) {
  116. float k_I = gains.I;
  117. if (is_zero(gains.FF)) {
  118. /*
  119. if the user hasn't set a direct FF then assume they are
  120. not doing sophisticated tuning. Set a minimum I value of
  121. 0.15 to ensure that the time constant for trimming in
  122. pitch is not too long. We have had a lot of user issues
  123. with very small I value leading to very slow pitch
  124. trimming, which causes a lot of problems for TECS. A
  125. value of 0.15 is still quite small, but a lot better
  126. than what many users are running.
  127. */
  128. k_I = MAX(k_I, 0.15f);
  129. }
  130. float ki_rate = k_I * gains.tau;
  131. //only integrate if gain and time step are positive and airspeed above min value.
  132. if (dt > 0 && aspeed > 0.5f*float(aparm.airspeed_min)) {
  133. float integrator_delta = rate_error * ki_rate * delta_time * scaler;
  134. if (_last_out < -45) {
  135. // prevent the integrator from increasing if surface defln demand is above the upper limit
  136. integrator_delta = MAX(integrator_delta , 0);
  137. } else if (_last_out > 45) {
  138. // prevent the integrator from decreasing if surface defln demand is below the lower limit
  139. integrator_delta = MIN(integrator_delta , 0);
  140. }
  141. _pid_info.I += integrator_delta;
  142. }
  143. } else {
  144. _pid_info.I = 0;
  145. }
  146. // Scale the integration limit
  147. float intLimScaled = gains.imax * 0.01f;
  148. // Constrain the integrator state
  149. _pid_info.I = constrain_float(_pid_info.I, -intLimScaled, intLimScaled);
  150. // Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
  151. // No conversion is required for K_D
  152. float eas2tas = _ahrs.get_EAS2TAS();
  153. float kp_ff = MAX((gains.P - gains.I * gains.tau) * gains.tau - gains.D , 0) / eas2tas;
  154. float k_ff = gains.FF / eas2tas;
  155. // Calculate the demanded control surface deflection
  156. // Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
  157. // path, but want a 1/speed^2 scaler applied to the rate error path.
  158. // This is because acceleration scales with speed^2, but rate scales with speed.
  159. _pid_info.P = desired_rate * kp_ff * scaler;
  160. _pid_info.FF = desired_rate * k_ff * scaler;
  161. _pid_info.D = rate_error * gains.D * scaler;
  162. _last_out = _pid_info.D + _pid_info.FF + _pid_info.P;
  163. _pid_info.target = desired_rate;
  164. _pid_info.actual = achieved_rate;
  165. if (autotune.running && aspeed > aparm.airspeed_min) {
  166. // let autotune have a go at the values
  167. // Note that we don't pass the integrator component so we get
  168. // a better idea of how much the base PD controller
  169. // contributed
  170. autotune.update(desired_rate, achieved_rate, _last_out);
  171. // set down rate to rate up when auto-tuning
  172. _max_rate_neg.set_and_save_ifchanged(gains.rmax);
  173. }
  174. _last_out += _pid_info.I;
  175. /*
  176. when we are past the users defined roll limit for the
  177. aircraft our priority should be to bring the aircraft back
  178. within the roll limit. Using elevator for pitch control at
  179. large roll angles is ineffective, and can be counter
  180. productive as it induces earth-frame yaw which can reduce
  181. the ability to roll. We linearly reduce elevator input when
  182. beyond the configured roll limit, reducing to zero at 90
  183. degrees
  184. */
  185. float roll_wrapped = labs(_ahrs.roll_sensor);
  186. if (roll_wrapped > 9000) {
  187. roll_wrapped = 18000 - roll_wrapped;
  188. }
  189. if (roll_wrapped > aparm.roll_limit_cd + 500 && aparm.roll_limit_cd < 8500 &&
  190. labs(_ahrs.pitch_sensor) < 7000) {
  191. float roll_prop = (roll_wrapped - (aparm.roll_limit_cd+500)) / (float)(9000 - aparm.roll_limit_cd);
  192. _last_out *= (1 - roll_prop);
  193. }
  194. // Convert to centi-degrees and constrain
  195. return constrain_float(_last_out * 100, -4500, 4500);
  196. }
  197. /*
  198. Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
  199. A positive demand is up
  200. Inputs are:
  201. 1) demanded pitch rate in degrees/second
  202. 2) control gain scaler = scaling_speed / aspeed
  203. 3) boolean which is true when stabilise mode is active
  204. 4) minimum FBW airspeed (metres/sec)
  205. 5) maximum FBW airspeed (metres/sec)
  206. */
  207. int32_t AP_PitchController::get_rate_out(float desired_rate, float scaler)
  208. {
  209. float aspeed;
  210. if (!_ahrs.airspeed_estimate(&aspeed)) {
  211. // If no airspeed available use average of min and max
  212. aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
  213. }
  214. return _get_rate_out(desired_rate, scaler, false, aspeed);
  215. }
  216. /*
  217. get the rate offset in degrees/second needed for pitch in body frame
  218. to maintain height in a coordinated turn.
  219. Also returns the inverted flag and the estimated airspeed in m/s for
  220. use by the rest of the pitch controller
  221. */
  222. float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const
  223. {
  224. float rate_offset;
  225. float bank_angle = _ahrs.roll;
  226. // limit bank angle between +- 80 deg if right way up
  227. if (fabsf(bank_angle) < radians(90)) {
  228. bank_angle = constrain_float(bank_angle,-radians(80),radians(80));
  229. inverted = false;
  230. } else {
  231. inverted = true;
  232. if (bank_angle > 0.0f) {
  233. bank_angle = constrain_float(bank_angle,radians(100),radians(180));
  234. } else {
  235. bank_angle = constrain_float(bank_angle,-radians(180),-radians(100));
  236. }
  237. }
  238. if (!_ahrs.airspeed_estimate(&aspeed)) {
  239. // If no airspeed available use average of min and max
  240. aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
  241. }
  242. if (abs(_ahrs.pitch_sensor) > 7000) {
  243. // don't do turn coordination handling when at very high pitch angles
  244. rate_offset = 0;
  245. } else {
  246. rate_offset = cosf(_ahrs.pitch)*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()) , float(aparm.airspeed_min))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
  247. }
  248. if (inverted) {
  249. rate_offset = -rate_offset;
  250. }
  251. return rate_offset;
  252. }
  253. // Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
  254. // A positive demand is up
  255. // Inputs are:
  256. // 1) demanded pitch angle in centi-degrees
  257. // 2) control gain scaler = scaling_speed / aspeed
  258. // 3) boolean which is true when stabilise mode is active
  259. // 4) minimum FBW airspeed (metres/sec)
  260. // 5) maximum FBW airspeed (metres/sec)
  261. //
  262. int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
  263. {
  264. // Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
  265. // Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn
  266. // Pitch rate offset is the component of turn rate about the pitch axis
  267. float aspeed;
  268. float rate_offset;
  269. bool inverted;
  270. if (gains.tau < 0.1f) {
  271. gains.tau.set(0.1f);
  272. }
  273. rate_offset = _get_coordination_rate_offset(aspeed, inverted);
  274. // Calculate the desired pitch rate (deg/sec) from the angle error
  275. float desired_rate = angle_err * 0.01f / gains.tau;
  276. // limit the maximum pitch rate demand. Don't apply when inverted
  277. // as the rates will be tuned when upright, and it is common that
  278. // much higher rates are needed inverted
  279. if (!inverted) {
  280. if (_max_rate_neg && desired_rate < -_max_rate_neg) {
  281. desired_rate = -_max_rate_neg;
  282. } else if (gains.rmax && desired_rate > gains.rmax) {
  283. desired_rate = gains.rmax;
  284. }
  285. }
  286. if (inverted) {
  287. desired_rate = -desired_rate;
  288. }
  289. // Apply the turn correction offset
  290. desired_rate = desired_rate + rate_offset;
  291. return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed);
  292. }
  293. void AP_PitchController::reset_I()
  294. {
  295. _pid_info.I = 0;
  296. }