AC_PosControl.cpp 49 KB

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