AC_AttitudeControl_Multi.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365
  1. #include "AC_AttitudeControl_Multi.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Math/AP_Math.h>
  4. // table of user settable parameters
  5. const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
  6. // parameters from parent vehicle
  7. AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
  8. // @Param: RAT_RLL_P
  9. // @DisplayName: Roll axis rate controller P gain
  10. // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
  11. // @Range: 0.01 0.5
  12. // @Increment: 0.005
  13. // @User: Standard
  14. // @Param: RAT_RLL_I
  15. // @DisplayName: Roll axis rate controller I gain
  16. // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
  17. // @Range: 0.01 2.0
  18. // @Increment: 0.01
  19. // @User: Standard
  20. // @Param: RAT_RLL_IMAX
  21. // @DisplayName: Roll axis rate controller I gain maximum
  22. // @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  23. // @Range: 0 1
  24. // @Increment: 0.01
  25. // @Units: %
  26. // @User: Standard
  27. // @Param: RAT_RLL_D
  28. // @DisplayName: Roll axis rate controller D gain
  29. // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
  30. // @Range: 0.0 0.05
  31. // @Increment: 0.001
  32. // @User: Standard
  33. // @Param: RAT_RLL_FF
  34. // @DisplayName: Roll axis rate controller feed forward
  35. // @Description: Roll axis rate controller feed forward
  36. // @Range: 0 0.5
  37. // @Increment: 0.001
  38. // @User: Standard
  39. // @Param: RAT_RLL_FLTT
  40. // @DisplayName: Roll axis rate controller target frequency in Hz
  41. // @Description: Roll axis rate controller target frequency in Hz
  42. // @Range: 1 50
  43. // @Increment: 1
  44. // @Units: Hz
  45. // @User: Standard
  46. // @Param: RAT_RLL_FLTE
  47. // @DisplayName: Roll axis rate controller error frequency in Hz
  48. // @Description: Roll axis rate controller error frequency in Hz
  49. // @Range: 1 100
  50. // @Increment: 1
  51. // @Units: Hz
  52. // @User: Standard
  53. // @Param: RAT_RLL_FLTD
  54. // @DisplayName: Roll axis rate controller derivative frequency in Hz
  55. // @Description: Roll axis rate controller derivative frequency in Hz
  56. // @Range: 1 100
  57. // @Increment: 1
  58. // @Units: Hz
  59. // @User: Standard
  60. AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),
  61. // @Param: RAT_PIT_P
  62. // @DisplayName: Pitch axis rate controller P gain
  63. // @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
  64. // @Range: 0.01 0.50
  65. // @Increment: 0.005
  66. // @User: Standard
  67. // @Param: RAT_PIT_I
  68. // @DisplayName: Pitch axis rate controller I gain
  69. // @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
  70. // @Range: 0.01 2.0
  71. // @Increment: 0.01
  72. // @User: Standard
  73. // @Param: RAT_PIT_IMAX
  74. // @DisplayName: Pitch axis rate controller I gain maximum
  75. // @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  76. // @Range: 0 1
  77. // @Increment: 0.01
  78. // @Units: %
  79. // @User: Standard
  80. // @Param: RAT_PIT_D
  81. // @DisplayName: Pitch axis rate controller D gain
  82. // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
  83. // @Range: 0.0 0.05
  84. // @Increment: 0.001
  85. // @User: Standard
  86. // @Param: RAT_PIT_FF
  87. // @DisplayName: Pitch axis rate controller feed forward
  88. // @Description: Pitch axis rate controller feed forward
  89. // @Range: 0 0.5
  90. // @Increment: 0.001
  91. // @User: Standard
  92. // @Param: RAT_PIT_FLTT
  93. // @DisplayName: Pitch axis rate controller target frequency in Hz
  94. // @Description: Pitch axis rate controller target frequency in Hz
  95. // @Range: 1 50
  96. // @Increment: 1
  97. // @Units: Hz
  98. // @User: Standard
  99. // @Param: RAT_PIT_FLTE
  100. // @DisplayName: Pitch axis rate controller error frequency in Hz
  101. // @Description: Pitch axis rate controller error frequency in Hz
  102. // @Range: 1 100
  103. // @Increment: 1
  104. // @Units: Hz
  105. // @User: Standard
  106. // @Param: RAT_PIT_FLTD
  107. // @DisplayName: Pitch axis rate controller derivative frequency in Hz
  108. // @Description: Pitch axis rate controller derivative frequency in Hz
  109. // @Range: 1 100
  110. // @Increment: 1
  111. // @Units: Hz
  112. // @User: Standard
  113. AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),
  114. // @Param: RAT_YAW_P
  115. // @DisplayName: Yaw axis rate controller P gain
  116. // @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
  117. // @Range: 0.10 2.50
  118. // @Increment: 0.005
  119. // @User: Standard
  120. // @Param: RAT_YAW_I
  121. // @DisplayName: Yaw axis rate controller I gain
  122. // @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
  123. // @Range: 0.010 1.0
  124. // @Increment: 0.01
  125. // @User: Standard
  126. // @Param: RAT_YAW_IMAX
  127. // @DisplayName: Yaw axis rate controller I gain maximum
  128. // @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  129. // @Range: 0 1
  130. // @Increment: 0.01
  131. // @Units: %
  132. // @User: Standard
  133. // @Param: RAT_YAW_D
  134. // @DisplayName: Yaw axis rate controller D gain
  135. // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
  136. // @Range: 0.000 0.02
  137. // @Increment: 0.001
  138. // @User: Standard
  139. // @Param: RAT_YAW_FF
  140. // @DisplayName: Yaw axis rate controller feed forward
  141. // @Description: Yaw axis rate controller feed forward
  142. // @Range: 0 0.5
  143. // @Increment: 0.001
  144. // @User: Standard
  145. // @Param: RAT_YAW_FLTT
  146. // @DisplayName: Yaw axis rate controller target frequency in Hz
  147. // @Description: Yaw axis rate controller target frequency in Hz
  148. // @Range: 1 5
  149. // @Increment: 1
  150. // @Units: Hz
  151. // @User: Standard
  152. // @Param: RAT_YAW_FLTE
  153. // @DisplayName: Yaw axis rate controller error frequency in Hz
  154. // @Description: Yaw axis rate controller error frequency in Hz
  155. // @Range: 1 10
  156. // @Increment: 1
  157. // @Units: Hz
  158. // @User: Standard
  159. // @Param: RAT_YAW_FLTD
  160. // @DisplayName: Yaw axis rate controller derivative frequency in Hz
  161. // @Description: Yaw axis rate controller derivative frequency in Hz
  162. // @Range: 1 20
  163. // @Increment: 1
  164. // @Units: Hz
  165. // @User: Standard
  166. AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),
  167. // @Param: THR_MIX_MIN
  168. // @DisplayName: Throttle Mix Minimum
  169. // @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
  170. // @Range: 0.1 0.25
  171. // @User: Advanced
  172. AP_GROUPINFO("THR_MIX_MIN", 4, AC_AttitudeControl_Multi, _thr_mix_min, AC_ATTITUDE_CONTROL_MIN_DEFAULT),
  173. // @Param: THR_MIX_MAX
  174. // @DisplayName: Throttle Mix Maximum
  175. // @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
  176. // @Range: 0.5 0.9
  177. // @User: Advanced
  178. AP_GROUPINFO("THR_MIX_MAX", 5, AC_AttitudeControl_Multi, _thr_mix_max, AC_ATTITUDE_CONTROL_MAX_DEFAULT),
  179. // @Param: THR_MIX_MAN
  180. // @DisplayName: Throttle Mix Manual
  181. // @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
  182. // @Range: 0.1 0.9
  183. // @User: Advanced
  184. AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Multi, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),
  185. // @Param: RAT_RLL_FILT
  186. // @DisplayName: Roll axis rate controller input frequency in Hz
  187. // @Description: Roll axis rate controller input frequency in Hz
  188. // @Range: 1 100
  189. // @Increment: 1
  190. // @Units: Hz
  191. // @User: Standard
  192. // @Param: RAT_PIT_FILT
  193. // @DisplayName: Pitch axis rate controller input frequency in Hz
  194. // @Description: Pitch axis rate controller input frequency in Hz
  195. // @Range: 1 100
  196. // @Increment: 1
  197. // @Units: Hz
  198. // @User: Standard
  199. // @Param: RAT_YAW_FILT
  200. // @DisplayName: Yaw axis rate controller input frequency in Hz
  201. // @Description: Yaw axis rate controller input frequency in Hz
  202. // @Range: 1 10
  203. // @Increment: 1
  204. // @Units: Hz
  205. // @User: Standard
  206. AP_GROUPEND
  207. };
  208. AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) :
  209. AC_AttitudeControl(ahrs, aparm, motors, dt),
  210. _motors_multi(motors),
  211. _pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
  212. _pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
  213. _pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, AC_ATC_MULTI_RATE_YAW_FILT_HZ, 0.0f, dt)
  214. {
  215. AP_Param::setup_object_defaults(this, var_info);
  216. }
  217. // Update Alt_Hold angle maximum
  218. void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)
  219. {
  220. // calc maximum tilt angle based on throttle
  221. float thr_max = _motors_multi.get_throttle_thrust_max();
  222. // divide by zero check
  223. if (is_zero(thr_max)) {
  224. _althold_lean_angle_max = 0.0f;
  225. return;
  226. }
  227. float althold_lean_angle_max = acosf(constrain_float(_throttle_in / (AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
  228. _althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
  229. }
  230. void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
  231. {
  232. _throttle_in = throttle_in;
  233. update_althold_lean_angle_max(throttle_in);
  234. _motors.set_throttle_filter_cutoff(filter_cutoff);
  235. if (apply_angle_boost) {
  236. // Apply angle boost
  237. throttle_in = get_throttle_boosted(throttle_in);
  238. } else {
  239. // Clear angle_boost for logging purposes
  240. _angle_boost = 0.0f;
  241. }
  242. _motors.set_throttle(throttle_in);
  243. _motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));
  244. }
  245. // returns a throttle including compensation for roll/pitch angle
  246. // throttle value should be 0 ~ 1
  247. float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in)
  248. {
  249. if (!_angle_boost_enabled) {
  250. _angle_boost = 0;
  251. return throttle_in;
  252. }
  253. // inverted_factor is 1 for tilt angles below 60 degrees
  254. // inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees
  255. float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
  256. float inverted_factor = constrain_float(2.0f * cos_tilt, 0.0f, 1.0f);
  257. float boost_factor = 1.0f / constrain_float(cos_tilt, 0.5f, 1.0f);
  258. float throttle_out = throttle_in * inverted_factor * boost_factor;
  259. _angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f);
  260. return throttle_out;
  261. }
  262. // returns a throttle including compensation for roll/pitch angle
  263. // throttle value should be 0 ~ 1
  264. float AC_AttitudeControl_Multi::get_throttle_avg_max(float throttle_in)
  265. {
  266. throttle_in = constrain_float(throttle_in, 0.0f, 1.0f);
  267. return MAX(throttle_in, throttle_in * MAX(0.0f, 1.0f - _throttle_rpy_mix) + _motors.get_throttle_hover() * _throttle_rpy_mix);
  268. }
  269. // update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value
  270. void AC_AttitudeControl_Multi::update_throttle_rpy_mix()
  271. {
  272. // slew _throttle_rpy_mix to _throttle_rpy_mix_desired
  273. if (_throttle_rpy_mix < _throttle_rpy_mix_desired) {
  274. // increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)
  275. _throttle_rpy_mix += MIN(2.0f * _dt, _throttle_rpy_mix_desired - _throttle_rpy_mix);
  276. } else if (_throttle_rpy_mix > _throttle_rpy_mix_desired) {
  277. // reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)
  278. _throttle_rpy_mix -= MIN(0.5f * _dt, _throttle_rpy_mix - _throttle_rpy_mix_desired);
  279. }
  280. _throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);
  281. }
  282. void AC_AttitudeControl_Multi::rate_controller_run()
  283. {
  284. // move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)
  285. update_throttle_rpy_mix();
  286. Vector3f gyro_latest = _ahrs.get_gyro_latest();
  287. _motors.set_roll(get_rate_roll_pid().update_all(_rate_target_ang_vel.x, gyro_latest.x, _motors.limit.roll));
  288. _motors.set_roll_ff(get_rate_roll_pid().get_ff());
  289. _motors.set_pitch(get_rate_pitch_pid().update_all(_rate_target_ang_vel.y, gyro_latest.y, _motors.limit.pitch));
  290. _motors.set_pitch_ff(get_rate_pitch_pid().get_ff());
  291. _motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
  292. _motors.set_yaw_ff(get_rate_yaw_pid().get_ff());
  293. control_monitor_update();
  294. }
  295. // sanity check parameters. should be called once before takeoff
  296. void AC_AttitudeControl_Multi::parameter_sanity_check()
  297. {
  298. // sanity check throttle mix parameters
  299. if (_thr_mix_man < 0.1f || _thr_mix_man > 4.0f) {
  300. // parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0
  301. // which can be useful for very high powered copters with very low hover throttle
  302. _thr_mix_man.set_and_save(AC_ATTITUDE_CONTROL_MAN_DEFAULT);
  303. }
  304. if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) {
  305. _thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);
  306. }
  307. if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {
  308. // parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0
  309. // which can be useful for very high powered copters with very low hover throttle
  310. _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);
  311. }
  312. if (_thr_mix_min > _thr_mix_max) {
  313. _thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);
  314. _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);
  315. }
  316. }