AC_PosControl.cpp 56 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_PosControl.h"
  3. #include <AP_Math/AP_Math.h>
  4. #include <AP_Logger/AP_Logger.h>
  5. #include "../../ArduSub/Sub.h"
  6. extern const AP_HAL::HAL& hal;
  7. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  8. // default gains for Plane
  9. # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default
  10. # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default
  11. # define POSCONTROL_ACC_Z_P 0.3f // vertical acceleration controller P gain default
  12. # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default
  13. # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
  14. # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default
  15. # define POSCONTROL_ACC_Z_FILT_HZ 10.0f // vertical acceleration controller input filter default
  16. # define POSCONTROL_ACC_Z_DT 0.02f // vertical acceleration controller dt default
  17. # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
  18. # define POSCONTROL_VEL_XY_P 1.4f // horizontal velocity controller P gain default
  19. # define POSCONTROL_VEL_XY_I 0.7f // horizontal velocity controller I gain default
  20. # define POSCONTROL_VEL_XY_D 0.35f // horizontal velocity controller D gain default
  21. # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
  22. # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
  23. # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
  24. #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
  25. // default gains for Sub
  26. # define POSCONTROL_POS_Z_P 3.0f // vertical position controller P gain default
  27. # define POSCONTROL_VEL_Z_P 8.0f // vertical velocity controller P gain default
  28. # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default
  29. # define POSCONTROL_ACC_Z_I 0.1f // vertical acceleration controller I gain default
  30. # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
  31. # define POSCONTROL_ACC_Z_IMAX 100 // vertical acceleration controller IMAX gain default
  32. # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default
  33. # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default
  34. # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
  35. # define POSCONTROL_VEL_XY_P 1.0f // horizontal velocity controller P gain default
  36. # define POSCONTROL_VEL_XY_I 0.5f // horizontal velocity controller I gain default
  37. # define POSCONTROL_VEL_XY_D 0.0f // horizontal velocity controller D gain default
  38. # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
  39. # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
  40. # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
  41. #else
  42. // default gains for Copter / TradHeli
  43. # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default
  44. # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default
  45. # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default
  46. # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default
  47. # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
  48. # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default
  49. # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default
  50. # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default
  51. # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
  52. # define POSCONTROL_VEL_XY_P 2.0f // horizontal velocity controller P gain default
  53. # define POSCONTROL_VEL_XY_I 1.0f // horizontal velocity controller I gain default
  54. # define POSCONTROL_VEL_XY_D 0.5f // horizontal velocity controller D gain default
  55. # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
  56. # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
  57. # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
  58. #endif
  59. const AP_Param::GroupInfo AC_PosControl::var_info[] = {
  60. // 0 was used for HOVER
  61. // @Param: _ACC_XY_FILT
  62. // @DisplayName: XY Acceleration filter cutoff frequency
  63. // @Description: Lower values will slow the response of the navigation controller and reduce twitchiness
  64. // @Units: Hz
  65. // @Range: 0.5 5
  66. // @Increment: 0.1
  67. // @User: Advanced
  68. AP_GROUPINFO("_ACC_XY_FILT", 1, AC_PosControl, _accel_xy_filt_hz, POSCONTROL_ACCEL_FILTER_HZ),
  69. // @Param: _POSZ_P
  70. // @DisplayName: Position (vertical) controller P gain
  71. // @Description: Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
  72. // @Range: 1.000 3.000
  73. // @User: Standard
  74. AP_SUBGROUPINFO(_p_pos_z, "_POSZ_", 2, AC_PosControl, AC_P),
  75. // @Param: _VELZ_P
  76. // @DisplayName: Velocity (vertical) controller P gain
  77. // @Description: Velocity (vertical) controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
  78. // @Range: 1.000 8.000
  79. // @User: Standard
  80. AP_SUBGROUPINFO(_p_vel_z, "_VELZ_", 3, AC_PosControl, AC_P),
  81. // @Param: _ACCZ_P
  82. // @DisplayName: Acceleration (vertical) controller P gain
  83. // @Description: Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
  84. // @Range: 0.500 1.500
  85. // @Increment: 0.05
  86. // @User: Standard
  87. // @Param: _ACCZ_I
  88. // @DisplayName: Acceleration (vertical) controller I gain
  89. // @Description: Acceleration (vertical) controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration
  90. // @Range: 0.000 3.000
  91. // @User: Standard
  92. // @Param: _ACCZ_IMAX
  93. // @DisplayName: Acceleration (vertical) controller I gain maximum
  94. // @Description: Acceleration (vertical) controller I gain maximum. Constrains the maximum pwm that the I term will generate
  95. // @Range: 0 1000
  96. // @Units: d%
  97. // @User: Standard
  98. // @Param: _ACCZ_D
  99. // @DisplayName: Acceleration (vertical) controller D gain
  100. // @Description: Acceleration (vertical) controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration
  101. // @Range: 0.000 0.400
  102. // @User: Standard
  103. // @Param: _ACCZ_FILT
  104. // @DisplayName: Acceleration (vertical) controller filter
  105. // @Description: Filter applied to acceleration to reduce noise. Lower values reduce noise but add delay.
  106. // @Range: 1.000 100.000
  107. // @Units: Hz
  108. // @User: Standard
  109. AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID),
  110. // @Param: _POSXY_P
  111. // @DisplayName: Position (horizonal) controller P gain
  112. // @Description: Position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller
  113. // @Range: 0.500 2.000
  114. // @User: Standard
  115. AP_SUBGROUPINFO(_p_pos_xy, "_POSXY_", 5, AC_PosControl, AC_P),
  116. // @Param: _VELXY_P
  117. // @DisplayName: Velocity (horizontal) P gain
  118. // @Description: Velocity (horizontal) P gain. Converts the difference between desired velocity to a target acceleration
  119. // @Range: 0.1 6.0
  120. // @Increment: 0.1
  121. // @User: Advanced
  122. // @Param: _VELXY_I
  123. // @DisplayName: Velocity (horizontal) I gain
  124. // @Description: Velocity (horizontal) I gain. Corrects long-term difference in desired velocity to a target acceleration
  125. // @Range: 0.02 1.00
  126. // @Increment: 0.01
  127. // @User: Advanced
  128. // @Param: _VELXY_D
  129. // @DisplayName: Velocity (horizontal) D gain
  130. // @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity
  131. // @Range: 0.00 1.00
  132. // @Increment: 0.001
  133. // @User: Advanced
  134. // @Param: _VELXY_IMAX
  135. // @DisplayName: Velocity (horizontal) integrator maximum
  136. // @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
  137. // @Range: 0 4500
  138. // @Increment: 10
  139. // @Units: cm/s/s
  140. // @User: Advanced
  141. // @Param: _VELXY_FILT
  142. // @DisplayName: Velocity (horizontal) input filter
  143. // @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for P and I terms
  144. // @Range: 0 100
  145. // @Units: Hz
  146. // @User: Advanced
  147. // @Param: _VELXY_D_FILT
  148. // @DisplayName: Velocity (horizontal) input filter
  149. // @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for P and I terms
  150. // @Range: 0 100
  151. // @Units: Hz
  152. // @User: Advanced
  153. AP_SUBGROUPINFO(_pid_vel_xy, "_VELXY_", 6, AC_PosControl, AC_PID_2D),
  154. // @Param: _ANGLE_MAX
  155. // @DisplayName: Position Control Angle Max
  156. // @Description: Maximum lean angle autopilot can request. Set to zero to use ANGLE_MAX parameter value
  157. // @Units: deg
  158. // @Range: 0 45
  159. // @Increment: 1
  160. // @User: Advanced
  161. AP_GROUPINFO("_ANGLE_MAX", 7, AC_PosControl, _lean_angle_max, 0.0f),
  162. AP_GROUPEND
  163. };
  164. // Default constructor.
  165. // Note that the Vector/Matrix constructors already implicitly zero
  166. // their values.
  167. //
  168. AC_PosControl::AC_PosControl(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
  169. const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
  170. _ahrs(ahrs),
  171. _inav(inav),
  172. _motors(motors),
  173. _attitude_control(attitude_control),
  174. _p_pos_z(POSCONTROL_POS_Z_P),
  175. _p_vel_z(POSCONTROL_VEL_Z_P),
  176. _pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f, POSCONTROL_ACC_Z_DT),
  177. _p_pos_xy(POSCONTROL_POS_XY_P),
  178. _pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ, POSCONTROL_DT_50HZ),
  179. _dt(POSCONTROL_DT_400HZ),
  180. _speed_down_cms(POSCONTROL_SPEED_DOWN),
  181. _speed_up_cms(POSCONTROL_SPEED_UP),
  182. _speed_cms(POSCONTROL_SPEED),
  183. _accel_z_cms(POSCONTROL_ACCEL_Z),
  184. _accel_cms(POSCONTROL_ACCEL_XY),
  185. _leash(POSCONTROL_LEASH_LENGTH_MIN),
  186. _leash_down_z(POSCONTROL_LEASH_LENGTH_MIN),
  187. _leash_up_z(POSCONTROL_LEASH_LENGTH_MIN),
  188. _accel_target_filter(POSCONTROL_ACCEL_FILTER_HZ)
  189. {
  190. AP_Param::setup_object_defaults(this, var_info);
  191. // initialise flags
  192. _flags.recalc_leash_z = true;
  193. _flags.recalc_leash_xy = true;
  194. _flags.reset_desired_vel_to_pos = true;
  195. _flags.reset_accel_to_lean_xy = true;
  196. _flags.reset_rate_to_accel_z = true;
  197. _flags.freeze_ff_z = true;
  198. _flags.use_desvel_ff_z = true;
  199. _limit.pos_up = true;
  200. _limit.pos_down = true;
  201. _limit.vel_up = true;
  202. _limit.vel_down = true;
  203. _limit.accel_xy = true;
  204. }
  205. ///
  206. /// z-axis position controller
  207. ///
  208. /// set_dt - sets time delta in seconds for all controllers (i.e. 100hz = 0.01, 400hz = 0.0025)
  209. void AC_PosControl::set_dt(float delta_sec)
  210. {
  211. _dt = delta_sec;
  212. // update PID controller dt
  213. _pid_accel_z.set_dt(_dt);
  214. _pid_vel_xy.set_dt(_dt);
  215. // update rate z-axis velocity error and accel error filters
  216. _vel_error_filter.set_cutoff_frequency(POSCONTROL_VEL_ERROR_CUTOFF_FREQ);
  217. }
  218. /// set_max_speed_z - set the maximum climb and descent rates
  219. /// To-Do: call this in the main code as part of flight mode initialisation
  220. void AC_PosControl::set_max_speed_z(float speed_down, float speed_up)
  221. {
  222. // ensure speed_down is always negative
  223. speed_down = -fabsf(speed_down);
  224. //默认_speed_down_cms -150 ,,_speed_up_cms 250
  225. if ((fabsf(_speed_down_cms - speed_down) > 1.0f) || (fabsf(_speed_up_cms - speed_up) > 1.0f)) {
  226. _speed_down_cms = speed_down;
  227. _speed_up_cms = speed_up;
  228. _flags.recalc_leash_z = true;
  229. calc_leash_length_z();// 刹车长度
  230. }
  231. }
  232. /// set_max_accel_z - set the maximum vertical acceleration in cm/s/s
  233. void AC_PosControl::set_max_accel_z(float accel_cmss)
  234. {
  235. if (fabsf(_accel_z_cms - accel_cmss) > 1.0f) {
  236. _accel_z_cms = accel_cmss;
  237. _flags.recalc_leash_z = true;
  238. calc_leash_length_z();
  239. }
  240. }
  241. /// set_alt_target_with_slew - adjusts target towards a final altitude target
  242. /// should be called continuously (with dt set to be the expected time between calls)
  243. /// actual position target will be moved no faster than the speed_down and speed_up
  244. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  245. void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
  246. {
  247. float alt_change = alt_cm - _pos_target.z;
  248. // do not use z-axis desired velocity feed forward
  249. _flags.use_desvel_ff_z = false;
  250. // adjust desired alt if motors have not hit their limits
  251. if ((alt_change < 0 && !_motors.limit.throttle_lower) || (alt_change > 0 && !_motors.limit.throttle_upper)) {
  252. if (!is_zero(dt)) {
  253. float climb_rate_cms = constrain_float(alt_change / dt, _speed_down_cms, _speed_up_cms);
  254. _pos_target.z += climb_rate_cms * dt;
  255. _vel_desired.z = climb_rate_cms; // recorded for reporting purposes
  256. }
  257. } else {
  258. // recorded for reporting purposes
  259. _vel_desired.z = 0.0f;
  260. }
  261. // do not let target get too far from current altitude
  262. float curr_alt = _inav.get_altitude();
  263. _pos_target.z = constrain_float(_pos_target.z, curr_alt - _leash_down_z, curr_alt + _leash_up_z);
  264. }
  265. /// set_alt_target_from_climb_rate - adjusts target up or down using a climb rate in cm/s
  266. /// should be called continuously (with dt set to be the expected time between calls)
  267. /// actual position target will be moved no faster than the speed_down and speed_up
  268. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  269. void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
  270. {
  271. // adjust desired alt if motors have not hit their limits
  272. // To-Do: add check of _limit.pos_down?
  273. if ((climb_rate_cms < 0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  274. _pos_target.z += climb_rate_cms * dt;
  275. }
  276. // do not use z-axis desired velocity feed forward
  277. // vel_desired set to desired climb rate for reporting and land-detector
  278. _flags.use_desvel_ff_z = false;
  279. _vel_desired.z = climb_rate_cms;
  280. }
  281. /// set_alt_target_from_climb_rate_ff - adjusts target up or down using a climb rate in cm/s using feed-forward
  282. /// should be called continuously (with dt set to be the expected time between calls)
  283. /// actual position target will be moved no faster than the speed_down and speed_up
  284. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  285. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  286. void AC_PosControl::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
  287. {
  288. // calculated increased maximum acceleration if over speed
  289. float accel_z_cms = _accel_z_cms;
  290. if (_vel_desired.z < _speed_down_cms && !is_zero(_speed_down_cms)) {
  291. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_down_cms;
  292. }
  293. if (_vel_desired.z > _speed_up_cms && !is_zero(_speed_up_cms)) {
  294. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_up_cms;
  295. }
  296. accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
  297. // jerk_z is calculated to reach full acceleration in 1000ms.
  298. float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
  299. float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f * fabsf(_vel_desired.z - climb_rate_cms) * jerk_z));
  300. _accel_last_z_cms += jerk_z * dt;
  301. _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
  302. float vel_change_limit = _accel_last_z_cms * dt;
  303. _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z - vel_change_limit, _vel_desired.z + vel_change_limit);
  304. _flags.use_desvel_ff_z = true;
  305. // adjust desired alt if motors have not hit their limits
  306. // To-Do: add check of _limit.pos_down?
  307. if ((_vel_desired.z < 0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  308. _pos_target.z += _vel_desired.z * dt;
  309. }
  310. }
  311. /// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
  312. /// should be called continuously (with dt set to be the expected time between calls)
  313. /// almost no checks are performed on the input
  314. void AC_PosControl::add_takeoff_climb_rate(float climb_rate_cms, float dt)
  315. {
  316. _pos_target.z += climb_rate_cms * dt;
  317. }
  318. /// shift altitude target (positive means move altitude up)
  319. void AC_PosControl::shift_alt_target(float z_cm)
  320. {
  321. _pos_target.z += z_cm;
  322. // freeze feedforward to avoid jump
  323. if (!is_zero(z_cm)) {
  324. freeze_ff_z();
  325. }
  326. }
  327. /// relax_alt_hold_controllers - set all desired and targets to measured
  328. void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
  329. {
  330. _pos_target.z = _inav.get_altitude();
  331. _vel_desired.z = 0.0f;
  332. _flags.use_desvel_ff_z = false;
  333. _vel_target.z = _inav.get_velocity_z();
  334. _vel_last.z = _inav.get_velocity_z();
  335. _accel_desired.z = 0.0f;
  336. _accel_last_z_cms = 0.0f;
  337. _flags.reset_rate_to_accel_z = true;
  338. _pid_accel_z.set_integrator((throttle_setting - _motors.get_throttle_hover()) * 1000.0f);
  339. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  340. _pid_accel_z.reset_filter();
  341. }
  342. // get_alt_error - returns altitude error in cm
  343. float AC_PosControl::get_alt_error() const
  344. {
  345. return (_pos_target.z - _inav.get_altitude());
  346. }
  347. /// set_target_to_stopping_point_z - returns reasonable stopping altitude in cm above home
  348. void AC_PosControl::set_target_to_stopping_point_z()
  349. {
  350. // check if z leash needs to be recalculated
  351. calc_leash_length_z();
  352. get_stopping_point_z(_pos_target);
  353. }
  354. /// get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
  355. void AC_PosControl::get_stopping_point_z(Vector3f& stopping_point) const
  356. {
  357. const float curr_pos_z = _inav.get_altitude();
  358. float curr_vel_z = _inav.get_velocity_z();
  359. float linear_distance; // half the distance we swap between linear and sqrt and the distance we offset sqrt
  360. float linear_velocity; // the velocity we swap between linear and sqrt
  361. // if position controller is active add current velocity error to avoid sudden jump in acceleration
  362. if (is_active_z()) {
  363. curr_vel_z += _vel_error.z;
  364. if (_flags.use_desvel_ff_z) {
  365. curr_vel_z -= _vel_desired.z;
  366. }
  367. }
  368. // avoid divide by zero by using current position if kP is very low or acceleration is zero
  369. if (_p_pos_z.kP() <= 0.0f || _accel_z_cms <= 0.0f) {
  370. stopping_point.z = curr_pos_z;
  371. return;
  372. }
  373. // calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
  374. linear_velocity = _accel_z_cms / _p_pos_z.kP();
  375. if (fabsf(curr_vel_z) < linear_velocity) {
  376. // if our current velocity is below the cross-over point we use a linear function
  377. stopping_point.z = curr_pos_z + curr_vel_z / _p_pos_z.kP();
  378. } else {
  379. linear_distance = _accel_z_cms / (2.0f * _p_pos_z.kP() * _p_pos_z.kP());
  380. if (curr_vel_z > 0) {
  381. stopping_point.z = curr_pos_z + (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
  382. } else {
  383. stopping_point.z = curr_pos_z - (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
  384. }
  385. }
  386. stopping_point.z = constrain_float(stopping_point.z, curr_pos_z - POSCONTROL_STOPPING_DIST_DOWN_MAX, curr_pos_z + POSCONTROL_STOPPING_DIST_UP_MAX);
  387. }
  388. /// init_takeoff - initialises target altitude if we are taking off
  389. void AC_PosControl::init_takeoff()
  390. {
  391. const Vector3f& curr_pos = _inav.get_position();
  392. _pos_target.z = curr_pos.z;
  393. // freeze feedforward to avoid jump
  394. freeze_ff_z();
  395. // shift difference between last motor out and hover throttle into accelerometer I
  396. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  397. // initialise ekf reset handler
  398. init_ekf_z_reset();
  399. }
  400. // is_active_z - returns true if the z-axis position controller has been run very recently
  401. bool AC_PosControl::is_active_z() const
  402. {
  403. return ((AP_HAL::micros64() - _last_update_z_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
  404. }
  405. /// update_z_controller - fly to altitude in cm above home
  406. void AC_PosControl::update_z_controller()
  407. {
  408. // check time since last cast
  409. const uint64_t now_us = AP_HAL::micros64();
  410. if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
  411. _flags.reset_rate_to_accel_z = true;
  412. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  413. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  414. _pid_accel_z.reset_filter();
  415. }
  416. _last_update_z_us = now_us;
  417. // check for ekf altitude reset
  418. //check_for_ekf_z_reset();
  419. // check if leash lengths need to be recalculated
  420. calc_leash_length_z();
  421. // call z-axis position controller
  422. run_z_controller_f();
  423. }
  424. float AC_PosControl::update_z_controller_f()
  425. {
  426. // check time since last cast
  427. const uint64_t now_us = AP_HAL::micros64();
  428. if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
  429. _flags.reset_rate_to_accel_z = true;
  430. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  431. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  432. _pid_accel_z.reset_filter();
  433. }
  434. _last_update_z_us = now_us;
  435. // check for ekf altitude reset
  436. //check_for_ekf_z_reset();
  437. // check if leash lengths need to be recalculated
  438. calc_leash_length_z();
  439. // call z-axis position controller
  440. return run_z_controller_f();
  441. }
  442. /// calc_leash_length - calculates the vertical leash lengths from maximum speed, acceleration
  443. /// called by update_z_controller if z-axis speed or accelerations are changed
  444. void AC_PosControl::calc_leash_length_z()
  445. {
  446. if (_flags.recalc_leash_z) {
  447. _leash_up_z = calc_leash_length(_speed_up_cms, _accel_z_cms, _p_pos_z.kP());
  448. _leash_down_z = calc_leash_length(-_speed_down_cms, _accel_z_cms, _p_pos_z.kP());
  449. _flags.recalc_leash_z = false;
  450. }
  451. }
  452. // run position control for Z axis
  453. // target altitude should be set with one of these functions: set_alt_target, set_target_to_stopping_point_z, init_takeoff
  454. // calculates desired rate in earth-frame z axis and passes to rate controller
  455. // vel_up_max, vel_down_max should have already been set before calling this method
  456. void AC_PosControl::run_z_controller()
  457. {
  458. //float curr_alt = _inav.get_altitude();//12.19
  459. float curr_alt = sub.barometer.get_altitude()*100;//_inav.get_altitude();//12.19
  460. float vel_from_baro = AC_AttitudeControl::sqrt_controller(curr_alt-last_alt, _p_pos_z.kP(), _accel_z_cms, _dt);//12.19
  461. static uint16_t i=0;
  462. uint16_t timecnt = (uint16_t)(0.25/_dt);
  463. i++;
  464. if (i>timecnt)
  465. {
  466. i = 0;
  467. last_alt = curr_alt;//12.19
  468. }
  469. // clear position limit flags
  470. _limit.pos_up = false;
  471. _limit.pos_down = false;
  472. // calculate altitude error
  473. _pos_error.z = _pos_target.z - curr_alt;
  474. // do not let target altitude get too far from current altitude
  475. if (_pos_error.z > _leash_up_z) {
  476. _pos_target.z = curr_alt + _leash_up_z;
  477. _pos_error.z = _leash_up_z;
  478. _limit.pos_up = true;
  479. }
  480. if (_pos_error.z < -_leash_down_z) {
  481. _pos_target.z = curr_alt - _leash_down_z;
  482. _pos_error.z = -_leash_down_z;
  483. _limit.pos_down = true;
  484. }
  485. // calculate _vel_target.z using from _pos_error.z using sqrt controller
  486. _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
  487. // check speed limits
  488. // To-Do: check these speed limits here or in the pos->rate controller
  489. _limit.vel_up = false;
  490. _limit.vel_down = false;
  491. if (_vel_target.z < _speed_down_cms) {
  492. _vel_target.z = _speed_down_cms;
  493. _limit.vel_down = true;
  494. }
  495. if (_vel_target.z > _speed_up_cms) {
  496. _vel_target.z = _speed_up_cms;
  497. _limit.vel_up = true;
  498. }
  499. // add feed forward component
  500. if (_flags.use_desvel_ff_z) {
  501. _vel_target.z += _vel_desired.z;
  502. }
  503. // the following section calculates acceleration required to achieve the velocity target
  504. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  505. Vector3f curr_vel;//12.19
  506. curr_vel.z=vel_from_baro;
  507. // TODO: remove velocity derivative calculation
  508. // reset last velocity target to current target
  509. if (_flags.reset_rate_to_accel_z) {//改变高度时候复位
  510. _vel_last.z = _vel_target.z;
  511. }
  512. // feed forward desired acceleration calculation
  513. if (_dt > 0.0f) {
  514. if (!_flags.freeze_ff_z) {
  515. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  516. } else {
  517. // stop the feed forward being calculated during a known discontinuity
  518. _flags.freeze_ff_z = false;
  519. }
  520. } else {
  521. _accel_desired.z = 0.0f;
  522. }
  523. // store this iteration's velocities for the next iteration
  524. _vel_last.z = _vel_target.z;
  525. // reset velocity error and filter if this controller has just been engaged
  526. if (_flags.reset_rate_to_accel_z) {
  527. // Reset Filter
  528. _vel_error.z = 0;
  529. _vel_error_filter.reset(0);
  530. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;//02.28
  531. _flags.reset_rate_to_accel_z = false;
  532. } else {
  533. // calculate rate error and filter with cut off frequency of 2 Hz
  534. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  535. _accel_target.z = _p_vel_z.get_p(_vel_error.z);//02.28
  536. }
  537. _accel_target.z += _accel_desired.z;
  538. // the following section calculates a desired throttle needed to achieve the acceleration target
  539. float z_accel_meas; // actual acceleration
  540. // Calculate Earth Frame Z acceleration
  541. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  542. // ensure imax is always large enough to overpower hover throttle
  543. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  544. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  545. }
  546. // float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f +_motors.get_throttle_hover();
  547. float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f +0.5;
  548. // send throttle to attitude controller with angle boost
  549. _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  550. static uint8_t cnt = 0;
  551. cnt++;
  552. if (cnt>250)
  553. {
  554. cnt = 0;
  555. //gcs().send_text(MAV_SEVERITY_INFO, " ff %d %d %f\n",(int)_flags.use_desvel_ff_z,(int)_flags.freeze_ff_z,_motors.get_throttle_hover());
  556. //gcs().send_text(MAV_SEVERITY_INFO, " pos %f %f %f %f\n",_pos_error.z,_vel_target.z,curr_vel.z,_accel_desired.z);
  557. gcs().send_text(MAV_SEVERITY_INFO, " pid %f %f %f %f\n",_accel_target.z,z_accel_meas,_accel_desired.z,thr_out);
  558. }
  559. }
  560. float AC_PosControl::run_z_controller_f()
  561. {
  562. //float curr_alt = _inav.get_altitude();//12.19
  563. float curr_alt = sub.barometer.get_altitude()*100;//_inav.get_altitude();//12.19
  564. float vel_from_baro = AC_AttitudeControl::sqrt_controller(curr_alt-last_alt, _p_pos_z.kP(), _accel_z_cms, _dt);//12.19
  565. static uint16_t i=0;
  566. uint16_t timecnt = (uint16_t)(0.25/_dt);
  567. i++;
  568. if (i>timecnt)
  569. {
  570. i = 0;
  571. last_alt = curr_alt;//12.19
  572. }
  573. // clear position limit flags
  574. _limit.pos_up = false;
  575. _limit.pos_down = false;
  576. // calculate altitude error
  577. _pos_error.z = _pos_target.z - curr_alt;
  578. // do not let target altitude get too far from current altitude
  579. if (_pos_error.z > _leash_up_z) {
  580. _pos_target.z = curr_alt + _leash_up_z;
  581. _pos_error.z = _leash_up_z;
  582. _limit.pos_up = true;
  583. }
  584. if (_pos_error.z < -_leash_down_z) {
  585. _pos_target.z = curr_alt - _leash_down_z;
  586. _pos_error.z = -_leash_down_z;
  587. _limit.pos_down = true;
  588. }
  589. // calculate _vel_target.z using from _pos_error.z using sqrt controller
  590. _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
  591. // check speed limits
  592. // To-Do: check these speed limits here or in the pos->rate controller
  593. _limit.vel_up = false;
  594. _limit.vel_down = false;
  595. if (_vel_target.z < _speed_down_cms) {
  596. _vel_target.z = _speed_down_cms;
  597. _limit.vel_down = true;
  598. }
  599. if (_vel_target.z > _speed_up_cms) {
  600. _vel_target.z = _speed_up_cms;
  601. _limit.vel_up = true;
  602. }
  603. // add feed forward component
  604. if (_flags.use_desvel_ff_z) {
  605. _vel_target.z += _vel_desired.z;
  606. }
  607. // the following section calculates acceleration required to achieve the velocity target
  608. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  609. Vector3f curr_vel;//12.19
  610. curr_vel.z=vel_from_baro;
  611. // TODO: remove velocity derivative calculation
  612. // reset last velocity target to current target
  613. if (_flags.reset_rate_to_accel_z) {//改变高度时候复位
  614. _vel_last.z = _vel_target.z;
  615. }
  616. // feed forward desired acceleration calculation
  617. if (_dt > 0.0f) {
  618. if (!_flags.freeze_ff_z) {
  619. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  620. } else {
  621. // stop the feed forward being calculated during a known discontinuity
  622. _flags.freeze_ff_z = false;
  623. }
  624. } else {
  625. _accel_desired.z = 0.0f;
  626. }
  627. // store this iteration's velocities for the next iteration
  628. _vel_last.z = _vel_target.z;
  629. static uint8_t freeze_ff_z =1;
  630. // reset velocity error and filter if this controller has just been engaged
  631. if (_flags.reset_rate_to_accel_z) {
  632. // Reset Filter
  633. _vel_error.z = 0;
  634. _vel_error_filter.reset(0);
  635. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;//02.28
  636. //freeze_ff_z = 0;//前馈一直有效
  637. _flags.reset_rate_to_accel_z = false;
  638. } else {
  639. // calculate rate error and filter with cut off frequency of 2 Hz
  640. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  641. _accel_target.z = _p_vel_z.get_p(_vel_error.z);//02.28
  642. freeze_ff_z =1;
  643. }
  644. _accel_target.z += _accel_desired.z;
  645. // the following section calculates a desired throttle needed to achieve the acceleration target
  646. float z_accel_meas; // actual acceleration
  647. // Calculate Earth Frame Z acceleration
  648. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  649. // ensure imax is always large enough to overpower hover throttle
  650. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  651. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  652. }
  653. // float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f +_motors.get_throttle_hover();
  654. float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f;
  655. float ff_p =(float)SRV_Channels::srv_channel(15)->get_output_min()/1000000;//参数
  656. float thr_out_ff = thr_out;
  657. if (freeze_ff_z!=0)
  658. {
  659. thr_out_ff = thr_out - curr_vel.z*ff_p;//增加了一个前馈项
  660. }
  661. // send throttle to attitude controller with angle boost
  662. // _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  663. static uint8_t cnt = 0;
  664. cnt++;
  665. if (cnt>250)
  666. {
  667. cnt = 0;
  668. //gcs().send_text(MAV_SEVERITY_INFO, " ff %d %d %f\n",(int)_flags.use_desvel_ff_z,(int)_flags.freeze_ff_z,_motors.get_throttle_hover());
  669. //gcs().send_text(MAV_SEVERITY_INFO, " pos %f %f %f %f\n",_pos_error.z,_vel_target.z,curr_vel.z,_accel_desired.z);
  670. gcs().send_text(MAV_SEVERITY_INFO, "pid %d %f %f %f %f\n",freeze_ff_z,_vel_target.z,thr_out,ff_p,thr_out_ff);
  671. }
  672. return thr_out_ff;
  673. }
  674. ///
  675. /// lateral position controller
  676. ///
  677. /// set_max_accel_xy - set the maximum horizontal acceleration in cm/s/s
  678. void AC_PosControl::set_max_accel_xy(float accel_cmss)
  679. {
  680. if (fabsf(_accel_cms - accel_cmss) > 1.0f) {
  681. _accel_cms = accel_cmss;
  682. _flags.recalc_leash_xy = true;
  683. calc_leash_length_xy();
  684. }
  685. }
  686. /// set_max_speed_xy - set the maximum horizontal speed maximum in cm/s
  687. void AC_PosControl::set_max_speed_xy(float speed_cms)
  688. {
  689. if (fabsf(_speed_cms - speed_cms) > 1.0f) {
  690. _speed_cms = speed_cms;
  691. _flags.recalc_leash_xy = true;
  692. calc_leash_length_xy();
  693. }
  694. }
  695. /// set_pos_target in cm from home
  696. void AC_PosControl::set_pos_target(const Vector3f& position)
  697. {
  698. _pos_target = position;
  699. _flags.use_desvel_ff_z = false;
  700. _vel_desired.z = 0.0f;
  701. // initialise roll and pitch to current roll and pitch. This avoids a twitch between when the target is set and the pos controller is first run
  702. // To-Do: this initialisation of roll and pitch targets needs to go somewhere between when pos-control is initialised and when it completes it's first cycle
  703. //_roll_target = constrain_int32(_ahrs.roll_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  704. //_pitch_target = constrain_int32(_ahrs.pitch_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  705. }
  706. /// set_xy_target in cm from home
  707. void AC_PosControl::set_xy_target(float x, float y)
  708. {
  709. _pos_target.x = x;
  710. _pos_target.y = y;
  711. }
  712. /// shift position target target in x, y axis
  713. void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
  714. {
  715. // move pos controller target
  716. _pos_target.x += x_cm;
  717. _pos_target.y += y_cm;
  718. }
  719. /// set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from home
  720. void AC_PosControl::set_target_to_stopping_point_xy()
  721. {
  722. // check if xy leash needs to be recalculated
  723. calc_leash_length_xy();
  724. get_stopping_point_xy(_pos_target);
  725. }
  726. /// get_stopping_point_xy - calculates stopping point based on current position, velocity, vehicle acceleration
  727. /// distance_max allows limiting distance to stopping point
  728. /// results placed in stopping_position vector
  729. /// set_max_accel_xy() should be called before this method to set vehicle acceleration
  730. /// set_leash_length() should have been called before this method
  731. void AC_PosControl::get_stopping_point_xy(Vector3f &stopping_point) const
  732. {
  733. const Vector3f curr_pos = _inav.get_position();
  734. Vector3f curr_vel = _inav.get_velocity();
  735. float linear_distance; // the distance at which we swap from a linear to sqrt response
  736. float linear_velocity; // the velocity above which we swap from a linear to sqrt response
  737. float stopping_dist; // the distance within the vehicle can stop
  738. float kP = _p_pos_xy.kP();
  739. // add velocity error to current velocity
  740. if (is_active_xy()) {
  741. curr_vel.x += _vel_error.x;
  742. curr_vel.y += _vel_error.y;
  743. }
  744. // calculate current velocity
  745. float vel_total = norm(curr_vel.x, curr_vel.y);
  746. // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
  747. if (kP <= 0.0f || _accel_cms <= 0.0f || is_zero(vel_total)) {
  748. stopping_point.x = curr_pos.x;
  749. stopping_point.y = curr_pos.y;
  750. return;
  751. }
  752. // calculate point at which velocity switches from linear to sqrt
  753. linear_velocity = _accel_cms / kP;
  754. // calculate distance within which we can stop
  755. if (vel_total < linear_velocity) {
  756. stopping_dist = vel_total / kP;
  757. } else {
  758. linear_distance = _accel_cms / (2.0f * kP * kP);
  759. stopping_dist = linear_distance + (vel_total * vel_total) / (2.0f * _accel_cms);
  760. }
  761. // constrain stopping distance
  762. stopping_dist = constrain_float(stopping_dist, 0, _leash);
  763. // convert the stopping distance into a stopping point using velocity vector
  764. stopping_point.x = curr_pos.x + (stopping_dist * curr_vel.x / vel_total);
  765. stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
  766. }
  767. /// get_distance_to_target - get horizontal distance to target position in cm
  768. float AC_PosControl::get_distance_to_target() const
  769. {
  770. return norm(_pos_error.x, _pos_error.y);
  771. }
  772. /// get_bearing_to_target - get bearing to target position in centi-degrees
  773. int32_t AC_PosControl::get_bearing_to_target() const
  774. {
  775. return get_bearing_cd(_inav.get_position(), _pos_target);
  776. }
  777. // is_active_xy - returns true if the xy position controller has been run very recently
  778. bool AC_PosControl::is_active_xy() const
  779. {
  780. return ((AP_HAL::micros64() - _last_update_xy_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
  781. }
  782. /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
  783. float AC_PosControl::get_lean_angle_max_cd() const
  784. {
  785. if (is_zero(_lean_angle_max)) {
  786. return _attitude_control.lean_angle_max();
  787. }
  788. return _lean_angle_max * 100.0f;
  789. }
  790. /// init_xy_controller - initialise the xy controller
  791. /// this should be called after setting the position target and the desired velocity and acceleration
  792. /// sets target roll angle, pitch angle and I terms based on vehicle current lean angles
  793. /// should be called once whenever significant changes to the position target are made
  794. /// this does not update the xy target
  795. void AC_PosControl::init_xy_controller()
  796. {
  797. // set roll, pitch lean angle targets to current attitude
  798. // todo: this should probably be based on the desired attitude not the current attitude
  799. _roll_target = _ahrs.roll_sensor;
  800. _pitch_target = _ahrs.pitch_sensor;
  801. // initialise I terms from lean angles
  802. _pid_vel_xy.reset_filter();
  803. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  804. _pid_vel_xy.set_integrator(_accel_target - _accel_desired);
  805. // flag reset required in rate to accel step
  806. _flags.reset_desired_vel_to_pos = true;
  807. _flags.reset_accel_to_lean_xy = true;
  808. // initialise ekf xy reset handler
  809. init_ekf_xy_reset();
  810. }
  811. /// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
  812. void AC_PosControl::update_xy_controller()
  813. {
  814. // compute dt
  815. const uint64_t now_us = AP_HAL::micros64();
  816. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  817. // sanity check dt
  818. if (dt >= POSCONTROL_ACTIVE_TIMEOUT_US * 1.0e-6f) {
  819. dt = 0.0f;
  820. }
  821. // check for ekf xy position reset
  822. check_for_ekf_xy_reset();
  823. // check if xy leash needs to be recalculated
  824. calc_leash_length_xy();
  825. // translate any adjustments from pilot to loiter target
  826. desired_vel_to_pos(dt);
  827. // run horizontal position controller
  828. run_xy_controller(dt);
  829. // update xy update time
  830. _last_update_xy_us = now_us;
  831. }
  832. float AC_PosControl::time_since_last_xy_update() const
  833. {
  834. const uint64_t now_us = AP_HAL::micros64();
  835. return (now_us - _last_update_xy_us) * 1.0e-6f;
  836. }
  837. // write log to dataflash
  838. void AC_PosControl::write_log()
  839. {
  840. const Vector3f &pos_target = get_pos_target();
  841. const Vector3f &vel_target = get_vel_target();
  842. const Vector3f &accel_target = get_accel_target();
  843. const Vector3f &position = _inav.get_position();
  844. const Vector3f &velocity = _inav.get_velocity();
  845. float accel_x, accel_y;
  846. lean_angles_to_accel(accel_x, accel_y);
  847. AP::logger().Write("PSC",
  848. "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
  849. "smmmmnnnnoooo",
  850. "F000000000000",
  851. "Qffffffffffff",
  852. AP_HAL::micros64(),
  853. double(pos_target.x * 0.01f),
  854. double(pos_target.y * 0.01f),
  855. double(position.x * 0.01f),
  856. double(position.y * 0.01f),
  857. double(vel_target.x * 0.01f),
  858. double(vel_target.y * 0.01f),
  859. double(velocity.x * 0.01f),
  860. double(velocity.y * 0.01f),
  861. double(accel_target.x * 0.01f),
  862. double(accel_target.y * 0.01f),
  863. double(accel_x * 0.01f),
  864. double(accel_y * 0.01f));
  865. }
  866. /// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
  867. void AC_PosControl::init_vel_controller_xyz()
  868. {
  869. // set roll, pitch lean angle targets to current attitude
  870. _roll_target = _ahrs.roll_sensor;
  871. _pitch_target = _ahrs.pitch_sensor;
  872. _pid_vel_xy.reset_filter();
  873. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  874. _pid_vel_xy.set_integrator(_accel_target);
  875. // flag reset required in rate to accel step
  876. _flags.reset_desired_vel_to_pos = true;
  877. _flags.reset_accel_to_lean_xy = true;
  878. // set target position
  879. const Vector3f& curr_pos = _inav.get_position();
  880. set_xy_target(curr_pos.x, curr_pos.y);
  881. set_alt_target(curr_pos.z);
  882. // move current vehicle velocity into feed forward velocity
  883. const Vector3f& curr_vel = _inav.get_velocity();
  884. set_desired_velocity(curr_vel);
  885. // set vehicle acceleration to zero
  886. set_desired_accel_xy(0.0f, 0.0f);
  887. // initialise ekf reset handlers
  888. init_ekf_xy_reset();
  889. init_ekf_z_reset();
  890. }
  891. /// update_velocity_controller_xy - run the velocity controller - should be called at 100hz or higher
  892. /// velocity targets should we set using set_desired_velocity_xy() method
  893. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  894. /// throttle targets will be sent directly to the motors
  895. void AC_PosControl::update_vel_controller_xy()
  896. {
  897. // capture time since last iteration
  898. const uint64_t now_us = AP_HAL::micros64();
  899. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  900. // sanity check dt
  901. if (dt >= 0.2f) {
  902. dt = 0.0f;
  903. }
  904. // check for ekf xy position reset
  905. check_for_ekf_xy_reset();
  906. // check if xy leash needs to be recalculated
  907. calc_leash_length_xy();
  908. // apply desired velocity request to position target
  909. // TODO: this will need to be removed and added to the calling function.
  910. desired_vel_to_pos(dt);
  911. // run position controller
  912. run_xy_controller(dt);
  913. // update xy update time
  914. _last_update_xy_us = now_us;
  915. }
  916. /// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
  917. /// velocity targets should we set using set_desired_velocity_xyz() method
  918. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  919. /// throttle targets will be sent directly to the motors
  920. void AC_PosControl::update_vel_controller_xyz()
  921. {
  922. update_vel_controller_xy();
  923. // update altitude target
  924. set_alt_target_from_climb_rate_ff(_vel_desired.z, _dt, false);
  925. // run z-axis position controller
  926. update_z_controller();
  927. }
  928. float AC_PosControl::get_horizontal_error() const
  929. {
  930. return norm(_pos_error.x, _pos_error.y);
  931. }
  932. ///
  933. /// private methods
  934. ///
  935. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration
  936. /// should be called whenever the speed, acceleration or position kP is modified
  937. void AC_PosControl::calc_leash_length_xy()
  938. {
  939. // todo: remove _flags.recalc_leash_xy or don't call this function after each variable change.
  940. if (_flags.recalc_leash_xy) {
  941. _leash = calc_leash_length(_speed_cms, _accel_cms, _p_pos_xy.kP());
  942. _flags.recalc_leash_xy = false;
  943. }
  944. }
  945. /// move velocity target using desired acceleration
  946. void AC_PosControl::desired_accel_to_vel(float nav_dt)
  947. {
  948. // range check nav_dt
  949. if (nav_dt < 0) {
  950. return;
  951. }
  952. // update target velocity
  953. if (_flags.reset_desired_vel_to_pos) {
  954. _flags.reset_desired_vel_to_pos = false;
  955. } else {
  956. _vel_desired.x += _accel_desired.x * nav_dt;
  957. _vel_desired.y += _accel_desired.y * nav_dt;
  958. }
  959. }
  960. /// desired_vel_to_pos - move position target using desired velocities
  961. void AC_PosControl::desired_vel_to_pos(float nav_dt)
  962. {
  963. // range check nav_dt
  964. if (nav_dt < 0) {
  965. return;
  966. }
  967. // update target position
  968. if (_flags.reset_desired_vel_to_pos) {
  969. _flags.reset_desired_vel_to_pos = false;
  970. } else {
  971. _pos_target.x += _vel_desired.x * nav_dt;
  972. _pos_target.y += _vel_desired.y * nav_dt;
  973. }
  974. }
  975. /// run horizontal position controller correcting position and velocity
  976. /// converts position (_pos_target) to target velocity (_vel_target)
  977. /// desired velocity (_vel_desired) is combined into final target velocity
  978. /// converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  979. /// converts desired accelerations provided in lat/lon frame to roll/pitch angles
  980. void AC_PosControl::run_xy_controller(float dt)
  981. {
  982. float ekfGndSpdLimit, ekfNavVelGainScaler;
  983. AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
  984. Vector3f curr_pos = _inav.get_position();
  985. float kP = ekfNavVelGainScaler * _p_pos_xy.kP(); // scale gains to compensate for noisy optical flow measurement in the EKF
  986. // avoid divide by zero
  987. if (kP <= 0.0f) {
  988. _vel_target.x = 0.0f;
  989. _vel_target.y = 0.0f;
  990. } else {
  991. // calculate distance error
  992. _pos_error.x = _pos_target.x - curr_pos.x;
  993. _pos_error.y = _pos_target.y - curr_pos.y;
  994. // Constrain _pos_error and target position
  995. // Constrain the maximum length of _vel_target to the maximum position correction velocity
  996. // TODO: replace the leash length with a user definable maximum position correction
  997. if (limit_vector_length(_pos_error.x, _pos_error.y, _leash)) {
  998. _pos_target.x = curr_pos.x + _pos_error.x;
  999. _pos_target.y = curr_pos.y + _pos_error.y;
  1000. }
  1001. _vel_target = sqrt_controller(_pos_error, kP, _accel_cms);
  1002. }
  1003. // add velocity feed-forward
  1004. _vel_target.x += _vel_desired.x;
  1005. _vel_target.y += _vel_desired.y;
  1006. // the following section converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  1007. Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
  1008. // check if vehicle velocity is being overridden
  1009. if (_flags.vehicle_horiz_vel_override) {
  1010. _flags.vehicle_horiz_vel_override = false;
  1011. } else {
  1012. _vehicle_horiz_vel.x = _inav.get_velocity().x;
  1013. _vehicle_horiz_vel.y = _inav.get_velocity().y;
  1014. }
  1015. // calculate velocity error
  1016. _vel_error.x = _vel_target.x - _vehicle_horiz_vel.x;
  1017. _vel_error.y = _vel_target.y - _vehicle_horiz_vel.y;
  1018. // TODO: constrain velocity error and velocity target
  1019. // call pi controller
  1020. _pid_vel_xy.set_input(_vel_error);
  1021. // get p
  1022. vel_xy_p = _pid_vel_xy.get_p();
  1023. // update i term if we have not hit the accel or throttle limits OR the i term will reduce
  1024. // TODO: move limit handling into the PI and PID controller
  1025. if (!_limit.accel_xy && !_motors.limit.throttle_upper) {
  1026. vel_xy_i = _pid_vel_xy.get_i();
  1027. } else {
  1028. vel_xy_i = _pid_vel_xy.get_i_shrink();
  1029. }
  1030. // get d
  1031. vel_xy_d = _pid_vel_xy.get_d();
  1032. // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise
  1033. accel_target.x = (vel_xy_p.x + vel_xy_i.x + vel_xy_d.x) * ekfNavVelGainScaler;
  1034. accel_target.y = (vel_xy_p.y + vel_xy_i.y + vel_xy_d.y) * ekfNavVelGainScaler;
  1035. // reset accel to current desired acceleration
  1036. if (_flags.reset_accel_to_lean_xy) {
  1037. _accel_target_filter.reset(Vector2f(accel_target.x, accel_target.y));
  1038. _flags.reset_accel_to_lean_xy = false;
  1039. }
  1040. // filter correction acceleration
  1041. _accel_target_filter.set_cutoff_frequency(MIN(_accel_xy_filt_hz, 5.0f * ekfNavVelGainScaler));
  1042. _accel_target_filter.apply(accel_target, dt);
  1043. // pass the correction acceleration to the target acceleration output
  1044. _accel_target.x = _accel_target_filter.get().x;
  1045. _accel_target.y = _accel_target_filter.get().y;
  1046. // Add feed forward into the target acceleration output
  1047. _accel_target.x += _accel_desired.x;
  1048. _accel_target.y += _accel_desired.y;
  1049. // the following section converts desired accelerations provided in lat/lon frame to roll/pitch angles
  1050. // limit acceleration using maximum lean angles
  1051. float angle_max = MIN(_attitude_control.get_althold_lean_angle_max(), get_lean_angle_max_cd());
  1052. float accel_max = MIN(GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)), POSCONTROL_ACCEL_XY_MAX);
  1053. _limit.accel_xy = limit_vector_length(_accel_target.x, _accel_target.y, accel_max);
  1054. // update angle targets that will be passed to stabilize controller
  1055. accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target);
  1056. }
  1057. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  1058. void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const
  1059. {
  1060. float accel_right, accel_forward;
  1061. // rotate accelerations into body forward-right frame
  1062. // todo: this should probably be based on the desired heading not the current heading
  1063. accel_forward = accel_x_cmss * _ahrs.cos_yaw() + accel_y_cmss * _ahrs.sin_yaw();
  1064. accel_right = -accel_x_cmss * _ahrs.sin_yaw() + accel_y_cmss * _ahrs.cos_yaw();
  1065. // update angle targets that will be passed to stabilize controller
  1066. pitch_target = atanf(-accel_forward / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  1067. float cos_pitch_target = cosf(pitch_target * M_PI / 18000.0f);
  1068. roll_target = atanf(accel_right * cos_pitch_target / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  1069. }
  1070. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  1071. void AC_PosControl::lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const
  1072. {
  1073. // rotate our roll, pitch angles into lat/lon frame
  1074. // todo: this should probably be based on the desired attitude not the current attitude
  1075. accel_x_cmss = (GRAVITY_MSS * 100) * (-_ahrs.cos_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() - _ahrs.sin_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll() * _ahrs.cos_pitch(), 0.5f);
  1076. accel_y_cmss = (GRAVITY_MSS * 100) * (-_ahrs.sin_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() + _ahrs.cos_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll() * _ahrs.cos_pitch(), 0.5f);
  1077. }
  1078. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and position kP gain
  1079. float AC_PosControl::calc_leash_length(float speed_cms, float accel_cms, float kP) const
  1080. {
  1081. float leash_length;
  1082. // sanity check acceleration and avoid divide by zero
  1083. if (accel_cms <= 0.0f) {
  1084. accel_cms = POSCONTROL_ACCELERATION_MIN;
  1085. }
  1086. // avoid divide by zero
  1087. if (kP <= 0.0f) {
  1088. return POSCONTROL_LEASH_LENGTH_MIN;
  1089. }
  1090. // calculate leash length 1/kP 为时间间隔dt
  1091. if (speed_cms <= accel_cms / kP) {
  1092. // linear leash length based on speed close in
  1093. leash_length = speed_cms / kP; //时间间隔很小的时候 V*dt
  1094. } else {
  1095. // leash length grows at sqrt of speed further out //时间间隔比较大的时候 1/2*a*dt^2+ v^2/2/a 这是根据开方器来的 看不懂
  1096. leash_length = (accel_cms / (2.0f * kP * kP)) + (speed_cms * speed_cms / (2.0f * accel_cms));
  1097. }
  1098. // ensure leash is at least 1m long
  1099. if (leash_length < POSCONTROL_LEASH_LENGTH_MIN) {
  1100. leash_length = POSCONTROL_LEASH_LENGTH_MIN;
  1101. }
  1102. return leash_length;
  1103. }
  1104. /// initialise ekf xy position reset check
  1105. void AC_PosControl::init_ekf_xy_reset()
  1106. {
  1107. Vector2f pos_shift;
  1108. _ekf_xy_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  1109. }
  1110. /// check for ekf position reset and adjust loiter or brake target position
  1111. void AC_PosControl::check_for_ekf_xy_reset()
  1112. {
  1113. // check for position shift
  1114. Vector2f pos_shift;
  1115. uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  1116. if (reset_ms != _ekf_xy_reset_ms) {
  1117. shift_pos_xy_target(pos_shift.x * 100.0f, pos_shift.y * 100.0f);
  1118. _ekf_xy_reset_ms = reset_ms;
  1119. }
  1120. }
  1121. /// initialise ekf z axis reset check
  1122. void AC_PosControl::init_ekf_z_reset()
  1123. {
  1124. float alt_shift;
  1125. _ekf_z_reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  1126. }
  1127. /// check for ekf position reset and adjust loiter or brake target position
  1128. void AC_PosControl::check_for_ekf_z_reset()
  1129. {
  1130. // check for position shift
  1131. float alt_shift;
  1132. uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  1133. if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) {
  1134. shift_alt_target(-alt_shift * 100.0f);
  1135. _ekf_z_reset_ms = reset_ms;
  1136. }
  1137. }
  1138. /// limit vector to a given length, returns true if vector was limited
  1139. bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
  1140. {
  1141. float vector_length = norm(vector_x, vector_y);
  1142. if ((vector_length > max_length) && is_positive(vector_length)) {
  1143. vector_x *= (max_length / vector_length);
  1144. vector_y *= (max_length / vector_length);
  1145. return true;
  1146. }
  1147. return false;
  1148. }
  1149. /// Proportional controller with piecewise sqrt sections to constrain second derivative
  1150. Vector3f AC_PosControl::sqrt_controller(const Vector3f& error, float p, float second_ord_lim)
  1151. {
  1152. if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {
  1153. return Vector3f(error.x * p, error.y * p, error.z);
  1154. }
  1155. float linear_dist = second_ord_lim / sq(p);
  1156. float error_length = norm(error.x, error.y);
  1157. if (error_length > linear_dist) {
  1158. float first_order_scale = safe_sqrt(2.0f * second_ord_lim * (error_length - (linear_dist * 0.5f))) / error_length;
  1159. return Vector3f(error.x * first_order_scale, error.y * first_order_scale, error.z);
  1160. } else {
  1161. return Vector3f(error.x * p, error.y * p, error.z);
  1162. }
  1163. }
  1164. bool AC_PosControl::pre_arm_checks(const char *param_prefix,
  1165. char *failure_msg,
  1166. const uint8_t failure_msg_len)
  1167. {
  1168. // validate AC_P members:
  1169. const struct {
  1170. const char *pid_name;
  1171. AC_P &p;
  1172. } ps[] = {
  1173. { "POSXY", get_pos_xy_p() },
  1174. { "POSZ", get_pos_z_p() },
  1175. { "VELZ", get_vel_z_p() },
  1176. };
  1177. for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
  1178. // all AC_P's must have a positive P value:
  1179. if (!is_positive(ps[i].p.kP())) {
  1180. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
  1181. return false;
  1182. }
  1183. }
  1184. // z-axis acceleration control PID doesn't use FF, so P and I must be positive
  1185. if (!is_positive(get_accel_z_pid().kP())) {
  1186. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_P must be > 0", param_prefix);
  1187. return false;
  1188. }
  1189. if (!is_positive(get_accel_z_pid().kI())) {
  1190. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_I must be > 0", param_prefix);
  1191. return false;
  1192. }
  1193. return true;
  1194. }