AC_PosControl.cpp 49 KB

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