AC_AttitudeControl.cpp 64 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224
  1. #include "AC_AttitudeControl.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. extern const AP_HAL::HAL& hal;
  4. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  5. // default gains for Plane
  6. # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft
  7. #else
  8. // default gains for Copter and Sub
  9. # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium
  10. #endif
  11. // table of user settable parameters
  12. const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
  13. // 0, 1 were RATE_RP_MAX, RATE_Y_MAX
  14. // @Param: SLEW_YAW
  15. // @DisplayName: Yaw target slew rate
  16. // @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
  17. // @Units: cdeg/s
  18. // @Range: 500 18000
  19. // @Increment: 100
  20. // @User: Advanced
  21. AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS),
  22. // 3 was for ACCEL_RP_MAX
  23. // @Param: ACCEL_Y_MAX
  24. // @DisplayName: Acceleration Max for Yaw
  25. // @Description: Maximum acceleration in yaw axis
  26. // @Units: cdeg/s/s
  27. // @Range: 0 72000
  28. // @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast
  29. // @Increment: 1000
  30. // @User: Advanced
  31. AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS),
  32. // @Param: RATE_FF_ENAB
  33. // @DisplayName: Rate Feedforward Enable
  34. // @Description: Controls whether body-frame rate feedfoward is enabled or disabled
  35. // @Values: 0:Disabled, 1:Enabled
  36. // @User: Advanced
  37. AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),
  38. // @Param: ACCEL_R_MAX
  39. // @DisplayName: Acceleration Max for Roll
  40. // @Description: Maximum acceleration in roll axis
  41. // @Units: cdeg/s/s
  42. // @Range: 0 180000
  43. // @Increment: 1000
  44. // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
  45. // @User: Advanced
  46. AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
  47. // @Param: ACCEL_P_MAX
  48. // @DisplayName: Acceleration Max for Pitch
  49. // @Description: Maximum acceleration in pitch axis
  50. // @Units: cdeg/s/s
  51. // @Range: 0 180000
  52. // @Increment: 1000
  53. // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast
  54. // @User: Advanced
  55. AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),
  56. // IDs 8,9,10,11 RESERVED (in use on Solo)
  57. // @Param: ANGLE_BOOST
  58. // @DisplayName: Angle Boost
  59. // @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
  60. // @Values: 0:Disabled, 1:Enabled
  61. // @User: Advanced
  62. AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),
  63. // @Param: ANG_RLL_P
  64. // @DisplayName: Roll axis angle controller P gain
  65. // @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
  66. // @Range: 3.000 12.000
  67. // @Range{Sub}: 0.0 12.000
  68. // @User: Standard
  69. AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),
  70. // @Param: ANG_PIT_P
  71. // @DisplayName: Pitch axis angle controller P gain
  72. // @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
  73. // @Range: 3.000 12.000
  74. // @Range{Sub}: 0.0 12.000
  75. // @User: Standard
  76. AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),
  77. // @Param: ANG_YAW_P
  78. // @DisplayName: Yaw axis angle controller P gain
  79. // @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
  80. // @Range: 3.000 6.000
  81. // @Range{Sub}: 0.0 6.000
  82. // @User: Standard
  83. AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),
  84. // @Param: ANG_LIM_TC
  85. // @DisplayName: Angle Limit (to maintain altitude) Time Constant
  86. // @Description: Angle Limit (to maintain altitude) Time Constant
  87. // @Range: 0.5 10.0
  88. // @User: Advanced
  89. AP_GROUPINFO("ANG_LIM_TC", 16, AC_AttitudeControl, _angle_limit_tc, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT),
  90. // @Param: RATE_R_MAX
  91. // @DisplayName: Angular Velocity Max for Roll
  92. // @Description: Maximum angular velocity in roll axis
  93. // @Units: deg/s
  94. // @Range: 0 1080
  95. // @Increment: 1
  96. // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
  97. // @User: Advanced
  98. AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max, 0.0f),
  99. // @Param: RATE_P_MAX
  100. // @DisplayName: Angular Velocity Max for Pitch
  101. // @Description: Maximum angular velocity in pitch axis
  102. // @Units: deg/s
  103. // @Range: 0 1080
  104. // @Increment: 1
  105. // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
  106. // @User: Advanced
  107. AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f),
  108. // @Param: RATE_Y_MAX
  109. // @DisplayName: Angular Velocity Max for Yaw
  110. // @Description: Maximum angular velocity in yaw axis
  111. // @Units: deg/s
  112. // @Range: 0 1080
  113. // @Increment: 1
  114. // @Values: 0:Disabled, 360:Slow, 720:Medium, 1080:Fast
  115. // @User: Advanced
  116. AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max, 0.0f),
  117. // @Param: INPUT_TC
  118. // @DisplayName: Attitude control input time constant
  119. // @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
  120. // @Units: s
  121. // @Range: 0 1
  122. // @Increment: 0.01
  123. // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
  124. // @User: Standard
  125. AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT),
  126. AP_GROUPEND
  127. };
  128. // Ensure attitude controller have zero errors to relax rate controller output
  129. void AC_AttitudeControl::relax_attitude_controllers()
  130. {
  131. // Initialize the attitude variables to the current attitude
  132. _ahrs.get_quat_body_to_ned(_attitude_target_quat);
  133. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  134. _attitude_ang_error.initialise();
  135. // Initialize the angular rate variables to the current rate
  136. _attitude_target_ang_vel = _ahrs.get_gyro();
  137. ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  138. _rate_target_ang_vel = _ahrs.get_gyro();
  139. // Initialize remaining variables
  140. _thrust_error_angle = 0.0f;
  141. // Reset the PID filters
  142. get_rate_roll_pid().reset_filter();
  143. get_rate_pitch_pid().reset_filter();
  144. get_rate_yaw_pid().reset_filter();
  145. // Reset the I terms
  146. reset_rate_controller_I_terms();
  147. }
  148. void AC_AttitudeControl::reset_rate_controller_I_terms()
  149. {
  150. get_rate_roll_pid().reset_I();
  151. get_rate_pitch_pid().reset_I();
  152. get_rate_yaw_pid().reset_I();
  153. }
  154. // The attitude controller works around the concept of the desired attitude, target attitude
  155. // and measured attitude. The desired attitude is the attitude input into the attitude controller
  156. // that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
  157. // to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed
  158. // directly into the rate controllers. The angular error between the measured attitude and the target attitude is
  159. // fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.
  160. // By feeding the target angular velocity directly into the rate controllers the measured and target attitudes
  161. // remain very close together.
  162. //
  163. // All input functions below follow the same procedure
  164. // 1. define the desired attitude the aircraft should attempt to achieve using the input variables
  165. // 2. using the desired attitude and input variables, define the target angular velocity so that it should
  166. // move the target attitude towards the desired attitude
  167. // 3. if _rate_bf_ff_enabled is not being used then make the target attitude
  168. // and target angular velocities equal to the desired attitude and desired angular velocities.
  169. // 4. ensure _attitude_target_quat, _attitude_target_euler_angle, _attitude_target_euler_rate and
  170. // _attitude_target_ang_vel have been defined. This ensures input modes can be changed without discontinuity.
  171. // 5. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and
  172. // integrate them into the target attitude. Any errors between the target attitude and the measured attitude are
  173. // corrected by first correcting the thrust vector until the angle between the target thrust vector measured
  174. // trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected.
  175. // Command a Quaternion attitude with feedforward and smoothing
  176. void AC_AttitudeControl::input_quaternion(Quaternion attitude_desired_quat)
  177. {
  178. // calculate the attitude target euler angles
  179. // _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  180. Quaternion attitude_error_quat = _attitude_target_quat.inverse() * attitude_desired_quat;//Q(n)(tb)的转置 *Q(n)(tbnew) = Q(tb)(tbnew),attitude_error_quat在tb坐标下
  181. Vector3f attitude_error_angle;
  182. attitude_error_quat.to_axis_angle(attitude_error_angle);
  183. if (_rate_bf_ff_enabled) {
  184. // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
  185. // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
  186. // and an exponential decay specified by _input_tc at the end.
  187. _attitude_target_ang_vel.x = input_shaping_angle(wrap_PI(attitude_error_angle.x), _input_tc, get_accel_roll_max_radss(), _attitude_target_ang_vel.x, _dt);
  188. _attitude_target_ang_vel.y = input_shaping_angle(wrap_PI(attitude_error_angle.y), _input_tc, get_accel_pitch_max_radss(), _attitude_target_ang_vel.y, _dt);
  189. _attitude_target_ang_vel.z = input_shaping_angle(wrap_PI(attitude_error_angle.z), _input_tc, get_accel_yaw_max_radss(), _attitude_target_ang_vel.z, _dt);
  190. //_attitude_target_ang_vel在tb系下
  191. // Limit the angular velocity
  192. ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
  193. // Convert body-frame angular velocity into euler angle derivative of desired attitude
  194. //_attitude_target_ang_vel 表示arget坐标系下的速度 以下这里没用
  195. //ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  196. } else {
  197. _attitude_target_quat = attitude_desired_quat;
  198. // Set rate feedforward requests to zero
  199. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  200. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  201. }
  202. // Call quaternion attitude controller
  203. attitude_controller_run_quat();
  204. }
  205. // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
  206. void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
  207. {
  208. // Convert from centidegrees on public interface to radians
  209. float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
  210. float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
  211. float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);
  212. // calculate the attitude target euler angles
  213. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  214. // Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
  215. euler_roll_angle += get_roll_trim_rad();
  216. if (_rate_bf_ff_enabled) {
  217. // translate the roll pitch and yaw acceleration limits to the euler axis
  218. Vector3f euler_accel = euler_accel_limit(_attitude_target_euler_angle, Vector3f(get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()));
  219. // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
  220. // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
  221. // and an exponential decay specified by smoothing_gain at the end.
  222. _attitude_target_euler_rate.x = input_shaping_angle(wrap_PI(euler_roll_angle - _attitude_target_euler_angle.x), _input_tc, euler_accel.x, _attitude_target_euler_rate.x, _dt);
  223. _attitude_target_euler_rate.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _attitude_target_euler_angle.y), _input_tc, euler_accel.y, _attitude_target_euler_rate.y, _dt);
  224. // When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
  225. // the output rate towards the input rate.
  226. _attitude_target_euler_rate.z = input_shaping_ang_vel(_attitude_target_euler_rate.z, euler_yaw_rate, euler_accel.z, _dt);
  227. // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
  228. euler_rate_to_ang_vel(_attitude_target_euler_angle, _attitude_target_euler_rate, _attitude_target_ang_vel);
  229. // Limit the angular velocity
  230. ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
  231. // Convert body-frame angular velocity into euler angle derivative of desired attitude
  232. ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  233. } else {
  234. // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
  235. _attitude_target_euler_angle.x = euler_roll_angle;
  236. _attitude_target_euler_angle.y = euler_pitch_angle;
  237. _attitude_target_euler_angle.z += euler_yaw_rate * _dt;
  238. // Compute quaternion target attitude
  239. _attitude_target_quat.from_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  240. // Set rate feedforward requests to zero
  241. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  242. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  243. }
  244. // Call quaternion attitude controller
  245. attitude_controller_run_quat();
  246. }
  247. void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw_quat_control(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
  248. {
  249. float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
  250. float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
  251. float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f);
  252. //
  253. Quaternion input_quat;
  254. input_quat.from_euler(euler_roll_angle,euler_pitch_angle,euler_yaw_angle);//输入得欧拉角转换的4元数 e - b
  255. input_quat.normalize();//归一化
  256. /*static int i = 0;
  257. i++;
  258. if (i>500)
  259. {
  260. i=0;
  261. gcs().send_text(MAV_SEVERITY_INFO, "Qmatrix_1_1 %f %f %f %f",Qmatrix_1.a.M0,Qmatrix_1.a.M1,Qmatrix_1.a.M2,Qmatrix_1.a.M3);
  262. gcs().send_text(MAV_SEVERITY_INFO, "Qmatrix_1_2 %f %f %f %f",Qmatrix_1.b.M0,Qmatrix_1.b.M1,Qmatrix_1.b.M2,Qmatrix_1.b.M3);
  263. gcs().send_text(MAV_SEVERITY_INFO, "Qmatrix_1_3 %f %f %f %f",Qmatrix_1.c.M0,Qmatrix_1.c.M1,Qmatrix_1.c.M2,Qmatrix_1.c.M3);
  264. gcs().send_text(MAV_SEVERITY_INFO, "Qmatrix_1_4 %f %f %f %f",Qmatrix_1.d.M0,Qmatrix_1.d.M1,Qmatrix_1.d.M2,Qmatrix_1.d.M3);
  265. }*/
  266. if (_rate_bf_ff_enabled) {
  267. //方案1--------------------------------
  268. //q' = 1/2*Q*W
  269. //q(t+dt)-q(t) = 1/2*Q*W*dt
  270. //2*Q(-1)*(q(t+dt)-q(t)) = w*dt
  271. //W = [0,Wx,Wy,Wz]得到机体三轴速度 在期望机体坐标系
  272. /*Matrix4f Qmatrix(_attitude_target_quat.q1, -_attitude_target_quat.q2, -_attitude_target_quat.q3, -_attitude_target_quat.q4,
  273. _attitude_target_quat.q2, _attitude_target_quat.q1, -_attitude_target_quat.q4, _attitude_target_quat.q3,
  274. _attitude_target_quat.q3, _attitude_target_quat.q4, _attitude_target_quat.q1, -_attitude_target_quat.q2,
  275. _attitude_target_quat.q4, -_attitude_target_quat.q3, _attitude_target_quat.q2, _attitude_target_quat.q1);
  276. Matrix4f Qmatrix_1;
  277. Qmatrix.inverse(Qmatrix_1);
  278. Quaternion error_quat = input_quat - _attitude_target_quat;
  279. Vector4f error_vec(error_quat.q1,error_quat.q2,error_quat.q3,error_quat.q4);
  280. Vector4f w4 = Qmatrix_1*error_vec;
  281. Vector3f error_angle3(2*w4.M1,2*w4.M2,2*w4.M3);*/
  282. //方案2------------------------------
  283. //Q' = 1/2*W*Q 齐次方程的通解Q(k+1) = e(1/2*A*dt) * Q(k) (1/2*A*dt) 上标 ,
  284. //根据2阶泰勒展开 近似计算,经过化简
  285. //如下计算 error_angle.M0 =1-(M1^2+M2^2+M3^2)/8 这里是近似值
  286. Matrix4f Qmatrix(_attitude_target_quat.q1,-0.5*_attitude_target_quat.q2,-0.5*_attitude_target_quat.q3, -0.5*_attitude_target_quat.q4,
  287. _attitude_target_quat.q2,0.5*_attitude_target_quat.q1,-0.5*_attitude_target_quat.q4, 0.5*_attitude_target_quat.q3,
  288. _attitude_target_quat.q3,0.5*_attitude_target_quat.q4, 0.5*_attitude_target_quat.q1, -0.5*_attitude_target_quat.q2,
  289. _attitude_target_quat.q4,-0.5*_attitude_target_quat.q3, 0.5*_attitude_target_quat.q2, 0.5*_attitude_target_quat.q1);
  290. Matrix4f Qmatrix_1;
  291. Vector4f error_angle;
  292. Qmatrix.inverse(Qmatrix_1);
  293. Vector4f _attitude_target_vec(input_quat.q1,input_quat.q2,input_quat.q3,input_quat.q4);
  294. error_angle = Qmatrix_1*_attitude_target_vec;
  295. //Vector3f error_angle3(error_angle.M1,error_angle.M2,error_angle.M3);//wrap_PI
  296. Vector3f error_angle3(wrap_PI(error_angle.M1),wrap_PI(error_angle.M2),wrap_PI(error_angle.M3));
  297. //限幅
  298. //注意这里的限幅原来的定义都是对应对地的 不是对机体坐标系的,这里直接拿来用了
  299. //从角度误差计算角速度
  300. _attitude_target_ang_vel.x = input_shaping_angle(error_angle3.x, _input_tc, get_accel_roll_max_radss(), _attitude_target_ang_vel.x, _dt);
  301. _attitude_target_ang_vel.y = input_shaping_angle(error_angle3.y, _input_tc, get_accel_pitch_max_radss(), _attitude_target_ang_vel.y, _dt);
  302. _attitude_target_ang_vel.z = input_shaping_angle(error_angle3.z, _input_tc, get_accel_yaw_max_radss(), _attitude_target_ang_vel.z, _dt);
  303. if (slew_yaw) {
  304. _attitude_target_ang_vel.z = constrain_float(_attitude_target_ang_vel.z, -get_slew_yaw_rads(), get_slew_yaw_rads());
  305. }
  306. ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
  307. }else {
  308. if (slew_yaw){
  309. float angle_error = constrain_float(wrap_PI(euler_yaw_angle - _ahrs.yaw), -get_slew_yaw_rads() * _dt, get_slew_yaw_rads() * _dt);
  310. euler_yaw_angle = _ahrs.yaw + angle_error;
  311. }
  312. _attitude_target_quat.from_euler(euler_roll_angle, euler_pitch_angle, euler_yaw_angle);
  313. // Set rate feedforward requests to zero
  314. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  315. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  316. }
  317. attitude_controller_run_quat();
  318. }
  319. // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
  320. void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
  321. {
  322. // Convert from centidegrees on public interface to radians
  323. float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
  324. float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
  325. float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f);
  326. // calculate the attitude target euler angles
  327. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  328. // Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
  329. euler_roll_angle += get_roll_trim_rad();
  330. if (_rate_bf_ff_enabled) {
  331. // translate the roll pitch and yaw acceleration limits to the euler axis
  332. Vector3f euler_accel = euler_accel_limit(_attitude_target_euler_angle, Vector3f(get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()));
  333. // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
  334. // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
  335. // and an exponential decay specified by _input_tc at the end.
  336. _attitude_target_euler_rate.x = input_shaping_angle(wrap_PI(euler_roll_angle - _attitude_target_euler_angle.x), _input_tc, euler_accel.x, _attitude_target_euler_rate.x, _dt);
  337. _attitude_target_euler_rate.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _attitude_target_euler_angle.y), _input_tc, euler_accel.y, _attitude_target_euler_rate.y, _dt);
  338. _attitude_target_euler_rate.z = input_shaping_angle(wrap_PI(euler_yaw_angle - _attitude_target_euler_angle.z), _input_tc, euler_accel.z, _attitude_target_euler_rate.z, _dt);
  339. if (slew_yaw) {
  340. _attitude_target_euler_rate.z = constrain_float(_attitude_target_euler_rate.z, -get_slew_yaw_rads(), get_slew_yaw_rads());
  341. }
  342. // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
  343. euler_rate_to_ang_vel(_attitude_target_euler_angle, _attitude_target_euler_rate, _attitude_target_ang_vel);
  344. // Limit the angular velocity
  345. ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
  346. // Convert body-frame angular velocity into euler angle derivative of desired attitude
  347. ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  348. } else {
  349. // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
  350. _attitude_target_euler_angle.x = euler_roll_angle;
  351. _attitude_target_euler_angle.y = euler_pitch_angle;
  352. if (slew_yaw) {
  353. // Compute constrained angle error
  354. float angle_error = constrain_float(wrap_PI(euler_yaw_angle - _attitude_target_euler_angle.z), -get_slew_yaw_rads() * _dt, get_slew_yaw_rads() * _dt);
  355. // Update attitude target from constrained angle error
  356. _attitude_target_euler_angle.z = wrap_PI(angle_error + _attitude_target_euler_angle.z);
  357. } else {
  358. _attitude_target_euler_angle.z = euler_yaw_angle;
  359. }
  360. // Compute quaternion target attitude
  361. _attitude_target_quat.from_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  362. // Set rate feedforward requests to zero
  363. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  364. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  365. }
  366. // Call quaternion attitude controller
  367. attitude_controller_run_quat();
  368. }
  369. // Command euler pitch and yaw angles and roll rate (used only by tailsitter quadplanes)
  370. // Multicopter style controls: roll stick is tailsitter bodyframe yaw in hover
  371. void AC_AttitudeControl::input_euler_rate_yaw_euler_angle_pitch_bf_roll_m(float euler_yaw_rate_cds, float euler_pitch_cd, float body_roll_cd)
  372. {
  373. // Convert from centidegrees on public interface to radians
  374. float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
  375. float euler_pitch = radians(constrain_float(euler_pitch_cd * 0.01f, -90.0f, 90.0f));
  376. float body_roll = radians(constrain_float(body_roll_cd * 0.01f, -90.0f, 90.0f));
  377. // Compute attitude error
  378. Quaternion attitude_vehicle_quat;
  379. Quaternion error_quat;
  380. attitude_vehicle_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned());
  381. error_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  382. Vector3f att_error;
  383. error_quat.to_axis_angle(att_error);
  384. // limit yaw error
  385. if (fabsf(att_error.z) < AC_ATTITUDE_THRUST_ERROR_ANGLE) {
  386. // update heading
  387. _attitude_target_euler_angle.z = wrap_PI(_attitude_target_euler_angle.z + euler_yaw_rate * _dt);
  388. }
  389. // init attitude target to desired euler yaw and pitch with zero roll
  390. _attitude_target_quat.from_euler(0, euler_pitch, _attitude_target_euler_angle.z);
  391. const float cpitch = cosf(euler_pitch);
  392. const float spitch = fabsf(sinf(euler_pitch));
  393. // apply body-frame yaw/roll (this is roll/yaw for a tailsitter in forward flight)
  394. // rotate body_roll axis by |sin(pitch angle)|
  395. Quaternion bf_roll_Q;
  396. bf_roll_Q.from_axis_angle(Vector3f(0, 0, spitch * body_roll));
  397. // rotate body_yaw axis by cos(pitch angle)
  398. Quaternion bf_yaw_Q;
  399. bf_yaw_Q.from_axis_angle(Vector3f(-cpitch * body_roll, 0, 0));
  400. _attitude_target_quat = _attitude_target_quat * bf_roll_Q * bf_yaw_Q;
  401. // _attitude_target_euler_angle roll and pitch: Note: roll/yaw will be indeterminate when pitch is near +/-90
  402. // These should be used only for logging target eulers, with the caveat noted above.
  403. // Also note that _attitude_target_quat.from_euler() should only be used in special circumstances
  404. // such as when attitude is specified directly in terms of Euler angles.
  405. // _attitude_target_euler_angle.x = _attitude_target_quat.get_euler_roll();
  406. // _attitude_target_euler_angle.y = euler_pitch;
  407. // Set rate feedforward requests to zero
  408. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  409. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  410. // Compute attitude error
  411. error_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  412. error_quat.to_axis_angle(att_error);
  413. // Compute the angular velocity target from the attitude error
  414. _rate_target_ang_vel = update_ang_vel_target_from_att_error(att_error);
  415. }
  416. // Command euler pitch and yaw angles and roll rate (used only by tailsitter quadplanes)
  417. // Plane style controls: yaw stick is tailsitter bodyframe yaw in hover
  418. void AC_AttitudeControl::input_euler_rate_yaw_euler_angle_pitch_bf_roll_p(float euler_yaw_rate_cds, float euler_pitch_cd, float body_roll_cd)
  419. {
  420. // Convert from centidegrees on public interface to radians
  421. float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
  422. float euler_pitch = radians(constrain_float(euler_pitch_cd * 0.01f, -90.0f, 90.0f));
  423. float body_roll = radians(constrain_float(body_roll_cd * 0.01f, -90.0f, 90.0f));
  424. const float cpitch = cosf(euler_pitch);
  425. const float spitch = fabsf(sinf(euler_pitch));
  426. // Compute attitude error
  427. Quaternion attitude_vehicle_quat;
  428. Quaternion error_quat;
  429. attitude_vehicle_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned());
  430. error_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  431. Vector3f att_error;
  432. error_quat.to_axis_angle(att_error);
  433. // limit yaw error
  434. if (fabsf(att_error.z) < AC_ATTITUDE_THRUST_ERROR_ANGLE) {
  435. // update heading
  436. float yaw_rate = euler_yaw_rate * spitch + body_roll * cpitch;
  437. _attitude_target_euler_angle.z = wrap_PI(_attitude_target_euler_angle.z + yaw_rate * _dt);
  438. }
  439. // init attitude target to desired euler yaw and pitch with zero roll
  440. _attitude_target_quat.from_euler(0, euler_pitch, _attitude_target_euler_angle.z);
  441. // apply body-frame yaw/roll (this is roll/yaw for a tailsitter in forward flight)
  442. // rotate body_roll axis by |sin(pitch angle)|
  443. Quaternion bf_roll_Q;
  444. bf_roll_Q.from_axis_angle(Vector3f(0, 0, spitch * body_roll));
  445. // rotate body_yaw axis by cos(pitch angle)
  446. Quaternion bf_yaw_Q;
  447. bf_yaw_Q.from_axis_angle(Vector3f(cpitch, 0, 0), euler_yaw_rate);
  448. _attitude_target_quat = _attitude_target_quat * bf_roll_Q * bf_yaw_Q;
  449. // _attitude_target_euler_angle roll and pitch: Note: roll/yaw will be indeterminate when pitch is near +/-90
  450. // These should be used only for logging target eulers, with the caveat noted above
  451. // Also note that _attitude_target_quat.from_euler() should only be used in special circumstances
  452. // such as when attitude is specified directly in terms of Euler angles.
  453. // _attitude_target_euler_angle.x = _attitude_target_quat.get_euler_roll();
  454. // _attitude_target_euler_angle.y = euler_pitch;
  455. // Set rate feedforward requests to zero
  456. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  457. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  458. // Compute attitude error
  459. error_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  460. error_quat.to_axis_angle(att_error);
  461. // Compute the angular velocity target from the attitude error
  462. _rate_target_ang_vel = update_ang_vel_target_from_att_error(att_error);
  463. }
  464. // Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
  465. void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
  466. {
  467. // Convert from centidegrees on public interface to radians
  468. float euler_roll_rate = radians(euler_roll_rate_cds * 0.01f);
  469. float euler_pitch_rate = radians(euler_pitch_rate_cds * 0.01f);
  470. float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);
  471. // calculate the attitude target euler angles
  472. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  473. if (_rate_bf_ff_enabled) {
  474. // translate the roll pitch and yaw acceleration limits to the euler axis
  475. Vector3f euler_accel = euler_accel_limit(_attitude_target_euler_angle, Vector3f(get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()));
  476. // When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing
  477. // the output rate towards the input rate.
  478. _attitude_target_euler_rate.x = input_shaping_ang_vel(_attitude_target_euler_rate.x, euler_roll_rate, euler_accel.x, _dt);
  479. _attitude_target_euler_rate.y = input_shaping_ang_vel(_attitude_target_euler_rate.y, euler_pitch_rate, euler_accel.y, _dt);
  480. _attitude_target_euler_rate.z = input_shaping_ang_vel(_attitude_target_euler_rate.z, euler_yaw_rate, euler_accel.z, _dt);
  481. // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
  482. euler_rate_to_ang_vel(_attitude_target_euler_angle, _attitude_target_euler_rate, _attitude_target_ang_vel);
  483. } else {
  484. // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
  485. // Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities.
  486. _attitude_target_euler_angle.x = wrap_PI(_attitude_target_euler_angle.x + euler_roll_rate * _dt);
  487. _attitude_target_euler_angle.y = constrain_float(_attitude_target_euler_angle.y + euler_pitch_rate * _dt, radians(-85.0f), radians(85.0f));
  488. _attitude_target_euler_angle.z = wrap_2PI(_attitude_target_euler_angle.z + euler_yaw_rate * _dt);
  489. // Set rate feedforward requests to zero
  490. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  491. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  492. // Compute quaternion target attitude
  493. _attitude_target_quat.from_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  494. }
  495. // Call quaternion attitude controller
  496. attitude_controller_run_quat();
  497. }
  498. // Command an angular velocity with angular velocity feedforward and smoothing
  499. void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
  500. {
  501. // Convert from centidegrees on public interface to radians
  502. float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
  503. float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
  504. float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
  505. //要先将roll_rate_rads,pitch_rate_rads,yaw_rate_rads转化到tb坐标系,原来是在N系-------wangdan
  506. Quaternion _ang_vel_quat = Quaternion(0.0f, 0.0f,0.0f, yaw_rate_rads);//手柄输出四元数 这样可以使得转向围绕的是地球坐标系
  507. Quaternion thrust_vec_quat_body;
  508. thrust_vec_quat_body = _attitude_target_quat.inverse() * _ang_vel_quat * _attitude_target_quat;//手柄转换到tb系
  509. //-----------------------------------------------------------------------------------------------------------------------
  510. // calculate the attitude target euler angles
  511. //_attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  512. if (_rate_bf_ff_enabled) {
  513. // Compute acceleration-limited body frame rates
  514. // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
  515. // the output rate towards the input rate.
  516. /*_attitude_target_ang_vel.x = input_shaping_ang_vel(_attitude_target_ang_vel.x, roll_rate_rads, get_accel_roll_max_radss(), _dt);
  517. _attitude_target_ang_vel.y = input_shaping_ang_vel(_attitude_target_ang_vel.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt);
  518. _attitude_target_ang_vel.z = input_shaping_ang_vel(_attitude_target_ang_vel.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt);
  519. */
  520. //使用机体四元数------------wangdan--------------
  521. _attitude_target_ang_vel.x = input_shaping_ang_vel(_attitude_target_ang_vel.x, roll_rate_rads + thrust_vec_quat_body.q2, get_accel_roll_max_radss(), _dt);
  522. _attitude_target_ang_vel.y = input_shaping_ang_vel(_attitude_target_ang_vel.y, pitch_rate_rads + thrust_vec_quat_body.q3, get_accel_pitch_max_radss(), _dt);
  523. _attitude_target_ang_vel.z = input_shaping_ang_vel(_attitude_target_ang_vel.z, thrust_vec_quat_body.q4, get_accel_yaw_max_radss(), _dt);
  524. //-------------------------------------
  525. // Convert body-frame angular velocity into euler angle derivative of desired
  526. //attitude _attitude_target_ang_vel默认实在tb坐标系下
  527. //注意后面用到的是_attitude_target_ang_vel,也就是说这个函数没有作用
  528. //ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  529. } else {
  530. // When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed.
  531. Quaternion attitude_target_update_quat;
  532. attitude_target_update_quat.from_axis_angle(Vector3f(roll_rate_rads * _dt, pitch_rate_rads * _dt, yaw_rate_rads * _dt));
  533. _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
  534. _attitude_target_quat.normalize();
  535. // Set rate feedforward requests to zero
  536. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  537. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  538. }
  539. // Call quaternion attitude controller
  540. attitude_controller_run_quat();
  541. }
  542. // Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization
  543. void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
  544. {
  545. // Convert from centidegrees on public interface to radians
  546. float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
  547. float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
  548. float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
  549. // Compute acceleration-limited body frame rates
  550. // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
  551. // the output rate towards the input rate.
  552. _attitude_target_ang_vel.x = input_shaping_ang_vel(_attitude_target_ang_vel.x, roll_rate_rads, get_accel_roll_max_radss(), _dt);
  553. _attitude_target_ang_vel.y = input_shaping_ang_vel(_attitude_target_ang_vel.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt);
  554. _attitude_target_ang_vel.z = input_shaping_ang_vel(_attitude_target_ang_vel.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt);
  555. // Update the unused targets attitude based on current attitude to condition mode change
  556. _ahrs.get_quat_body_to_ned(_attitude_target_quat);
  557. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  558. // Convert body-frame angular velocity into euler angle derivative of desired attitude
  559. ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  560. _rate_target_ang_vel = _attitude_target_ang_vel;
  561. }
  562. // Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
  563. void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
  564. {
  565. // Convert from centidegrees on public interface to radians
  566. float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);
  567. float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);
  568. float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);
  569. // Update attitude error
  570. Vector3f attitude_error_vector;
  571. _attitude_ang_error.to_axis_angle(attitude_error_vector);
  572. Quaternion attitude_ang_error_update_quat;
  573. // limit the integrated error angle
  574. float err_mag = attitude_error_vector.length();
  575. if (err_mag > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
  576. attitude_error_vector *= AC_ATTITUDE_THRUST_ERROR_ANGLE / err_mag;
  577. _attitude_ang_error.from_axis_angle(attitude_error_vector);
  578. }
  579. Vector3f gyro_latest = _ahrs.get_gyro_latest();
  580. attitude_ang_error_update_quat.from_axis_angle(Vector3f((_attitude_target_ang_vel.x-gyro_latest.x) * _dt, (_attitude_target_ang_vel.y-gyro_latest.y) * _dt, (_attitude_target_ang_vel.z-gyro_latest.z) * _dt));
  581. _attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;
  582. // Compute acceleration-limited body frame rates
  583. // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
  584. // the output rate towards the input rate.
  585. _attitude_target_ang_vel.x = input_shaping_ang_vel(_attitude_target_ang_vel.x, roll_rate_rads, get_accel_roll_max_radss(), _dt);
  586. _attitude_target_ang_vel.y = input_shaping_ang_vel(_attitude_target_ang_vel.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt);
  587. _attitude_target_ang_vel.z = input_shaping_ang_vel(_attitude_target_ang_vel.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt);
  588. // Retrieve quaternion vehicle attitude
  589. Quaternion attitude_vehicle_quat;
  590. _ahrs.get_quat_body_to_ned(attitude_vehicle_quat);
  591. // Update the unused targets attitude based on current attitude to condition mode change
  592. _attitude_target_quat = attitude_vehicle_quat * _attitude_ang_error;
  593. // calculate the attitude target euler angles
  594. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  595. // Convert body-frame angular velocity into euler angle derivative of desired attitude
  596. ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
  597. // Compute the angular velocity target from the integrated rate error
  598. _attitude_ang_error.to_axis_angle(attitude_error_vector);
  599. _rate_target_ang_vel = update_ang_vel_target_from_att_error(attitude_error_vector);
  600. _rate_target_ang_vel += _attitude_target_ang_vel;
  601. // ensure Quaternions stay normalized
  602. _attitude_ang_error.normalize();
  603. }
  604. // Command an angular step (i.e change) in body frame angle
  605. // Used to command a step in angle without exciting the orthogonal axis during autotune
  606. void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(float roll_angle_step_bf_cd, float pitch_angle_step_bf_cd, float yaw_angle_step_bf_cd)
  607. {
  608. // Convert from centidegrees on public interface to radians
  609. float roll_step_rads = radians(roll_angle_step_bf_cd * 0.01f);
  610. float pitch_step_rads = radians(pitch_angle_step_bf_cd * 0.01f);
  611. float yaw_step_rads = radians(yaw_angle_step_bf_cd * 0.01f);
  612. // rotate attitude target by desired step
  613. Quaternion attitude_target_update_quat;
  614. attitude_target_update_quat.from_axis_angle(Vector3f(roll_step_rads, pitch_step_rads, yaw_step_rads));
  615. _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
  616. _attitude_target_quat.normalize();
  617. // calculate the attitude target euler angles
  618. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  619. // Set rate feedforward requests to zero
  620. _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
  621. _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
  622. // Call quaternion attitude controller
  623. attitude_controller_run_quat();
  624. }
  625. // Calculates the body frame angular velocities to follow the target attitude
  626. void AC_AttitudeControl::attitude_controller_run_quat()
  627. {
  628. // Retrieve quaternion vehicle attitude
  629. Quaternion attitude_vehicle_quat;
  630. _ahrs.get_quat_body_to_ned(attitude_vehicle_quat);
  631. // Compute attitude error
  632. Vector3f attitude_error_vector;
  633. thrust_heading_rotation_angles(_attitude_target_quat, attitude_vehicle_quat, attitude_error_vector, _thrust_error_angle);
  634. // Compute the angular velocity target from the attitude error
  635. _rate_target_ang_vel = update_ang_vel_target_from_att_error(attitude_error_vector);//rate_target_ang_vel则是在当前姿态cb下
  636. // Add feedforward term that attempts to ensure that roll and pitch errors rotate with the body frame rather than the reference frame.
  637. // todo: this should probably be a matrix that couples yaw as well.
  638. _rate_target_ang_vel.x += constrain_float(attitude_error_vector.y, -M_PI / 4, M_PI / 4) * _ahrs.get_gyro().z;
  639. _rate_target_ang_vel.y += -constrain_float(attitude_error_vector.x, -M_PI / 4, M_PI / 4) * _ahrs.get_gyro().z;
  640. ang_vel_limit(_rate_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
  641. // Add the angular velocity feedforward, rotated into vehicle frame
  642. Quaternion attitude_target_ang_vel_quat = Quaternion(0.0f, _attitude_target_ang_vel.x, _attitude_target_ang_vel.y, _attitude_target_ang_vel.z);
  643. //attitude_vehicle_quat在N系下的当前姿态 _attitude_target_quat在N系下的目标姿态 to_to_from_quat表示由目标转向当前的旋转
  644. Quaternion to_to_from_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  645. //将tb下的期望角速率旋转至cb下获取当前姿态的角速率期望前馈叠加量desired_ang_vel_quat
  646. //attitude_target_ang_vel_quat原来的的ardusub程序是在目标坐标系下
  647. Quaternion desired_ang_vel_quat = to_to_from_quat.inverse() * attitude_target_ang_vel_quat * to_to_from_quat;
  648. // Quaternion desired_ang_vel_quat = Quaternion(0.0f, _attitude_target_ang_vel.x, _attitude_target_ang_vel.y, _attitude_target_ang_vel.z);//wangdan
  649. // Correct the thrust vector and smoothly add feedforward and yaw input
  650. if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {
  651. _rate_target_ang_vel.z = _ahrs.get_gyro().z;
  652. } else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
  653. float feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);
  654. _rate_target_ang_vel.x += desired_ang_vel_quat.q2 * feedforward_scalar;
  655. _rate_target_ang_vel.y += desired_ang_vel_quat.q3 * feedforward_scalar;
  656. _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
  657. _rate_target_ang_vel.z = _ahrs.get_gyro().z * (1.0 - feedforward_scalar) + _rate_target_ang_vel.z * feedforward_scalar;
  658. } else {
  659. _rate_target_ang_vel.x += desired_ang_vel_quat.q2;
  660. _rate_target_ang_vel.y += desired_ang_vel_quat.q3;
  661. _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
  662. }
  663. if (_rate_bf_ff_enabled) {
  664. // rotate target and normalize
  665. Quaternion attitude_target_update_quat;
  666. attitude_target_update_quat.from_axis_angle(Vector3f(_attitude_target_ang_vel.x * _dt, _attitude_target_ang_vel.y * _dt, _attitude_target_ang_vel.z * _dt));
  667. _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
  668. _attitude_target_quat.normalize();
  669. }
  670. // ensure Quaternions stay normalized
  671. _attitude_target_quat.normalize();
  672. // Record error to handle EKF resets
  673. _attitude_ang_error = attitude_vehicle_quat.inverse() * _attitude_target_quat;
  674. }
  675. // thrust_heading_rotation_angles - calculates two ordered rotations to move the att_from_quat quaternion to the att_to_quat quaternion.
  676. // The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
  677. void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& att_to_quat, const Quaternion& att_from_quat, Vector3f& att_diff_angle, float& thrust_vec_dot)
  678. {
  679. Matrix3f att_to_rot_matrix; // rotation from the target body frame to the inertial frame.
  680. att_to_quat.rotation_matrix(att_to_rot_matrix);//ned坐标系
  681. Vector3f att_to_thrust_vec = att_to_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  682. Matrix3f att_from_rot_matrix; // rotation from the current body frame to the inertial frame.
  683. att_from_quat.rotation_matrix(att_from_rot_matrix);//ned坐标系
  684. Vector3f att_from_thrust_vec = att_from_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  685. // the cross product of the desired and target thrust vector defines the rotation vector
  686. Vector3f thrust_vec_cross = att_from_thrust_vec % att_to_thrust_vec;
  687. // the dot product is used to calculate the angle between the target and desired thrust vectors
  688. thrust_vec_dot = acosf(constrain_float(att_from_thrust_vec * att_to_thrust_vec, -1.0f, 1.0f));
  689. // Normalize the thrust rotation vector
  690. float thrust_vector_length = thrust_vec_cross.length();
  691. if (is_zero(thrust_vector_length) || is_zero(thrust_vec_dot)) {
  692. thrust_vec_cross = Vector3f(0, 0, 1);
  693. thrust_vec_dot = 0.0f;
  694. } else {
  695. thrust_vec_cross /= thrust_vector_length;
  696. }
  697. Quaternion thrust_vec_correction_quat;
  698. thrust_vec_correction_quat.from_axis_angle(thrust_vec_cross, thrust_vec_dot);
  699. // Rotate thrust_vec_correction_quat to the att_from frame 这个旋转其实是变换了坐标系,但是向量本身没有变
  700. thrust_vec_correction_quat = att_from_quat.inverse() * thrust_vec_correction_quat * att_from_quat;//thrust_vec_correction_quat 在ned坐标系 转换到机体坐标系
  701. // calculate the remaining rotation required after thrust vector is rotated transformed to the att_from frame
  702. Quaternion yaw_vec_correction_quat = thrust_vec_correction_quat.inverse() * att_from_quat.inverse() * att_to_quat;
  703. // calculate the angle error in x and y.
  704. Vector3f rotation;
  705. thrust_vec_correction_quat.to_axis_angle(rotation);
  706. att_diff_angle.x = rotation.x;
  707. att_diff_angle.y = rotation.y;
  708. // calculate the angle error in z (x and y should be zero here).
  709. yaw_vec_correction_quat.to_axis_angle(rotation);
  710. att_diff_angle.z = rotation.z;
  711. // Todo: Limit roll an pitch error based on output saturation and maximum error.
  712. // Limit Yaw Error based on maximum acceleration - Update to include output saturation and maximum error.
  713. // Currently the limit is based on the maximum acceleration using the linear part of the SQRT controller.
  714. // This should be updated to be based on an angle limit, saturation, or unlimited based on user defined parameters.
  715. if (!is_zero(_p_angle_yaw.kP()) && fabsf(att_diff_angle.z) > AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP()) {
  716. att_diff_angle.z = constrain_float(wrap_PI(att_diff_angle.z), -AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP(), AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP());
  717. yaw_vec_correction_quat.from_axis_angle(Vector3f(0.0f, 0.0f, att_diff_angle.z));
  718. att_to_quat = att_from_quat * thrust_vec_correction_quat * yaw_vec_correction_quat;
  719. }
  720. }
  721. // calculates the velocity correction from an angle error. The angular velocity has acceleration and
  722. // deceleration limits including basic jerk limiting using _input_tc
  723. float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float dt)
  724. {
  725. // Calculate the velocity as error approaches zero with acceleration limited by accel_max_radss
  726. float desired_ang_vel = sqrt_controller(error_angle, 1.0f / MAX(input_tc, 0.01f), accel_max, dt);
  727. // Acceleration is limited directly to smooth the beginning of the curve.
  728. return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt);
  729. }
  730. // limits the acceleration and deceleration of a velocity request
  731. float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
  732. {
  733. // Acceleration is limited directly to smooth the beginning of the curve.
  734. if (is_positive(accel_max)) {
  735. float delta_ang_vel = accel_max * dt;
  736. return constrain_float(desired_ang_vel, target_ang_vel - delta_ang_vel, target_ang_vel + delta_ang_vel);
  737. } else {
  738. return desired_ang_vel;
  739. }
  740. }
  741. // calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
  742. // This function can be used to predict the delay associated with angle requests.
  743. void AC_AttitudeControl::input_shaping_rate_predictor(const Vector2f &error_angle, Vector2f& target_ang_vel, float dt) const
  744. {
  745. if (_rate_bf_ff_enabled) {
  746. // translate the roll pitch and yaw acceleration limits to the euler axis
  747. target_ang_vel.x = input_shaping_angle(wrap_PI(error_angle.x), _input_tc, get_accel_roll_max_radss(), target_ang_vel.x, dt);
  748. target_ang_vel.y = input_shaping_angle(wrap_PI(error_angle.y), _input_tc, get_accel_pitch_max_radss(), target_ang_vel.y, dt);
  749. } else {
  750. target_ang_vel.x = _p_angle_roll.get_p(wrap_PI(error_angle.x));
  751. target_ang_vel.y = _p_angle_pitch.get_p(wrap_PI(error_angle.y));
  752. }
  753. // Limit the angular velocity correction
  754. Vector3f ang_vel(target_ang_vel.x, target_ang_vel.y, 0.0f);
  755. ang_vel_limit(ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), 0.0f);
  756. target_ang_vel.x = ang_vel.x;
  757. target_ang_vel.y = ang_vel.y;
  758. }
  759. // limits angular velocity
  760. void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const
  761. {
  762. if (is_zero(ang_vel_roll_max) || is_zero(ang_vel_pitch_max)) {
  763. if (!is_zero(ang_vel_roll_max)) {
  764. euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max, ang_vel_roll_max);
  765. }
  766. if (!is_zero(ang_vel_pitch_max)) {
  767. euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max, ang_vel_pitch_max);
  768. }
  769. } else {
  770. Vector2f thrust_vector_ang_vel(euler_rad.x / ang_vel_roll_max, euler_rad.y / ang_vel_pitch_max);
  771. float thrust_vector_length = thrust_vector_ang_vel.length();
  772. if (thrust_vector_length > 1.0f) {
  773. euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max / thrust_vector_length;
  774. euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max / thrust_vector_length;
  775. }
  776. }
  777. if (!is_zero(ang_vel_yaw_max)) {
  778. euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max, ang_vel_yaw_max);
  779. }
  780. }
  781. // translates body frame acceleration limits to the euler axis
  782. Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel)
  783. {
  784. float sin_phi = constrain_float(fabsf(sinf(euler_rad.x)), 0.1f, 1.0f);
  785. float cos_phi = constrain_float(fabsf(cosf(euler_rad.x)), 0.1f, 1.0f);
  786. float sin_theta = constrain_float(fabsf(sinf(euler_rad.y)), 0.1f, 1.0f);
  787. Vector3f rot_accel;
  788. if (is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) {
  789. rot_accel.x = euler_accel.x;
  790. rot_accel.y = euler_accel.y;
  791. rot_accel.z = euler_accel.z;
  792. } else {
  793. rot_accel.x = euler_accel.x;
  794. rot_accel.y = MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi);
  795. rot_accel.z = MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / sin_phi), euler_accel.z / cos_phi);
  796. }
  797. return rot_accel;
  798. }
  799. // Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
  800. void AC_AttitudeControl::shift_ef_yaw_target(float yaw_shift_cd)
  801. {
  802. float yaw_shift = radians(yaw_shift_cd * 0.01f);
  803. Quaternion _attitude_target_update_quat;
  804. _attitude_target_update_quat.from_axis_angle(Vector3f(0.0f, 0.0f, yaw_shift));
  805. _attitude_target_quat = _attitude_target_update_quat * _attitude_target_quat;
  806. }
  807. // Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
  808. void AC_AttitudeControl::inertial_frame_reset()
  809. {
  810. // Retrieve quaternion vehicle attitude
  811. Quaternion attitude_vehicle_quat;
  812. _ahrs.get_quat_body_to_ned(attitude_vehicle_quat);
  813. // Recalculate the target quaternion
  814. _attitude_target_quat = attitude_vehicle_quat * _attitude_ang_error;
  815. // calculate the attitude target euler angles
  816. _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
  817. }
  818. // Convert a 321-intrinsic euler angle derivative to an angular velocity vector
  819. void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads)
  820. {
  821. float sin_theta = sinf(euler_rad.y);
  822. float cos_theta = cosf(euler_rad.y);
  823. float sin_phi = sinf(euler_rad.x);
  824. float cos_phi = cosf(euler_rad.x);
  825. ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z;
  826. ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z;
  827. ang_vel_rads.z = -sin_phi * euler_rate_rads.y + cos_theta * cos_phi * euler_rate_rads.z;
  828. }
  829. // Convert an angular velocity vector to a 321-intrinsic euler angle derivative
  830. // Returns false if the vehicle is pitched 90 degrees up or down
  831. bool AC_AttitudeControl::ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads)
  832. {
  833. float sin_theta = sinf(euler_rad.y);
  834. float cos_theta = cosf(euler_rad.y);
  835. float sin_phi = sinf(euler_rad.x);
  836. float cos_phi = cosf(euler_rad.x);
  837. // When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false.
  838. if (is_zero(cos_theta)) {
  839. return false;
  840. }
  841. euler_rate_rads.x = ang_vel_rads.x + sin_phi * (sin_theta / cos_theta) * ang_vel_rads.y + cos_phi * (sin_theta / cos_theta) * ang_vel_rads.z;
  842. euler_rate_rads.y = cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z;
  843. euler_rate_rads.z = (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z;
  844. return true;
  845. }
  846. // Update rate_target_ang_vel using attitude_error_rot_vec_rad
  847. Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)
  848. {
  849. Vector3f rate_target_ang_vel;
  850. // Compute the roll angular velocity demand from the roll angle error
  851. if (_use_sqrt_controller) {
  852. rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, _p_angle_roll.kP(), constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
  853. } else {
  854. rate_target_ang_vel.x = _p_angle_roll.kP() * attitude_error_rot_vec_rad.x;
  855. }
  856. // todo: Add Angular Velocity Limit
  857. // Compute the pitch angular velocity demand from the pitch angle error
  858. if (_use_sqrt_controller) {
  859. rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, _p_angle_pitch.kP(), constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
  860. } else {
  861. rate_target_ang_vel.y = _p_angle_pitch.kP() * attitude_error_rot_vec_rad.y;
  862. }
  863. // todo: Add Angular Velocity Limit
  864. // Compute the yaw angular velocity demand from the yaw angle error
  865. if (_use_sqrt_controller) {
  866. rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, _p_angle_yaw.kP(), constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt);
  867. } else {
  868. rate_target_ang_vel.z = _p_angle_yaw.kP() * attitude_error_rot_vec_rad.z;
  869. }
  870. // todo: Add Angular Velocity Limit
  871. return rate_target_ang_vel;
  872. }
  873. // Enable or disable body-frame feed forward
  874. void AC_AttitudeControl::accel_limiting(bool enable_limits)
  875. {
  876. if (enable_limits) {
  877. // If enabling limits, reload from eeprom or set to defaults
  878. if (is_zero(_accel_roll_max)) {
  879. _accel_roll_max.load();
  880. }
  881. if (is_zero(_accel_pitch_max)) {
  882. _accel_pitch_max.load();
  883. }
  884. if (is_zero(_accel_yaw_max)) {
  885. _accel_yaw_max.load();
  886. }
  887. } else {
  888. _accel_roll_max = 0.0f;
  889. _accel_pitch_max = 0.0f;
  890. _accel_yaw_max = 0.0f;
  891. }
  892. }
  893. // Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
  894. float AC_AttitudeControl::get_althold_lean_angle_max() const
  895. {
  896. // convert to centi-degrees for public interface
  897. return MAX(ToDeg(_althold_lean_angle_max), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN) * 100.0f;
  898. }
  899. // Proportional controller with piecewise sqrt sections to constrain second derivative
  900. float AC_AttitudeControl::sqrt_controller(float error, float p, float second_ord_lim, float dt)
  901. {
  902. float correction_rate;
  903. if (is_negative(second_ord_lim) || is_zero(second_ord_lim)) {
  904. // second order limit is zero or negative.
  905. correction_rate = error * p;
  906. } else if (is_zero(p)) {
  907. // P term is zero but we have a second order limit.
  908. if (is_positive(error)) {
  909. correction_rate = safe_sqrt(2.0f * second_ord_lim * (error));
  910. } else if (is_negative(error)) {
  911. correction_rate = -safe_sqrt(2.0f * second_ord_lim * (-error));
  912. } else {
  913. correction_rate = 0.0f;
  914. }
  915. } else {
  916. // Both the P and second order limit have been defined.
  917. float linear_dist = second_ord_lim / sq(p);
  918. if (error > linear_dist) {
  919. correction_rate = safe_sqrt(2.0f * second_ord_lim * (error - (linear_dist / 2.0f)));
  920. } else if (error < -linear_dist) {
  921. correction_rate = -safe_sqrt(2.0f * second_ord_lim * (-error - (linear_dist / 2.0f)));
  922. } else {
  923. correction_rate = error * p;
  924. }
  925. }
  926. if (!is_zero(dt)) {
  927. // this ensures we do not get small oscillations by over shooting the error correction in the last time step.
  928. return constrain_float(correction_rate, -fabsf(error) / dt, fabsf(error) / dt);
  929. } else {
  930. return correction_rate;
  931. }
  932. }
  933. // Inverse proportional controller with piecewise sqrt sections to constrain second derivative
  934. float AC_AttitudeControl::stopping_point(float first_ord_mag, float p, float second_ord_lim)
  935. {
  936. if (is_positive(second_ord_lim) && !is_zero(second_ord_lim) && is_zero(p)) {
  937. return (first_ord_mag * first_ord_mag) / (2.0f * second_ord_lim);
  938. } else if ((is_negative(second_ord_lim) || is_zero(second_ord_lim)) && !is_zero(p)) {
  939. return first_ord_mag / p;
  940. } else if ((is_negative(second_ord_lim) || is_zero(second_ord_lim)) && is_zero(p)) {
  941. return 0.0f;
  942. }
  943. // calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
  944. float linear_velocity = second_ord_lim / p;
  945. if (fabsf(first_ord_mag) < linear_velocity) {
  946. // if our current velocity is below the cross-over point we use a linear function
  947. return first_ord_mag / p;
  948. } else {
  949. float linear_dist = second_ord_lim / sq(p);
  950. float overshoot = (linear_dist * 0.5f) + sq(first_ord_mag) / (2.0f * second_ord_lim);
  951. if (is_positive(first_ord_mag)) {
  952. return overshoot;
  953. } else {
  954. return -overshoot;
  955. }
  956. }
  957. }
  958. // Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps
  959. float AC_AttitudeControl::max_rate_step_bf_roll()
  960. {
  961. float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(), get_rate_roll_pid().get_filt_D_alpha());
  962. float alpha_remaining = 1 - alpha;
  963. // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
  964. float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
  965. return 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_roll_pid().kD()) / _dt + get_rate_roll_pid().kP());
  966. }
  967. // Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps
  968. float AC_AttitudeControl::max_rate_step_bf_pitch()
  969. {
  970. float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(), get_rate_pitch_pid().get_filt_D_alpha());
  971. float alpha_remaining = 1 - alpha;
  972. // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
  973. float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
  974. return 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_pitch_pid().kD()) / _dt + get_rate_pitch_pid().kP());
  975. }
  976. // Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps
  977. float AC_AttitudeControl::max_rate_step_bf_yaw()
  978. {
  979. float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(), get_rate_yaw_pid().get_filt_D_alpha());
  980. float alpha_remaining = 1 - alpha;
  981. // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max
  982. float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);
  983. return 2.0f * throttle_hover * AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_yaw_pid().kD()) / _dt + get_rate_yaw_pid().kP());
  984. }
  985. bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,
  986. char *failure_msg,
  987. const uint8_t failure_msg_len)
  988. {
  989. // validate AC_P members:
  990. const struct {
  991. const char *pid_name;
  992. AC_P &p;
  993. } ps[] = {
  994. { "ANG_PIT", get_angle_pitch_p() },
  995. { "ANG_RLL", get_angle_roll_p() },
  996. { "ANG_YAW", get_angle_yaw_p() }
  997. };
  998. for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
  999. // all AC_P's must have a positive P value:
  1000. if (!is_positive(ps[i].p.kP())) {
  1001. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
  1002. return false;
  1003. }
  1004. }
  1005. // validate AC_PID members:
  1006. const struct {
  1007. const char *pid_name;
  1008. AC_PID &pid;
  1009. } pids[] = {
  1010. { "RAT_RLL", get_rate_roll_pid() },
  1011. { "RAT_PIT", get_rate_pitch_pid() },
  1012. { "RAT_YAW", get_rate_yaw_pid() },
  1013. };
  1014. for (uint8_t i=0; i<ARRAY_SIZE(pids); i++) {
  1015. // if the PID has a positive FF then we just ensure kP and
  1016. // kI aren't negative
  1017. AC_PID &pid = pids[i].pid;
  1018. const char *pid_name = pids[i].pid_name;
  1019. if (is_positive(pid.ff())) {
  1020. // kP and kI must be non-negative:
  1021. if (is_negative(pid.kP())) {
  1022. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be >= 0", param_prefix, pid_name);
  1023. return false;
  1024. }
  1025. if (is_negative(pid.kI())) {
  1026. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be >= 0", param_prefix, pid_name);
  1027. return false;
  1028. }
  1029. } else {
  1030. // kP and kI must be positive:
  1031. if (!is_positive(pid.kP())) {
  1032. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, pid_name);
  1033. return false;
  1034. }
  1035. if (!is_positive(pid.kI())) {
  1036. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be > 0", param_prefix, pid_name);
  1037. return false;
  1038. }
  1039. }
  1040. // never allow a negative D term (but zero is allowed)
  1041. if (is_negative(pid.kD())) {
  1042. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_D must be >= 0", param_prefix, pid_name);
  1043. return false;
  1044. }
  1045. }
  1046. return true;
  1047. }