AC_AttitudeControl_Heli.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402
  1. #include "AC_AttitudeControl_Heli.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. // table of user settable parameters
  4. const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
  5. // parameters from parent vehicle
  6. AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
  7. // @Param: HOVR_ROL_TRM
  8. // @DisplayName: Hover Roll Trim
  9. // @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
  10. // @Units: cdeg
  11. // @Range: 0 1000
  12. // @User: Advanced
  13. AP_GROUPINFO("HOVR_ROL_TRM", 1, AC_AttitudeControl_Heli, _hover_roll_trim, AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT),
  14. // @Param: RAT_RLL_P
  15. // @DisplayName: Roll axis rate controller P gain
  16. // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
  17. // @Range: 0.08 0.35
  18. // @Increment: 0.005
  19. // @User: Standard
  20. // @Param: RAT_RLL_I
  21. // @DisplayName: Roll axis rate controller I gain
  22. // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
  23. // @Range: 0.01 0.6
  24. // @Increment: 0.01
  25. // @User: Standard
  26. // @Param: RAT_RLL_IMAX
  27. // @DisplayName: Roll axis rate controller I gain maximum
  28. // @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  29. // @Range: 0 1
  30. // @Increment: 0.01
  31. // @User: Standard
  32. // @Param: RAT_RLL_D
  33. // @DisplayName: Roll axis rate controller D gain
  34. // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
  35. // @Range: 0.001 0.03
  36. // @Increment: 0.001
  37. // @User: Standard
  38. // @Param: RAT_RLL_FF
  39. // @DisplayName: Roll axis rate controller feed forward
  40. // @Description: Roll axis rate controller feed forward
  41. // @Range: 0 0.5
  42. // @Increment: 0.001
  43. // @User: Standard
  44. // @Param: RAT_RLL_FILT
  45. // @DisplayName: Roll axis rate controller input frequency in Hz
  46. // @Description: Roll axis rate controller input frequency in Hz
  47. // @Units: Hz
  48. // @Range: 1 20
  49. // @Increment: 1
  50. AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),
  51. // @Param: RAT_PIT_P
  52. // @DisplayName: Pitch axis rate controller P gain
  53. // @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
  54. // @Range: 0.08 0.35
  55. // @Increment: 0.005
  56. // @User: Standard
  57. // @Param: RAT_PIT_I
  58. // @DisplayName: Pitch axis rate controller I gain
  59. // @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
  60. // @Range: 0.01 0.6
  61. // @Increment: 0.01
  62. // @User: Standard
  63. // @Param: RAT_PIT_IMAX
  64. // @DisplayName: Pitch axis rate controller I gain maximum
  65. // @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  66. // @Range: 0 1
  67. // @Increment: 0.01
  68. // @User: Standard
  69. // @Param: RAT_PIT_D
  70. // @DisplayName: Pitch axis rate controller D gain
  71. // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
  72. // @Range: 0.001 0.03
  73. // @Increment: 0.001
  74. // @User: Standard
  75. // @Param: RAT_PIT_FF
  76. // @DisplayName: Pitch axis rate controller feed forward
  77. // @Description: Pitch axis rate controller feed forward
  78. // @Range: 0 0.5
  79. // @Increment: 0.001
  80. // @User: Standard
  81. // @Param: RAT_PIT_FILT
  82. // @DisplayName: Pitch axis rate controller input frequency in Hz
  83. // @Description: Pitch axis rate controller input frequency in Hz
  84. // @Units: Hz
  85. // @Range: 1 20
  86. // @Increment: 1
  87. AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),
  88. // @Param: RAT_YAW_P
  89. // @DisplayName: Yaw axis rate controller P gain
  90. // @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
  91. // @Range: 0.180 0.60
  92. // @Increment: 0.005
  93. // @User: Standard
  94. // @Param: RAT_YAW_I
  95. // @DisplayName: Yaw axis rate controller I gain
  96. // @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
  97. // @Range: 0.01 0.06
  98. // @Increment: 0.01
  99. // @User: Standard
  100. // @Param: RAT_YAW_IMAX
  101. // @DisplayName: Yaw axis rate controller I gain maximum
  102. // @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
  103. // @Range: 0 1
  104. // @Increment: 0.01
  105. // @User: Standard
  106. // @Param: RAT_YAW_D
  107. // @DisplayName: Yaw axis rate controller D gain
  108. // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
  109. // @Range: 0.000 0.02
  110. // @Increment: 0.001
  111. // @User: Standard
  112. // @Param: RAT_YAW_FF
  113. // @DisplayName: Yaw axis rate controller feed forward
  114. // @Description: Yaw axis rate controller feed forward
  115. // @Range: 0 0.5
  116. // @Increment: 0.001
  117. // @User: Standard
  118. // @Param: RAT_YAW_FILT
  119. // @DisplayName: Yaw axis rate controller input frequency in Hz
  120. // @Description: Yaw axis rate controller input frequency in Hz
  121. // @Units: Hz
  122. // @Range: 1 20
  123. // @Increment: 1
  124. AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
  125. // @Param: PIRO_COMP
  126. // @DisplayName: Piro Comp Enable
  127. // @Description: Pirouette compensation enabled
  128. // @Values: 0:Disabled,1:Enabled
  129. // @User: Advanced
  130. AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
  131. AP_GROUPEND
  132. };
  133. // passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode
  134. void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
  135. {
  136. // convert from centidegrees on public interface to radians
  137. float yaw_rate_bf_rads = radians(yaw_rate_bf_cds * 0.01f);
  138. // store roll, pitch and passthroughs
  139. // NOTE: this abuses yaw_rate_bf_rads
  140. _passthrough_roll = roll_passthrough;
  141. _passthrough_pitch = pitch_passthrough;
  142. _passthrough_yaw = degrees(yaw_rate_bf_rads) * 100.0f;
  143. // set rate controller to use pass through
  144. _flags_heli.flybar_passthrough = true;
  145. // set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
  146. _attitude_target_ang_vel.x = _ahrs.get_gyro().x;
  147. _attitude_target_ang_vel.y = _ahrs.get_gyro().y;
  148. // accel limit desired yaw rate
  149. if (get_accel_yaw_max_radss() > 0.0f) {
  150. float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt;
  151. float rate_change_rads = yaw_rate_bf_rads - _attitude_target_ang_vel.z;
  152. rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
  153. _attitude_target_ang_vel.z += rate_change_rads;
  154. } else {
  155. _attitude_target_ang_vel.z = yaw_rate_bf_rads;
  156. }
  157. integrate_bf_rate_error_to_angle_errors();
  158. _att_error_rot_vec_rad.x = 0;
  159. _att_error_rot_vec_rad.y = 0;
  160. // update our earth-frame angle targets
  161. Vector3f att_error_euler_rad;
  162. // convert angle error rotation vector into 321-intrinsic euler angle difference
  163. // NOTE: this results an an approximation linearized about the vehicle's attitude
  164. if (ang_vel_to_euler_rate(Vector3f(_ahrs.roll, _ahrs.pitch, _ahrs.yaw), _att_error_rot_vec_rad, att_error_euler_rad)) {
  165. _attitude_target_euler_angle.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);
  166. _attitude_target_euler_angle.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);
  167. _attitude_target_euler_angle.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);
  168. }
  169. // handle flipping over pitch axis
  170. if (_attitude_target_euler_angle.y > M_PI / 2.0f) {
  171. _attitude_target_euler_angle.x = wrap_PI(_attitude_target_euler_angle.x + M_PI);
  172. _attitude_target_euler_angle.y = wrap_PI(M_PI - _attitude_target_euler_angle.x);
  173. _attitude_target_euler_angle.z = wrap_2PI(_attitude_target_euler_angle.z + M_PI);
  174. }
  175. if (_attitude_target_euler_angle.y < -M_PI / 2.0f) {
  176. _attitude_target_euler_angle.x = wrap_PI(_attitude_target_euler_angle.x + M_PI);
  177. _attitude_target_euler_angle.y = wrap_PI(-M_PI - _attitude_target_euler_angle.x);
  178. _attitude_target_euler_angle.z = wrap_2PI(_attitude_target_euler_angle.z + M_PI);
  179. }
  180. // convert body-frame angle errors to body-frame rate targets
  181. _rate_target_ang_vel = update_ang_vel_target_from_att_error(_att_error_rot_vec_rad);
  182. // set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
  183. _rate_target_ang_vel.x = _attitude_target_ang_vel.x;
  184. _rate_target_ang_vel.y = _attitude_target_ang_vel.y;
  185. // add desired target to yaw
  186. _rate_target_ang_vel.z += _attitude_target_ang_vel.z;
  187. _thrust_error_angle = norm(_att_error_rot_vec_rad.x, _att_error_rot_vec_rad.y);
  188. }
  189. void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()
  190. {
  191. // Integrate the angular velocity error into the attitude error
  192. _att_error_rot_vec_rad += (_attitude_target_ang_vel - _ahrs.get_gyro()) * _dt;
  193. // Constrain attitude error
  194. _att_error_rot_vec_rad.x = constrain_float(_att_error_rot_vec_rad.x, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
  195. _att_error_rot_vec_rad.y = constrain_float(_att_error_rot_vec_rad.y, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
  196. _att_error_rot_vec_rad.z = constrain_float(_att_error_rot_vec_rad.z, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
  197. }
  198. // subclass non-passthrough too, for external gyro, no flybar
  199. void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
  200. {
  201. _passthrough_yaw = yaw_rate_bf_cds;
  202. AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
  203. }
  204. //
  205. // rate controller (body-frame) methods
  206. //
  207. // rate_controller_run - run lowest level rate controller and send outputs to the motors
  208. // should be called at 100hz or more
  209. void AC_AttitudeControl_Heli::rate_controller_run()
  210. {
  211. Vector3f gyro_latest = _ahrs.get_gyro_latest();
  212. // call rate controllers and send output to motors object
  213. // if using a flybar passthrough roll and pitch directly to motors
  214. if (_flags_heli.flybar_passthrough) {
  215. _motors.set_roll(_passthrough_roll / 4500.0f);
  216. _motors.set_pitch(_passthrough_pitch / 4500.0f);
  217. } else {
  218. rate_bf_to_motor_roll_pitch(gyro_latest, _rate_target_ang_vel.x, _rate_target_ang_vel.y);
  219. }
  220. if (_flags_heli.tail_passthrough) {
  221. _motors.set_yaw(_passthrough_yaw / 4500.0f);
  222. } else {
  223. _motors.set_yaw(rate_target_to_motor_yaw(gyro_latest.z, _rate_target_ang_vel.z));
  224. }
  225. }
  226. // Update Alt_Hold angle maximum
  227. void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
  228. {
  229. float althold_lean_angle_max = acosf(constrain_float(_throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
  230. _althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
  231. }
  232. //
  233. // private methods
  234. //
  235. //
  236. // body-frame rate controller
  237. //
  238. // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
  239. void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
  240. {
  241. if (_flags_heli.leaky_i) {
  242. _pid_rate_roll.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
  243. }
  244. float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _flags_heli.limit_roll);
  245. if (_flags_heli.leaky_i) {
  246. _pid_rate_pitch.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
  247. }
  248. float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _flags_heli.limit_pitch);
  249. // use pid library to calculate ff
  250. float roll_ff = _pid_rate_roll.get_ff();
  251. float pitch_ff = _pid_rate_pitch.get_ff();
  252. // add feed forward and final output
  253. float roll_out = roll_pid + roll_ff;
  254. float pitch_out = pitch_pid + pitch_ff;
  255. // constrain output and update limit flags
  256. if (fabsf(roll_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
  257. roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
  258. _flags_heli.limit_roll = true;
  259. } else {
  260. _flags_heli.limit_roll = false;
  261. }
  262. if (fabsf(pitch_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
  263. pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
  264. _flags_heli.limit_pitch = true;
  265. } else {
  266. _flags_heli.limit_pitch = false;
  267. }
  268. // output to motors
  269. _motors.set_roll(roll_out);
  270. _motors.set_pitch(pitch_out);
  271. // Piro-Comp, or Pirouette Compensation is a pre-compensation calculation, which basically rotates the Roll and Pitch Rate I-terms as the
  272. // helicopter rotates in yaw. Much of the built-up I-term is needed to tip the disk into the incoming wind. Fast yawing can create an instability
  273. // as the built-up I-term in one axis must be reduced, while the other increases. This helps solve that by rotating the I-terms before the error occurs.
  274. // It does assume that the rotor aerodynamics and mechanics are essentially symmetrical about the main shaft, which is a generally valid assumption.
  275. if (_piro_comp_enabled) {
  276. // used to hold current I-terms while doing piro comp:
  277. const float piro_roll_i = _pid_rate_roll.get_i();
  278. const float piro_pitch_i = _pid_rate_pitch.get_i();
  279. Vector2f yawratevector;
  280. yawratevector.x = cosf(-rate_rads.z * _dt);
  281. yawratevector.y = sinf(-rate_rads.z * _dt);
  282. yawratevector.normalize();
  283. _pid_rate_roll.set_integrator(piro_roll_i * yawratevector.x - piro_pitch_i * yawratevector.y);
  284. _pid_rate_pitch.set_integrator(piro_pitch_i * yawratevector.x + piro_roll_i * yawratevector.y);
  285. }
  286. }
  287. // rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
  288. float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_target_rads)
  289. {
  290. if (!((AP_MotorsHeli&)_motors).rotor_runup_complete()) {
  291. _pid_rate_yaw.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
  292. }
  293. float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _flags_heli.limit_yaw);
  294. // use pid library to calculate ff
  295. float vff = _pid_rate_yaw.get_ff();
  296. // add feed forward
  297. float yaw_out = pid + vff;
  298. // constrain output and update limit flag
  299. if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
  300. yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
  301. _flags_heli.limit_yaw = true;
  302. } else {
  303. _flags_heli.limit_yaw = false;
  304. }
  305. // output to motors
  306. return yaw_out;
  307. }
  308. //
  309. // throttle functions
  310. //
  311. void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
  312. {
  313. _throttle_in = throttle_in;
  314. update_althold_lean_angle_max(throttle_in);
  315. _motors.set_throttle_filter_cutoff(filter_cutoff);
  316. _motors.set_throttle(throttle_in);
  317. // Clear angle_boost for logging purposes
  318. _angle_boost = 0.0f;
  319. }
  320. // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
  321. void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
  322. {
  323. if (_inverted_flight) {
  324. euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
  325. }
  326. AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
  327. }
  328. // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
  329. void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
  330. {
  331. if (_inverted_flight) {
  332. euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
  333. }
  334. AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);
  335. }