AP_RollController.cpp 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218
  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. // Code by Jon Challinger
  14. // Modified by Paul Riseborough
  15. //
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "AP_RollController.h"
  18. extern const AP_HAL::HAL& hal;
  19. const AP_Param::GroupInfo AP_RollController::var_info[] = {
  20. // @Param: TCONST
  21. // @DisplayName: Roll Time Constant
  22. // @Description: Time constant in seconds from demanded to achieved roll 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.
  23. // @Range: 0.4 1.0
  24. // @Units: s
  25. // @Increment: 0.1
  26. // @User: Advanced
  27. AP_GROUPINFO("TCONST", 0, AP_RollController, gains.tau, 0.5f),
  28. // @Param: P
  29. // @DisplayName: Proportional Gain
  30. // @Description: Proportional gain from roll angle demands to ailerons. Higher values allow more servo response but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  31. // @Range: 0.1 4.0
  32. // @Increment: 0.1
  33. // @User: User
  34. AP_GROUPINFO("P", 1, AP_RollController, gains.P, 1.0f),
  35. // @Param: D
  36. // @DisplayName: Damping Gain
  37. // @Description: Damping gain from roll acceleration to ailerons. Higher values reduce rolling in turbulence, but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  38. // @Range: 0 0.2
  39. // @Increment: 0.01
  40. // @User: User
  41. AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.08f),
  42. // @Param: I
  43. // @DisplayName: Integrator Gain
  44. // @Description: Integrator gain from long-term roll angle offsets to ailerons. Higher values "trim" out offsets faster but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
  45. // @Range: 0 1.0
  46. // @Increment: 0.05
  47. // @User: User
  48. AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.3f),
  49. // @Param: RMAX
  50. // @DisplayName: Maximum Roll Rate
  51. // @Description: Maximum roll rate that the roll controller demands (degrees/sec) in ACRO mode.
  52. // @Range: 0 180
  53. // @Units: deg/s
  54. // @Increment: 1
  55. // @User: Advanced
  56. AP_GROUPINFO("RMAX", 4, AP_RollController, gains.rmax, 0),
  57. // @Param: IMAX
  58. // @DisplayName: Integrator limit
  59. // @Description: Limit of roll 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.
  60. // @Range: 0 4500
  61. // @Increment: 1
  62. // @User: Advanced
  63. AP_GROUPINFO("IMAX", 5, AP_RollController, gains.imax, 3000),
  64. // @Param: FF
  65. // @DisplayName: Feed forward Gain
  66. // @Description: Gain from demanded rate to aileron output.
  67. // @Range: 0.1 4.0
  68. // @Increment: 0.1
  69. // @User: User
  70. AP_GROUPINFO("FF", 6, AP_RollController, gains.FF, 0.0f),
  71. AP_GROUPEND
  72. };
  73. /*
  74. internal rate controller, called by attitude and rate controller
  75. public functions
  76. */
  77. int32_t AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator)
  78. {
  79. uint32_t tnow = AP_HAL::millis();
  80. uint32_t dt = tnow - _last_t;
  81. if (_last_t == 0 || dt > 1000) {
  82. dt = 0;
  83. }
  84. _last_t = tnow;
  85. // Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
  86. // No conversion is required for K_D
  87. float ki_rate = gains.I * gains.tau;
  88. float eas2tas = _ahrs.get_EAS2TAS();
  89. float kp_ff = MAX((gains.P - gains.I * gains.tau) * gains.tau - gains.D , 0) / eas2tas;
  90. float k_ff = gains.FF / eas2tas;
  91. float delta_time = (float)dt * 0.001f;
  92. // Get body rate vector (radians/sec)
  93. float omega_x = _ahrs.get_gyro().x;
  94. // Calculate the roll rate error (deg/sec) and apply gain scaler
  95. float achieved_rate = ToDeg(omega_x);
  96. float rate_error = (desired_rate - achieved_rate) * scaler;
  97. // Get an airspeed estimate - default to zero if none available
  98. float aspeed;
  99. if (!_ahrs.airspeed_estimate(&aspeed)) {
  100. aspeed = 0.0f;
  101. }
  102. // Multiply roll rate error by _ki_rate, apply scaler and integrate
  103. // Scaler is applied before integrator so that integrator state relates directly to aileron deflection
  104. // This means aileron trim offset doesn't change as the value of scaler changes with airspeed
  105. // Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
  106. if (!disable_integrator && ki_rate > 0) {
  107. //only integrate if gain and time step are positive and airspeed above min value.
  108. if (dt > 0 && aspeed > float(aparm.airspeed_min)) {
  109. float integrator_delta = rate_error * ki_rate * delta_time * scaler;
  110. // prevent the integrator from increasing if surface defln demand is above the upper limit
  111. if (_last_out < -45) {
  112. integrator_delta = MAX(integrator_delta , 0);
  113. } else if (_last_out > 45) {
  114. // prevent the integrator from decreasing if surface defln demand is below the lower limit
  115. integrator_delta = MIN(integrator_delta, 0);
  116. }
  117. _pid_info.I += integrator_delta;
  118. }
  119. } else {
  120. _pid_info.I = 0;
  121. }
  122. // Scale the integration limit
  123. float intLimScaled = gains.imax * 0.01f;
  124. // Constrain the integrator state
  125. _pid_info.I = constrain_float(_pid_info.I, -intLimScaled, intLimScaled);
  126. // Calculate the demanded control surface deflection
  127. // Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
  128. // path, but want a 1/speed^2 scaler applied to the rate error path.
  129. // This is because acceleration scales with speed^2, but rate scales with speed.
  130. _pid_info.D = rate_error * gains.D * scaler;
  131. _pid_info.P = desired_rate * kp_ff * scaler;
  132. _pid_info.FF = desired_rate * k_ff * scaler;
  133. _pid_info.target = desired_rate;
  134. _pid_info.actual = achieved_rate;
  135. _last_out = _pid_info.FF + _pid_info.P + _pid_info.D;
  136. if (autotune.running && aspeed > aparm.airspeed_min) {
  137. // let autotune have a go at the values
  138. // Note that we don't pass the integrator component so we get
  139. // a better idea of how much the base PD controller
  140. // contributed
  141. autotune.update(desired_rate, achieved_rate, _last_out);
  142. }
  143. _last_out += _pid_info.I;
  144. // Convert to centi-degrees and constrain
  145. return constrain_float(_last_out * 100, -4500, 4500);
  146. }
  147. /*
  148. Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
  149. A positive demand is up
  150. Inputs are:
  151. 1) desired roll rate in degrees/sec
  152. 2) control gain scaler = scaling_speed / aspeed
  153. */
  154. int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
  155. {
  156. return _get_rate_out(desired_rate, scaler, false);
  157. }
  158. /*
  159. Function returns an equivalent aileron deflection in centi-degrees in the range from -4500 to 4500
  160. A positive demand is up
  161. Inputs are:
  162. 1) demanded bank angle in centi-degrees
  163. 2) control gain scaler = scaling_speed / aspeed
  164. 3) boolean which is true when stabilise mode is active
  165. 4) minimum FBW airspeed (metres/sec)
  166. */
  167. int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
  168. {
  169. if (gains.tau < 0.1f) {
  170. gains.tau.set(0.1f);
  171. }
  172. // Calculate the desired roll rate (deg/sec) from the angle error
  173. float desired_rate = angle_err * 0.01f / gains.tau;
  174. // Limit the demanded roll rate
  175. if (gains.rmax && desired_rate < -gains.rmax) {
  176. desired_rate = - gains.rmax;
  177. } else if (gains.rmax && desired_rate > gains.rmax) {
  178. desired_rate = gains.rmax;
  179. }
  180. return _get_rate_out(desired_rate, scaler, disable_integrator);
  181. }
  182. void AP_RollController::reset_I()
  183. {
  184. _pid_info.I = 0;
  185. }