AC_PosControl.cpp 50 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243
  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();
  423. }
  424. /// calc_leash_length - calculates the vertical leash lengths from maximum speed, acceleration
  425. /// called by update_z_controller if z-axis speed or accelerations are changed
  426. void AC_PosControl::calc_leash_length_z()
  427. {
  428. if (_flags.recalc_leash_z) {
  429. _leash_up_z = calc_leash_length(_speed_up_cms, _accel_z_cms, _p_pos_z.kP());
  430. _leash_down_z = calc_leash_length(-_speed_down_cms, _accel_z_cms, _p_pos_z.kP());
  431. _flags.recalc_leash_z = false;
  432. }
  433. }
  434. // run position control for Z axis
  435. // target altitude should be set with one of these functions: set_alt_target, set_target_to_stopping_point_z, init_takeoff
  436. // calculates desired rate in earth-frame z axis and passes to rate controller
  437. // vel_up_max, vel_down_max should have already been set before calling this method
  438. void AC_PosControl::run_z_controller()
  439. {
  440. //float curr_alt = _inav.get_altitude();//12.19
  441. float curr_alt = sub.barometer.get_altitude()*100;//_inav.get_altitude();//12.19
  442. float vel_from_baro = AC_AttitudeControl::sqrt_controller(curr_alt-last_alt, _p_pos_z.kP(), _accel_z_cms, _dt);//12.19
  443. static uint16_t i=0;
  444. uint16_t timecnt = (uint16_t)(0.25/_dt);
  445. i++;
  446. if (i>timecnt)
  447. {
  448. i = 0;
  449. last_alt = curr_alt;//12.19
  450. }
  451. // clear position limit flags
  452. _limit.pos_up = false;
  453. _limit.pos_down = false;
  454. // calculate altitude error
  455. _pos_error.z = _pos_target.z - curr_alt;
  456. // do not let target altitude get too far from current altitude
  457. if (_pos_error.z > _leash_up_z) {
  458. _pos_target.z = curr_alt + _leash_up_z;
  459. _pos_error.z = _leash_up_z;
  460. _limit.pos_up = true;
  461. }
  462. if (_pos_error.z < -_leash_down_z) {
  463. _pos_target.z = curr_alt - _leash_down_z;
  464. _pos_error.z = -_leash_down_z;
  465. _limit.pos_down = true;
  466. }
  467. // calculate _vel_target.z using from _pos_error.z using sqrt controller
  468. _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
  469. // check speed limits
  470. // To-Do: check these speed limits here or in the pos->rate controller
  471. _limit.vel_up = false;
  472. _limit.vel_down = false;
  473. if (_vel_target.z < _speed_down_cms) {
  474. _vel_target.z = _speed_down_cms;
  475. _limit.vel_down = true;
  476. }
  477. if (_vel_target.z > _speed_up_cms) {
  478. _vel_target.z = _speed_up_cms;
  479. _limit.vel_up = true;
  480. }
  481. // add feed forward component
  482. if (_flags.use_desvel_ff_z) {
  483. _vel_target.z += _vel_desired.z;
  484. }
  485. // the following section calculates acceleration required to achieve the velocity target
  486. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  487. Vector3f curr_vel;//12.19
  488. curr_vel.z=vel_from_baro;
  489. // TODO: remove velocity derivative calculation
  490. // reset last velocity target to current target
  491. if (_flags.reset_rate_to_accel_z) {
  492. _vel_last.z = _vel_target.z;
  493. }
  494. // feed forward desired acceleration calculation
  495. if (_dt > 0.0f) {
  496. if (!_flags.freeze_ff_z) {
  497. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  498. } else {
  499. // stop the feed forward being calculated during a known discontinuity
  500. _flags.freeze_ff_z = false;
  501. }
  502. } else {
  503. _accel_desired.z = 0.0f;
  504. }
  505. // store this iteration's velocities for the next iteration
  506. _vel_last.z = _vel_target.z;
  507. // reset velocity error and filter if this controller has just been engaged
  508. if (_flags.reset_rate_to_accel_z) {
  509. // Reset Filter
  510. _vel_error.z = 0;
  511. _vel_error_filter.reset(0);
  512. _flags.reset_rate_to_accel_z = false;
  513. } else {
  514. // calculate rate error and filter with cut off frequency of 2 Hz
  515. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  516. }
  517. _accel_target.z = _p_vel_z.get_p(_vel_error.z);
  518. _accel_target.z += _accel_desired.z;
  519. // the following section calculates a desired throttle needed to achieve the acceleration target
  520. float z_accel_meas; // actual acceleration
  521. // Calculate Earth Frame Z acceleration
  522. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  523. // ensure imax is always large enough to overpower hover throttle
  524. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  525. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  526. }
  527. 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();
  528. // send throttle to attitude controller with angle boost
  529. _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  530. }
  531. ///
  532. /// lateral position controller
  533. ///
  534. /// set_max_accel_xy - set the maximum horizontal acceleration in cm/s/s
  535. void AC_PosControl::set_max_accel_xy(float accel_cmss)
  536. {
  537. if (fabsf(_accel_cms - accel_cmss) > 1.0f) {
  538. _accel_cms = accel_cmss;
  539. _flags.recalc_leash_xy = true;
  540. calc_leash_length_xy();
  541. }
  542. }
  543. /// set_max_speed_xy - set the maximum horizontal speed maximum in cm/s
  544. void AC_PosControl::set_max_speed_xy(float speed_cms)
  545. {
  546. if (fabsf(_speed_cms - speed_cms) > 1.0f) {
  547. _speed_cms = speed_cms;
  548. _flags.recalc_leash_xy = true;
  549. calc_leash_length_xy();
  550. }
  551. }
  552. /// set_pos_target in cm from home
  553. void AC_PosControl::set_pos_target(const Vector3f& position)
  554. {
  555. _pos_target = position;
  556. _flags.use_desvel_ff_z = false;
  557. _vel_desired.z = 0.0f;
  558. // 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
  559. // 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
  560. //_roll_target = constrain_int32(_ahrs.roll_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  561. //_pitch_target = constrain_int32(_ahrs.pitch_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  562. }
  563. /// set_xy_target in cm from home
  564. void AC_PosControl::set_xy_target(float x, float y)
  565. {
  566. _pos_target.x = x;
  567. _pos_target.y = y;
  568. }
  569. /// shift position target target in x, y axis
  570. void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
  571. {
  572. // move pos controller target
  573. _pos_target.x += x_cm;
  574. _pos_target.y += y_cm;
  575. }
  576. /// set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from home
  577. void AC_PosControl::set_target_to_stopping_point_xy()
  578. {
  579. // check if xy leash needs to be recalculated
  580. calc_leash_length_xy();
  581. get_stopping_point_xy(_pos_target);
  582. }
  583. /// get_stopping_point_xy - calculates stopping point based on current position, velocity, vehicle acceleration
  584. /// distance_max allows limiting distance to stopping point
  585. /// results placed in stopping_position vector
  586. /// set_max_accel_xy() should be called before this method to set vehicle acceleration
  587. /// set_leash_length() should have been called before this method
  588. void AC_PosControl::get_stopping_point_xy(Vector3f &stopping_point) const
  589. {
  590. const Vector3f curr_pos = _inav.get_position();
  591. Vector3f curr_vel = _inav.get_velocity();
  592. float linear_distance; // the distance at which we swap from a linear to sqrt response
  593. float linear_velocity; // the velocity above which we swap from a linear to sqrt response
  594. float stopping_dist; // the distance within the vehicle can stop
  595. float kP = _p_pos_xy.kP();
  596. // add velocity error to current velocity
  597. if (is_active_xy()) {
  598. curr_vel.x += _vel_error.x;
  599. curr_vel.y += _vel_error.y;
  600. }
  601. // calculate current velocity
  602. float vel_total = norm(curr_vel.x, curr_vel.y);
  603. // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
  604. if (kP <= 0.0f || _accel_cms <= 0.0f || is_zero(vel_total)) {
  605. stopping_point.x = curr_pos.x;
  606. stopping_point.y = curr_pos.y;
  607. return;
  608. }
  609. // calculate point at which velocity switches from linear to sqrt
  610. linear_velocity = _accel_cms / kP;
  611. // calculate distance within which we can stop
  612. if (vel_total < linear_velocity) {
  613. stopping_dist = vel_total / kP;
  614. } else {
  615. linear_distance = _accel_cms / (2.0f * kP * kP);
  616. stopping_dist = linear_distance + (vel_total * vel_total) / (2.0f * _accel_cms);
  617. }
  618. // constrain stopping distance
  619. stopping_dist = constrain_float(stopping_dist, 0, _leash);
  620. // convert the stopping distance into a stopping point using velocity vector
  621. stopping_point.x = curr_pos.x + (stopping_dist * curr_vel.x / vel_total);
  622. stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
  623. }
  624. /// get_distance_to_target - get horizontal distance to target position in cm
  625. float AC_PosControl::get_distance_to_target() const
  626. {
  627. return norm(_pos_error.x, _pos_error.y);
  628. }
  629. /// get_bearing_to_target - get bearing to target position in centi-degrees
  630. int32_t AC_PosControl::get_bearing_to_target() const
  631. {
  632. return get_bearing_cd(_inav.get_position(), _pos_target);
  633. }
  634. // is_active_xy - returns true if the xy position controller has been run very recently
  635. bool AC_PosControl::is_active_xy() const
  636. {
  637. return ((AP_HAL::micros64() - _last_update_xy_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
  638. }
  639. /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
  640. float AC_PosControl::get_lean_angle_max_cd() const
  641. {
  642. if (is_zero(_lean_angle_max)) {
  643. return _attitude_control.lean_angle_max();
  644. }
  645. return _lean_angle_max * 100.0f;
  646. }
  647. /// init_xy_controller - initialise the xy controller
  648. /// this should be called after setting the position target and the desired velocity and acceleration
  649. /// sets target roll angle, pitch angle and I terms based on vehicle current lean angles
  650. /// should be called once whenever significant changes to the position target are made
  651. /// this does not update the xy target
  652. void AC_PosControl::init_xy_controller()
  653. {
  654. // set roll, pitch lean angle targets to current attitude
  655. // todo: this should probably be based on the desired attitude not the current attitude
  656. _roll_target = _ahrs.roll_sensor;
  657. _pitch_target = _ahrs.pitch_sensor;
  658. // initialise I terms from lean angles
  659. _pid_vel_xy.reset_filter();
  660. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  661. _pid_vel_xy.set_integrator(_accel_target - _accel_desired);
  662. // flag reset required in rate to accel step
  663. _flags.reset_desired_vel_to_pos = true;
  664. _flags.reset_accel_to_lean_xy = true;
  665. // initialise ekf xy reset handler
  666. init_ekf_xy_reset();
  667. }
  668. /// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
  669. void AC_PosControl::update_xy_controller()
  670. {
  671. // compute dt
  672. const uint64_t now_us = AP_HAL::micros64();
  673. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  674. // sanity check dt
  675. if (dt >= POSCONTROL_ACTIVE_TIMEOUT_US * 1.0e-6f) {
  676. dt = 0.0f;
  677. }
  678. // check for ekf xy position reset
  679. check_for_ekf_xy_reset();
  680. // check if xy leash needs to be recalculated
  681. calc_leash_length_xy();
  682. // translate any adjustments from pilot to loiter target
  683. desired_vel_to_pos(dt);
  684. // run horizontal position controller
  685. run_xy_controller(dt);
  686. // update xy update time
  687. _last_update_xy_us = now_us;
  688. }
  689. float AC_PosControl::time_since_last_xy_update() const
  690. {
  691. const uint64_t now_us = AP_HAL::micros64();
  692. return (now_us - _last_update_xy_us) * 1.0e-6f;
  693. }
  694. // write log to dataflash
  695. void AC_PosControl::write_log()
  696. {
  697. const Vector3f &pos_target = get_pos_target();
  698. const Vector3f &vel_target = get_vel_target();
  699. const Vector3f &accel_target = get_accel_target();
  700. const Vector3f &position = _inav.get_position();
  701. const Vector3f &velocity = _inav.get_velocity();
  702. float accel_x, accel_y;
  703. lean_angles_to_accel(accel_x, accel_y);
  704. AP::logger().Write("PSC",
  705. "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
  706. "smmmmnnnnoooo",
  707. "F000000000000",
  708. "Qffffffffffff",
  709. AP_HAL::micros64(),
  710. double(pos_target.x * 0.01f),
  711. double(pos_target.y * 0.01f),
  712. double(position.x * 0.01f),
  713. double(position.y * 0.01f),
  714. double(vel_target.x * 0.01f),
  715. double(vel_target.y * 0.01f),
  716. double(velocity.x * 0.01f),
  717. double(velocity.y * 0.01f),
  718. double(accel_target.x * 0.01f),
  719. double(accel_target.y * 0.01f),
  720. double(accel_x * 0.01f),
  721. double(accel_y * 0.01f));
  722. }
  723. /// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
  724. void AC_PosControl::init_vel_controller_xyz()
  725. {
  726. // set roll, pitch lean angle targets to current attitude
  727. _roll_target = _ahrs.roll_sensor;
  728. _pitch_target = _ahrs.pitch_sensor;
  729. _pid_vel_xy.reset_filter();
  730. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  731. _pid_vel_xy.set_integrator(_accel_target);
  732. // flag reset required in rate to accel step
  733. _flags.reset_desired_vel_to_pos = true;
  734. _flags.reset_accel_to_lean_xy = true;
  735. // set target position
  736. const Vector3f& curr_pos = _inav.get_position();
  737. set_xy_target(curr_pos.x, curr_pos.y);
  738. set_alt_target(curr_pos.z);
  739. // move current vehicle velocity into feed forward velocity
  740. const Vector3f& curr_vel = _inav.get_velocity();
  741. set_desired_velocity(curr_vel);
  742. // set vehicle acceleration to zero
  743. set_desired_accel_xy(0.0f, 0.0f);
  744. // initialise ekf reset handlers
  745. init_ekf_xy_reset();
  746. init_ekf_z_reset();
  747. }
  748. /// update_velocity_controller_xy - run the velocity controller - should be called at 100hz or higher
  749. /// velocity targets should we set using set_desired_velocity_xy() method
  750. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  751. /// throttle targets will be sent directly to the motors
  752. void AC_PosControl::update_vel_controller_xy()
  753. {
  754. // capture time since last iteration
  755. const uint64_t now_us = AP_HAL::micros64();
  756. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  757. // sanity check dt
  758. if (dt >= 0.2f) {
  759. dt = 0.0f;
  760. }
  761. // check for ekf xy position reset
  762. check_for_ekf_xy_reset();
  763. // check if xy leash needs to be recalculated
  764. calc_leash_length_xy();
  765. // apply desired velocity request to position target
  766. // TODO: this will need to be removed and added to the calling function.
  767. desired_vel_to_pos(dt);
  768. // run position controller
  769. run_xy_controller(dt);
  770. // update xy update time
  771. _last_update_xy_us = now_us;
  772. }
  773. /// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
  774. /// velocity targets should we set using set_desired_velocity_xyz() method
  775. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  776. /// throttle targets will be sent directly to the motors
  777. void AC_PosControl::update_vel_controller_xyz()
  778. {
  779. update_vel_controller_xy();
  780. // update altitude target
  781. set_alt_target_from_climb_rate_ff(_vel_desired.z, _dt, false);
  782. // run z-axis position controller
  783. update_z_controller();
  784. }
  785. float AC_PosControl::get_horizontal_error() const
  786. {
  787. return norm(_pos_error.x, _pos_error.y);
  788. }
  789. ///
  790. /// private methods
  791. ///
  792. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration
  793. /// should be called whenever the speed, acceleration or position kP is modified
  794. void AC_PosControl::calc_leash_length_xy()
  795. {
  796. // todo: remove _flags.recalc_leash_xy or don't call this function after each variable change.
  797. if (_flags.recalc_leash_xy) {
  798. _leash = calc_leash_length(_speed_cms, _accel_cms, _p_pos_xy.kP());
  799. _flags.recalc_leash_xy = false;
  800. }
  801. }
  802. /// move velocity target using desired acceleration
  803. void AC_PosControl::desired_accel_to_vel(float nav_dt)
  804. {
  805. // range check nav_dt
  806. if (nav_dt < 0) {
  807. return;
  808. }
  809. // update target velocity
  810. if (_flags.reset_desired_vel_to_pos) {
  811. _flags.reset_desired_vel_to_pos = false;
  812. } else {
  813. _vel_desired.x += _accel_desired.x * nav_dt;
  814. _vel_desired.y += _accel_desired.y * nav_dt;
  815. }
  816. }
  817. /// desired_vel_to_pos - move position target using desired velocities
  818. void AC_PosControl::desired_vel_to_pos(float nav_dt)
  819. {
  820. // range check nav_dt
  821. if (nav_dt < 0) {
  822. return;
  823. }
  824. // update target position
  825. if (_flags.reset_desired_vel_to_pos) {
  826. _flags.reset_desired_vel_to_pos = false;
  827. } else {
  828. _pos_target.x += _vel_desired.x * nav_dt;
  829. _pos_target.y += _vel_desired.y * nav_dt;
  830. }
  831. }
  832. /// run horizontal position controller correcting position and velocity
  833. /// converts position (_pos_target) to target velocity (_vel_target)
  834. /// desired velocity (_vel_desired) is combined into final target velocity
  835. /// converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  836. /// converts desired accelerations provided in lat/lon frame to roll/pitch angles
  837. void AC_PosControl::run_xy_controller(float dt)
  838. {
  839. float ekfGndSpdLimit, ekfNavVelGainScaler;
  840. AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
  841. Vector3f curr_pos = _inav.get_position();
  842. float kP = ekfNavVelGainScaler * _p_pos_xy.kP(); // scale gains to compensate for noisy optical flow measurement in the EKF
  843. // avoid divide by zero
  844. if (kP <= 0.0f) {
  845. _vel_target.x = 0.0f;
  846. _vel_target.y = 0.0f;
  847. } else {
  848. // calculate distance error
  849. _pos_error.x = _pos_target.x - curr_pos.x;
  850. _pos_error.y = _pos_target.y - curr_pos.y;
  851. // Constrain _pos_error and target position
  852. // Constrain the maximum length of _vel_target to the maximum position correction velocity
  853. // TODO: replace the leash length with a user definable maximum position correction
  854. if (limit_vector_length(_pos_error.x, _pos_error.y, _leash)) {
  855. _pos_target.x = curr_pos.x + _pos_error.x;
  856. _pos_target.y = curr_pos.y + _pos_error.y;
  857. }
  858. _vel_target = sqrt_controller(_pos_error, kP, _accel_cms);
  859. }
  860. // add velocity feed-forward
  861. _vel_target.x += _vel_desired.x;
  862. _vel_target.y += _vel_desired.y;
  863. // the following section converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  864. Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
  865. // check if vehicle velocity is being overridden
  866. if (_flags.vehicle_horiz_vel_override) {
  867. _flags.vehicle_horiz_vel_override = false;
  868. } else {
  869. _vehicle_horiz_vel.x = _inav.get_velocity().x;
  870. _vehicle_horiz_vel.y = _inav.get_velocity().y;
  871. }
  872. // calculate velocity error
  873. _vel_error.x = _vel_target.x - _vehicle_horiz_vel.x;
  874. _vel_error.y = _vel_target.y - _vehicle_horiz_vel.y;
  875. // TODO: constrain velocity error and velocity target
  876. // call pi controller
  877. _pid_vel_xy.set_input(_vel_error);
  878. // get p
  879. vel_xy_p = _pid_vel_xy.get_p();
  880. // update i term if we have not hit the accel or throttle limits OR the i term will reduce
  881. // TODO: move limit handling into the PI and PID controller
  882. if (!_limit.accel_xy && !_motors.limit.throttle_upper) {
  883. vel_xy_i = _pid_vel_xy.get_i();
  884. } else {
  885. vel_xy_i = _pid_vel_xy.get_i_shrink();
  886. }
  887. // get d
  888. vel_xy_d = _pid_vel_xy.get_d();
  889. // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise
  890. accel_target.x = (vel_xy_p.x + vel_xy_i.x + vel_xy_d.x) * ekfNavVelGainScaler;
  891. accel_target.y = (vel_xy_p.y + vel_xy_i.y + vel_xy_d.y) * ekfNavVelGainScaler;
  892. // reset accel to current desired acceleration
  893. if (_flags.reset_accel_to_lean_xy) {
  894. _accel_target_filter.reset(Vector2f(accel_target.x, accel_target.y));
  895. _flags.reset_accel_to_lean_xy = false;
  896. }
  897. // filter correction acceleration
  898. _accel_target_filter.set_cutoff_frequency(MIN(_accel_xy_filt_hz, 5.0f * ekfNavVelGainScaler));
  899. _accel_target_filter.apply(accel_target, dt);
  900. // pass the correction acceleration to the target acceleration output
  901. _accel_target.x = _accel_target_filter.get().x;
  902. _accel_target.y = _accel_target_filter.get().y;
  903. // Add feed forward into the target acceleration output
  904. _accel_target.x += _accel_desired.x;
  905. _accel_target.y += _accel_desired.y;
  906. // the following section converts desired accelerations provided in lat/lon frame to roll/pitch angles
  907. // limit acceleration using maximum lean angles
  908. float angle_max = MIN(_attitude_control.get_althold_lean_angle_max(), get_lean_angle_max_cd());
  909. float accel_max = MIN(GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)), POSCONTROL_ACCEL_XY_MAX);
  910. _limit.accel_xy = limit_vector_length(_accel_target.x, _accel_target.y, accel_max);
  911. // update angle targets that will be passed to stabilize controller
  912. accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target);
  913. }
  914. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  915. void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const
  916. {
  917. float accel_right, accel_forward;
  918. // rotate accelerations into body forward-right frame
  919. // todo: this should probably be based on the desired heading not the current heading
  920. accel_forward = accel_x_cmss * _ahrs.cos_yaw() + accel_y_cmss * _ahrs.sin_yaw();
  921. accel_right = -accel_x_cmss * _ahrs.sin_yaw() + accel_y_cmss * _ahrs.cos_yaw();
  922. // update angle targets that will be passed to stabilize controller
  923. pitch_target = atanf(-accel_forward / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  924. float cos_pitch_target = cosf(pitch_target * M_PI / 18000.0f);
  925. roll_target = atanf(accel_right * cos_pitch_target / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  926. }
  927. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  928. void AC_PosControl::lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const
  929. {
  930. // rotate our roll, pitch angles into lat/lon frame
  931. // todo: this should probably be based on the desired attitude not the current attitude
  932. 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);
  933. 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);
  934. }
  935. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and position kP gain
  936. float AC_PosControl::calc_leash_length(float speed_cms, float accel_cms, float kP) const
  937. {
  938. float leash_length;
  939. // sanity check acceleration and avoid divide by zero
  940. if (accel_cms <= 0.0f) {
  941. accel_cms = POSCONTROL_ACCELERATION_MIN;
  942. }
  943. // avoid divide by zero
  944. if (kP <= 0.0f) {
  945. return POSCONTROL_LEASH_LENGTH_MIN;
  946. }
  947. // calculate leash length 1/kP 为时间间隔dt
  948. if (speed_cms <= accel_cms / kP) {
  949. // linear leash length based on speed close in
  950. leash_length = speed_cms / kP; //时间间隔很小的时候 V*dt
  951. } else {
  952. // leash length grows at sqrt of speed further out //时间间隔比较大的时候 1/2*a*dt^2+ v^2/2/a 这是根据开方器来的 看不懂
  953. leash_length = (accel_cms / (2.0f * kP * kP)) + (speed_cms * speed_cms / (2.0f * accel_cms));
  954. }
  955. // ensure leash is at least 1m long
  956. if (leash_length < POSCONTROL_LEASH_LENGTH_MIN) {
  957. leash_length = POSCONTROL_LEASH_LENGTH_MIN;
  958. }
  959. return leash_length;
  960. }
  961. /// initialise ekf xy position reset check
  962. void AC_PosControl::init_ekf_xy_reset()
  963. {
  964. Vector2f pos_shift;
  965. _ekf_xy_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  966. }
  967. /// check for ekf position reset and adjust loiter or brake target position
  968. void AC_PosControl::check_for_ekf_xy_reset()
  969. {
  970. // check for position shift
  971. Vector2f pos_shift;
  972. uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  973. if (reset_ms != _ekf_xy_reset_ms) {
  974. shift_pos_xy_target(pos_shift.x * 100.0f, pos_shift.y * 100.0f);
  975. _ekf_xy_reset_ms = reset_ms;
  976. }
  977. }
  978. /// initialise ekf z axis reset check
  979. void AC_PosControl::init_ekf_z_reset()
  980. {
  981. float alt_shift;
  982. _ekf_z_reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  983. }
  984. /// check for ekf position reset and adjust loiter or brake target position
  985. void AC_PosControl::check_for_ekf_z_reset()
  986. {
  987. // check for position shift
  988. float alt_shift;
  989. uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  990. if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) {
  991. shift_alt_target(-alt_shift * 100.0f);
  992. _ekf_z_reset_ms = reset_ms;
  993. }
  994. }
  995. /// limit vector to a given length, returns true if vector was limited
  996. bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
  997. {
  998. float vector_length = norm(vector_x, vector_y);
  999. if ((vector_length > max_length) && is_positive(vector_length)) {
  1000. vector_x *= (max_length / vector_length);
  1001. vector_y *= (max_length / vector_length);
  1002. return true;
  1003. }
  1004. return false;
  1005. }
  1006. /// Proportional controller with piecewise sqrt sections to constrain second derivative
  1007. Vector3f AC_PosControl::sqrt_controller(const Vector3f& error, float p, float second_ord_lim)
  1008. {
  1009. if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {
  1010. return Vector3f(error.x * p, error.y * p, error.z);
  1011. }
  1012. float linear_dist = second_ord_lim / sq(p);
  1013. float error_length = norm(error.x, error.y);
  1014. if (error_length > linear_dist) {
  1015. float first_order_scale = safe_sqrt(2.0f * second_ord_lim * (error_length - (linear_dist * 0.5f))) / error_length;
  1016. return Vector3f(error.x * first_order_scale, error.y * first_order_scale, error.z);
  1017. } else {
  1018. return Vector3f(error.x * p, error.y * p, error.z);
  1019. }
  1020. }
  1021. bool AC_PosControl::pre_arm_checks(const char *param_prefix,
  1022. char *failure_msg,
  1023. const uint8_t failure_msg_len)
  1024. {
  1025. // validate AC_P members:
  1026. const struct {
  1027. const char *pid_name;
  1028. AC_P &p;
  1029. } ps[] = {
  1030. { "POSXY", get_pos_xy_p() },
  1031. { "POSZ", get_pos_z_p() },
  1032. { "VELZ", get_vel_z_p() },
  1033. };
  1034. for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
  1035. // all AC_P's must have a positive P value:
  1036. if (!is_positive(ps[i].p.kP())) {
  1037. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
  1038. return false;
  1039. }
  1040. }
  1041. // z-axis acceleration control PID doesn't use FF, so P and I must be positive
  1042. if (!is_positive(get_accel_z_pid().kP())) {
  1043. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_P must be > 0", param_prefix);
  1044. return false;
  1045. }
  1046. if (!is_positive(get_accel_z_pid().kI())) {
  1047. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_I must be > 0", param_prefix);
  1048. return false;
  1049. }
  1050. return true;
  1051. }