AC_PosControl.bak 59 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541
  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. alt_rate(10.0)
  190. {
  191. AP_Param::setup_object_defaults(this, var_info);
  192. // initialise flags
  193. _flags.recalc_leash_z = true;
  194. _flags.recalc_leash_xy = true;
  195. _flags.reset_desired_vel_to_pos = true;
  196. _flags.reset_accel_to_lean_xy = true;
  197. _flags.reset_rate_to_accel_z = true;
  198. _flags.freeze_ff_z = true;
  199. _flags.use_desvel_ff_z = true;
  200. _limit.pos_up = true;
  201. _limit.pos_down = true;
  202. _limit.vel_up = true;
  203. _limit.vel_down = true;
  204. _limit.accel_xy = true;
  205. }
  206. ///
  207. /// z-axis position controller
  208. ///
  209. /// set_dt - sets time delta in seconds for all controllers (i.e. 100hz = 0.01, 400hz = 0.0025)
  210. void AC_PosControl::set_dt(float delta_sec)
  211. {
  212. _dt = delta_sec;
  213. // update PID controller dt
  214. _pid_accel_z.set_dt(_dt);
  215. _pid_vel_xy.set_dt(_dt);
  216. // update rate z-axis velocity error and accel error filters
  217. _vel_error_filter.set_cutoff_frequency(POSCONTROL_VEL_ERROR_CUTOFF_FREQ);
  218. }
  219. /// set_max_speed_z - set the maximum climb and descent rates
  220. /// To-Do: call this in the main code as part of flight mode initialisation
  221. void AC_PosControl::set_max_speed_z(float speed_down, float speed_up)
  222. {
  223. // ensure speed_down is always negative
  224. speed_down = -fabsf(speed_down);
  225. //默认_speed_down_cms -150 ,,_speed_up_cms 250
  226. if ((fabsf(_speed_down_cms - speed_down) > 1.0f) || (fabsf(_speed_up_cms - speed_up) > 1.0f)) {
  227. _speed_down_cms = speed_down;
  228. _speed_up_cms = speed_up;
  229. _flags.recalc_leash_z = true;
  230. calc_leash_length_z();// 刹车长度
  231. }
  232. }
  233. /// set_max_accel_z - set the maximum vertical acceleration in cm/s/s
  234. void AC_PosControl::set_max_accel_z(float accel_cmss)
  235. {
  236. if (fabsf(_accel_z_cms - accel_cmss) > 1.0f) {
  237. _accel_z_cms = accel_cmss;
  238. _flags.recalc_leash_z = true;
  239. calc_leash_length_z();
  240. }
  241. }
  242. /// set_alt_target_with_slew - adjusts target towards a final altitude target
  243. /// should be called continuously (with dt set to be the expected time between calls)
  244. /// actual position target will be moved no faster than the speed_down and speed_up
  245. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  246. void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
  247. {
  248. float alt_change = alt_cm - _pos_target.z;
  249. // do not use z-axis desired velocity feed forward
  250. _flags.use_desvel_ff_z = false;
  251. // adjust desired alt if motors have not hit their limits
  252. if ((alt_change < 0 && !_motors.limit.throttle_lower) || (alt_change > 0 && !_motors.limit.throttle_upper)) {
  253. if (!is_zero(dt)) {
  254. float climb_rate_cms = constrain_float(alt_change / dt, _speed_down_cms, _speed_up_cms);
  255. _pos_target.z += climb_rate_cms * dt;
  256. _vel_desired.z = climb_rate_cms; // recorded for reporting purposes
  257. }
  258. } else {
  259. // recorded for reporting purposes
  260. _vel_desired.z = 0.0f;
  261. }
  262. // do not let target get too far from current altitude
  263. float curr_alt = _inav.get_altitude();
  264. _pos_target.z = constrain_float(_pos_target.z, curr_alt - _leash_down_z, curr_alt + _leash_up_z);
  265. }
  266. /// set_alt_target_from_climb_rate - adjusts target up or down using a climb rate in cm/s
  267. /// should be called continuously (with dt set to be the expected time between calls)
  268. /// actual position target will be moved no faster than the speed_down and speed_up
  269. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  270. void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
  271. {
  272. // adjust desired alt if motors have not hit their limits
  273. // To-Do: add check of _limit.pos_down?
  274. if ((climb_rate_cms < 0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  275. _pos_target.z += climb_rate_cms * dt;
  276. }
  277. // do not use z-axis desired velocity feed forward
  278. // vel_desired set to desired climb rate for reporting and land-detector
  279. _flags.use_desvel_ff_z = false;
  280. _vel_desired.z = climb_rate_cms;
  281. }
  282. /// set_alt_target_from_climb_rate_ff - adjusts target up or down using a climb rate in cm/s using feed-forward
  283. /// should be called continuously (with dt set to be the expected time between calls)
  284. /// actual position target will be moved no faster than the speed_down and speed_up
  285. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  286. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  287. void AC_PosControl::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
  288. {
  289. // calculated increased maximum acceleration if over speed
  290. float accel_z_cms = _accel_z_cms;
  291. if (_vel_desired.z < _speed_down_cms && !is_zero(_speed_down_cms)) {
  292. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_down_cms;
  293. }
  294. if (_vel_desired.z > _speed_up_cms && !is_zero(_speed_up_cms)) {
  295. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_up_cms;
  296. }
  297. accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
  298. // jerk_z is calculated to reach full acceleration in 1000ms.
  299. float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
  300. float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f * fabsf(_vel_desired.z - climb_rate_cms) * jerk_z));
  301. _accel_last_z_cms += jerk_z * dt;
  302. _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
  303. float vel_change_limit = _accel_last_z_cms * dt;
  304. _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z - vel_change_limit, _vel_desired.z + vel_change_limit);
  305. _flags.use_desvel_ff_z = true;
  306. // adjust desired alt if motors have not hit their limits
  307. // To-Do: add check of _limit.pos_down?
  308. if ((_vel_desired.z < 0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  309. _pos_target.z += _vel_desired.z * dt;
  310. }
  311. }
  312. /// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
  313. /// should be called continuously (with dt set to be the expected time between calls)
  314. /// almost no checks are performed on the input
  315. void AC_PosControl::add_takeoff_climb_rate(float climb_rate_cms, float dt)
  316. {
  317. _pos_target.z += climb_rate_cms * dt;
  318. }
  319. /// shift altitude target (positive means move altitude up)
  320. void AC_PosControl::shift_alt_target(float z_cm)
  321. {
  322. _pos_target.z += z_cm;
  323. // freeze feedforward to avoid jump
  324. if (!is_zero(z_cm)) {
  325. freeze_ff_z();
  326. }
  327. }
  328. /// relax_alt_hold_controllers - set all desired and targets to measured
  329. void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
  330. {
  331. _pos_target.z = _inav.get_altitude();
  332. _vel_desired.z = 0.0f;
  333. _flags.use_desvel_ff_z = false;
  334. _vel_target.z = _inav.get_velocity_z();
  335. _vel_last.z = _inav.get_velocity_z();
  336. _accel_desired.z = 0.0f;
  337. _accel_last_z_cms = 0.0f;
  338. _flags.reset_rate_to_accel_z = true;
  339. _pid_accel_z.set_integrator((throttle_setting - _motors.get_throttle_hover()) * 1000.0f);
  340. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  341. _pid_accel_z.reset_filter();
  342. }
  343. // get_alt_error - returns altitude error in cm
  344. float AC_PosControl::get_alt_error() const
  345. {
  346. return (_pos_target.z - _inav.get_altitude());
  347. }
  348. /// set_target_to_stopping_point_z - returns reasonable stopping altitude in cm above home
  349. void AC_PosControl::set_target_to_stopping_point_z()
  350. {
  351. // check if z leash needs to be recalculated
  352. calc_leash_length_z();
  353. get_stopping_point_z(_pos_target);
  354. }
  355. /// get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
  356. void AC_PosControl::get_stopping_point_z(Vector3f& stopping_point) const
  357. {
  358. const float curr_pos_z = _inav.get_altitude();
  359. float curr_vel_z = _inav.get_velocity_z();
  360. float linear_distance; // half the distance we swap between linear and sqrt and the distance we offset sqrt
  361. float linear_velocity; // the velocity we swap between linear and sqrt
  362. // if position controller is active add current velocity error to avoid sudden jump in acceleration
  363. if (is_active_z()) {
  364. curr_vel_z += _vel_error.z;
  365. if (_flags.use_desvel_ff_z) {
  366. curr_vel_z -= _vel_desired.z;
  367. }
  368. }
  369. // avoid divide by zero by using current position if kP is very low or acceleration is zero
  370. if (_p_pos_z.kP() <= 0.0f || _accel_z_cms <= 0.0f) {
  371. stopping_point.z = curr_pos_z;
  372. return;
  373. }
  374. // calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
  375. linear_velocity = _accel_z_cms / _p_pos_z.kP();
  376. if (fabsf(curr_vel_z) < linear_velocity) {
  377. // if our current velocity is below the cross-over point we use a linear function
  378. stopping_point.z = curr_pos_z + curr_vel_z / _p_pos_z.kP();
  379. } else {
  380. linear_distance = _accel_z_cms / (2.0f * _p_pos_z.kP() * _p_pos_z.kP());
  381. if (curr_vel_z > 0) {
  382. stopping_point.z = curr_pos_z + (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
  383. } else {
  384. stopping_point.z = curr_pos_z - (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
  385. }
  386. }
  387. stopping_point.z = constrain_float(stopping_point.z, curr_pos_z - POSCONTROL_STOPPING_DIST_DOWN_MAX, curr_pos_z + POSCONTROL_STOPPING_DIST_UP_MAX);
  388. }
  389. /// init_takeoff - initialises target altitude if we are taking off
  390. void AC_PosControl::init_takeoff()
  391. {
  392. const Vector3f& curr_pos = _inav.get_position();
  393. _pos_target.z = curr_pos.z;
  394. // freeze feedforward to avoid jump
  395. freeze_ff_z();
  396. // shift difference between last motor out and hover throttle into accelerometer I
  397. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  398. // initialise ekf reset handler
  399. init_ekf_z_reset();
  400. }
  401. // is_active_z - returns true if the z-axis position controller has been run very recently
  402. bool AC_PosControl::is_active_z() const
  403. {
  404. return ((AP_HAL::micros64() - _last_update_z_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
  405. }
  406. /// update_z_controller - fly to altitude in cm above home
  407. void AC_PosControl::update_z_controller()
  408. {
  409. // check time since last cast
  410. const uint64_t now_us = AP_HAL::micros64();
  411. if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
  412. _flags.reset_rate_to_accel_z = true;
  413. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  414. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  415. _pid_accel_z.reset_filter();
  416. }
  417. _last_update_z_us = now_us;
  418. // check for ekf altitude reset
  419. //check_for_ekf_z_reset();
  420. // check if leash lengths need to be recalculated
  421. calc_leash_length_z();
  422. // call z-axis position controller
  423. run_z_controller();
  424. }
  425. float AC_PosControl::update_z_controller_f()
  426. {
  427. // check time since last cast
  428. const uint64_t now_us = AP_HAL::micros64();
  429. if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
  430. _flags.reset_rate_to_accel_z = true;
  431. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  432. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  433. _pid_accel_z.reset_filter();
  434. }
  435. _last_update_z_us = now_us;
  436. // check for ekf altitude reset
  437. //check_for_ekf_z_reset();
  438. // check if leash lengths need to be recalculated
  439. calc_leash_length_z();
  440. // call z-axis position controller
  441. return run_z_controller_f();
  442. }
  443. /// calc_leash_length - calculates the vertical leash lengths from maximum speed, acceleration
  444. /// called by update_z_controller if z-axis speed or accelerations are changed
  445. void AC_PosControl::calc_leash_length_z()
  446. {
  447. if (_flags.recalc_leash_z) {
  448. _leash_up_z = calc_leash_length(_speed_up_cms, _accel_z_cms, _p_pos_z.kP());
  449. _leash_down_z = calc_leash_length(-_speed_down_cms, _accel_z_cms, _p_pos_z.kP());
  450. _flags.recalc_leash_z = false;
  451. }
  452. }
  453. // run position control for Z axis
  454. // target altitude should be set with one of these functions: set_alt_target, set_target_to_stopping_point_z, init_takeoff
  455. // calculates desired rate in earth-frame z axis and passes to rate controller
  456. // vel_up_max, vel_down_max should have already been set before calling this method
  457. void AC_PosControl::run_z_controller()
  458. {
  459. //float curr_alt = _inav.get_altitude();//12.19
  460. float curr_alt = sub.barometer.get_altitude()*100;//_inav.get_altitude();//12.19
  461. // clear position limit flags
  462. _limit.pos_up = false;
  463. _limit.pos_down = false;
  464. // calculate altitude error
  465. _pos_error.z = _pos_target.z - curr_alt;
  466. // do not let target altitude get too far from current altitude
  467. if (_pos_error.z > _leash_up_z) {
  468. _pos_target.z = curr_alt + _leash_up_z;
  469. _pos_error.z = _leash_up_z;
  470. _limit.pos_up = true;
  471. }
  472. if (_pos_error.z < -_leash_down_z) {
  473. _pos_target.z = curr_alt - _leash_down_z;
  474. _pos_error.z = -_leash_down_z;
  475. _limit.pos_down = true;
  476. }
  477. // calculate _vel_target.z using from _pos_error.z using sqrt controller
  478. _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
  479. // check speed limits
  480. // To-Do: check these speed limits here or in the pos->rate controller
  481. _limit.vel_up = false;
  482. _limit.vel_down = false;
  483. if (_vel_target.z < _speed_down_cms) {
  484. _vel_target.z = _speed_down_cms;
  485. _limit.vel_down = true;
  486. }
  487. if (_vel_target.z > _speed_up_cms) {
  488. _vel_target.z = _speed_up_cms;
  489. _limit.vel_up = true;
  490. }
  491. // add feed forward component
  492. if (_flags.use_desvel_ff_z) {
  493. _vel_target.z += _vel_desired.z;
  494. }
  495. // the following section calculates acceleration required to achieve the velocity target
  496. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  497. Vector3f curr_vel;//12.19
  498. curr_vel.z=alt_rate.get();
  499. // TODO: remove velocity derivative calculation
  500. // reset last velocity target to current target
  501. if (_flags.reset_rate_to_accel_z) {//改变高度时候复位
  502. _vel_last.z = _vel_target.z;
  503. }
  504. // feed forward desired acceleration calculation
  505. if (_dt > 0.0f) {
  506. if (!_flags.freeze_ff_z) {
  507. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  508. } else {
  509. // stop the feed forward being calculated during a known discontinuity
  510. _flags.freeze_ff_z = false;
  511. }
  512. } else {
  513. _accel_desired.z = 0.0f;
  514. }
  515. // store this iteration's velocities for the next iteration
  516. _vel_last.z = _vel_target.z;
  517. // reset velocity error and filter if this controller has just been engaged
  518. if (_flags.reset_rate_to_accel_z) {
  519. // Reset Filter
  520. _vel_error.z = 0;
  521. _vel_error_filter.reset(0);
  522. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;//02.28
  523. _flags.reset_rate_to_accel_z = false;
  524. } else {
  525. // calculate rate error and filter with cut off frequency of 2 Hz
  526. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  527. _accel_target.z = _p_vel_z.get_p(_vel_error.z);//02.28
  528. }
  529. _accel_target.z += _accel_desired.z;
  530. // the following section calculates a desired throttle needed to achieve the acceleration target
  531. float z_accel_meas; // actual acceleration
  532. // Calculate Earth Frame Z acceleration
  533. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  534. // ensure imax is always large enough to overpower hover throttle
  535. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  536. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  537. }
  538. // 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();
  539. float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f +0.5;
  540. // send throttle to attitude controller with angle boost
  541. _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  542. static uint8_t cnt = 0;
  543. cnt++;
  544. if (cnt>250)
  545. {
  546. cnt = 0;
  547. //gcs().send_text(MAV_SEVERITY_INFO, " ff %d %d %f\n",(int)_flags.use_desvel_ff_z,(int)_flags.freeze_ff_z,_motors.get_throttle_hover());
  548. //gcs().send_text(MAV_SEVERITY_INFO, " pos %f %f %f %f\n",_pos_error.z,_vel_target.z,curr_vel.z,_accel_desired.z);
  549. gcs().send_text(MAV_SEVERITY_INFO, " pid %f %f %f %f\n",_accel_target.z,z_accel_meas,_accel_desired.z,thr_out);
  550. }
  551. }
  552. float AC_PosControl::run_z_controller_wangdan(float _vel)
  553. {
  554. //超时复位
  555. const uint64_t now_us = AP_HAL::micros64();
  556. if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
  557. _flags.reset_rate_to_accel_z = true;
  558. _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
  559. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  560. _pid_accel_z.reset_filter();
  561. }
  562. _last_update_z_us = now_us;
  563. //速度环
  564. _vel_target.z = _vel;
  565. // add feed forward component
  566. if (_flags.use_desvel_ff_z) {
  567. _vel_target.z += _vel_desired.z;
  568. }
  569. // the following section calculates acceleration required to achieve the velocity target
  570. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  571. Vector3f curr_vel;//12.19
  572. curr_vel.z=alt_rate.get();
  573. // TODO: remove velocity derivative calculation
  574. // reset last velocity target to current target
  575. if (_flags.reset_rate_to_accel_z) {//改变高度时候复位
  576. _vel_last.z = _vel_target.z;
  577. }
  578. // feed forward desired acceleration calculation
  579. if (_dt > 0.0f) {
  580. if (!_flags.freeze_ff_z) {
  581. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  582. } else {
  583. // stop the feed forward being calculated during a known discontinuity
  584. _flags.freeze_ff_z = false;
  585. }
  586. } else {
  587. _accel_desired.z = 0.0f;
  588. }
  589. // store this iteration's velocities for the next iteration
  590. _vel_last.z = _vel_target.z;
  591. // reset velocity error and filter if this controller has just been engaged
  592. if (_flags.reset_rate_to_accel_z) {
  593. // Reset Filter
  594. _vel_error.z = 0;
  595. _vel_error_filter.reset(0);
  596. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;//02.28
  597. _flags.reset_rate_to_accel_z = false;
  598. } else {
  599. // calculate rate error and filter with cut off frequency of 2 Hz
  600. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  601. _accel_target.z = _p_vel_z.get_p(_vel_error.z);//02.28
  602. }
  603. _accel_target.z += _accel_desired.z;
  604. // the following section calculates a desired throttle needed to achieve the acceleration target
  605. float z_accel_meas; // actual acceleration
  606. // Calculate Earth Frame Z acceleration
  607. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  608. // ensure imax is always large enough to overpower hover throttle
  609. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  610. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  611. }
  612. // 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();
  613. float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f;
  614. // send throttle to attitude controller with angle boost
  615. //_attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  616. static uint8_t cnt = 0;
  617. cnt++;
  618. if (cnt>250)
  619. {
  620. cnt = 0;
  621. //gcs().send_text(MAV_SEVERITY_INFO, " ff %d %d %f\n",(int)_flags.use_desvel_ff_z,(int)_flags.freeze_ff_z,_motors.get_throttle_hover());
  622. //gcs().send_text(MAV_SEVERITY_INFO, " pos %f %f %f %f\n",_pos_error.z,_vel_target.z,curr_vel.z,_accel_desired.z);
  623. gcs().send_text(MAV_SEVERITY_INFO, " pid %f %f %f %f\n",_vel_target.z,curr_vel.z,_accel_target.z,thr_out);
  624. }
  625. return thr_out;
  626. }
  627. void AC_PosControl::calculate_rate(float dt){
  628. LowPassFilterFloat curr_alt(10.0);
  629. curr_alt.apply(sub.barometer.get_altitude()*100,dt);//_inav.get_altitude();//12.19
  630. alt_rate.apply((curr_alt.get()-last_alt)/dt,dt);//12.19 cm
  631. last_alt = curr_alt.get();//12.19
  632. }
  633. float AC_PosControl::run_z_controller_f()
  634. {
  635. //float curr_alt = _inav.get_altitude();//12.19
  636. float curr_alt = sub.barometer.get_altitude()*100;//_inav.get_altitude();//12.19
  637. // clear position limit flags
  638. _limit.pos_up = false;
  639. _limit.pos_down = false;
  640. // calculate altitude error
  641. _pos_error.z = _pos_target.z - curr_alt;
  642. // do not let target altitude get too far from current altitude
  643. if (_pos_error.z > _leash_up_z) {
  644. _pos_target.z = curr_alt + _leash_up_z;
  645. _pos_error.z = _leash_up_z;
  646. _limit.pos_up = true;
  647. }
  648. if (_pos_error.z < -_leash_down_z) {
  649. _pos_target.z = curr_alt - _leash_down_z;
  650. _pos_error.z = -_leash_down_z;
  651. _limit.pos_down = true;
  652. }
  653. // calculate _vel_target.z using from _pos_error.z using sqrt controller
  654. _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
  655. // check speed limits
  656. // To-Do: check these speed limits here or in the pos->rate controller
  657. _limit.vel_up = false;
  658. _limit.vel_down = false;
  659. if (_vel_target.z < _speed_down_cms) {
  660. _vel_target.z = _speed_down_cms;
  661. _limit.vel_down = true;
  662. }
  663. if (_vel_target.z > _speed_up_cms) {
  664. _vel_target.z = _speed_up_cms;
  665. _limit.vel_up = true;
  666. }
  667. // add feed forward component
  668. float ff =(float)SRV_Channels::srv_channel(15)->get_output_max()/10000;//test
  669. static float ff_ratio = ff;
  670. if (_flags.use_desvel_ff_z) {
  671. if (fabsf(_vel_desired.z)>0)
  672. {
  673. ff_ratio = constrain_float(ff_ratio*0.997,0.0,2.5);
  674. _vel_target.z += _vel_desired.z*(1+ff_ratio);//前馈加系数试试
  675. }else{
  676. //没有前馈控制
  677. ff_ratio = ff;
  678. }
  679. }else{
  680. ff_ratio = ff;
  681. }
  682. // the following section calculates acceleration required to achieve the velocity target
  683. //const Vector3f& curr_vel = _inav.get_velocity();//12.19
  684. Vector3f curr_vel;//12.19
  685. curr_vel.z=alt_rate.get();
  686. // TODO: remove velocity derivative calculation
  687. // reset last velocity target to current target
  688. if (_flags.reset_rate_to_accel_z) {//改变高度时候复位
  689. _vel_last.z = _vel_target.z;
  690. }
  691. // feed forward desired acceleration calculation
  692. if (_dt > 0.0f) {
  693. if (!_flags.freeze_ff_z) {
  694. _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
  695. } else {
  696. // stop the feed forward being calculated during a known discontinuity
  697. _flags.freeze_ff_z = false;
  698. }
  699. } else {
  700. _accel_desired.z = 0.0f;
  701. }
  702. // store this iteration's velocities for the next iteration
  703. _vel_last.z = _vel_target.z;
  704. // reset velocity error and filter if this controller has just been engaged
  705. if (_flags.reset_rate_to_accel_z) {
  706. // Reset Filter
  707. _vel_error.z = 0;
  708. _vel_error_filter.reset(0);
  709. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;//02.28
  710. _flags.reset_rate_to_accel_z = false;
  711. } else {
  712. // calculate rate error and filter with cut off frequency of 2 Hz
  713. _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
  714. _accel_target.z = _p_vel_z.get_p(_vel_error.z);//02.28
  715. }
  716. _accel_target.z += _accel_desired.z;
  717. // the following section calculates a desired throttle needed to achieve the acceleration target
  718. float z_accel_meas; // actual acceleration
  719. // Calculate Earth Frame Z acceleration
  720. z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  721. // ensure imax is always large enough to overpower hover throttle
  722. if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
  723. _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
  724. }
  725. // 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();
  726. float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f;
  727. //如果加一个当前速度前馈的话最多可以用0.002
  728. // send throttle to attitude controller with angle boost
  729. // _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
  730. static uint16_t count = 0;
  731. count++;
  732. if (count>200)
  733. {
  734. count = 0;
  735. gcs().send_text(MAV_SEVERITY_INFO, "ff %f %f %f \n",_vel_target.z,_accel_target.z,z_accel_meas);
  736. }
  737. return thr_out;
  738. }
  739. ///
  740. /// lateral position controller
  741. ///
  742. /// set_max_accel_xy - set the maximum horizontal acceleration in cm/s/s
  743. void AC_PosControl::set_max_accel_xy(float accel_cmss)
  744. {
  745. if (fabsf(_accel_cms - accel_cmss) > 1.0f) {
  746. _accel_cms = accel_cmss;
  747. _flags.recalc_leash_xy = true;
  748. calc_leash_length_xy();
  749. }
  750. }
  751. /// set_max_speed_xy - set the maximum horizontal speed maximum in cm/s
  752. void AC_PosControl::set_max_speed_xy(float speed_cms)
  753. {
  754. if (fabsf(_speed_cms - speed_cms) > 1.0f) {
  755. _speed_cms = speed_cms;
  756. _flags.recalc_leash_xy = true;
  757. calc_leash_length_xy();
  758. }
  759. }
  760. /// set_pos_target in cm from home
  761. void AC_PosControl::set_pos_target(const Vector3f& position)
  762. {
  763. _pos_target = position;
  764. _flags.use_desvel_ff_z = false;
  765. _vel_desired.z = 0.0f;
  766. // 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
  767. // 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
  768. //_roll_target = constrain_int32(_ahrs.roll_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  769. //_pitch_target = constrain_int32(_ahrs.pitch_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
  770. }
  771. /// set_xy_target in cm from home
  772. void AC_PosControl::set_xy_target(float x, float y)
  773. {
  774. _pos_target.x = x;
  775. _pos_target.y = y;
  776. }
  777. /// shift position target target in x, y axis
  778. void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
  779. {
  780. // move pos controller target
  781. _pos_target.x += x_cm;
  782. _pos_target.y += y_cm;
  783. }
  784. /// set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from home
  785. void AC_PosControl::set_target_to_stopping_point_xy()
  786. {
  787. // check if xy leash needs to be recalculated
  788. calc_leash_length_xy();
  789. get_stopping_point_xy(_pos_target);
  790. }
  791. /// get_stopping_point_xy - calculates stopping point based on current position, velocity, vehicle acceleration
  792. /// distance_max allows limiting distance to stopping point
  793. /// results placed in stopping_position vector
  794. /// set_max_accel_xy() should be called before this method to set vehicle acceleration
  795. /// set_leash_length() should have been called before this method
  796. void AC_PosControl::get_stopping_point_xy(Vector3f &stopping_point) const
  797. {
  798. const Vector3f curr_pos = _inav.get_position();
  799. Vector3f curr_vel = _inav.get_velocity();
  800. float linear_distance; // the distance at which we swap from a linear to sqrt response
  801. float linear_velocity; // the velocity above which we swap from a linear to sqrt response
  802. float stopping_dist; // the distance within the vehicle can stop
  803. float kP = _p_pos_xy.kP();
  804. // add velocity error to current velocity
  805. if (is_active_xy()) {
  806. curr_vel.x += _vel_error.x;
  807. curr_vel.y += _vel_error.y;
  808. }
  809. // calculate current velocity
  810. float vel_total = norm(curr_vel.x, curr_vel.y);
  811. // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
  812. if (kP <= 0.0f || _accel_cms <= 0.0f || is_zero(vel_total)) {
  813. stopping_point.x = curr_pos.x;
  814. stopping_point.y = curr_pos.y;
  815. return;
  816. }
  817. // calculate point at which velocity switches from linear to sqrt
  818. linear_velocity = _accel_cms / kP;
  819. // calculate distance within which we can stop
  820. if (vel_total < linear_velocity) {
  821. stopping_dist = vel_total / kP;
  822. } else {
  823. linear_distance = _accel_cms / (2.0f * kP * kP);
  824. stopping_dist = linear_distance + (vel_total * vel_total) / (2.0f * _accel_cms);
  825. }
  826. // constrain stopping distance
  827. stopping_dist = constrain_float(stopping_dist, 0, _leash);
  828. // convert the stopping distance into a stopping point using velocity vector
  829. stopping_point.x = curr_pos.x + (stopping_dist * curr_vel.x / vel_total);
  830. stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
  831. }
  832. /// get_distance_to_target - get horizontal distance to target position in cm
  833. float AC_PosControl::get_distance_to_target() const
  834. {
  835. return norm(_pos_error.x, _pos_error.y);
  836. }
  837. /// get_bearing_to_target - get bearing to target position in centi-degrees
  838. int32_t AC_PosControl::get_bearing_to_target() const
  839. {
  840. return get_bearing_cd(_inav.get_position(), _pos_target);
  841. }
  842. // is_active_xy - returns true if the xy position controller has been run very recently
  843. bool AC_PosControl::is_active_xy() const
  844. {
  845. return ((AP_HAL::micros64() - _last_update_xy_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
  846. }
  847. /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
  848. float AC_PosControl::get_lean_angle_max_cd() const
  849. {
  850. if (is_zero(_lean_angle_max)) {
  851. return _attitude_control.lean_angle_max();
  852. }
  853. return _lean_angle_max * 100.0f;
  854. }
  855. /// init_xy_controller - initialise the xy controller
  856. /// this should be called after setting the position target and the desired velocity and acceleration
  857. /// sets target roll angle, pitch angle and I terms based on vehicle current lean angles
  858. /// should be called once whenever significant changes to the position target are made
  859. /// this does not update the xy target
  860. void AC_PosControl::init_xy_controller()
  861. {
  862. // set roll, pitch lean angle targets to current attitude
  863. // todo: this should probably be based on the desired attitude not the current attitude
  864. _roll_target = _ahrs.roll_sensor;
  865. _pitch_target = _ahrs.pitch_sensor;
  866. // initialise I terms from lean angles
  867. _pid_vel_xy.reset_filter();
  868. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  869. _pid_vel_xy.set_integrator(_accel_target - _accel_desired);
  870. // flag reset required in rate to accel step
  871. _flags.reset_desired_vel_to_pos = true;
  872. _flags.reset_accel_to_lean_xy = true;
  873. // initialise ekf xy reset handler
  874. init_ekf_xy_reset();
  875. }
  876. /// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
  877. void AC_PosControl::update_xy_controller()
  878. {
  879. // compute dt
  880. const uint64_t now_us = AP_HAL::micros64();
  881. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  882. // sanity check dt
  883. if (dt >= POSCONTROL_ACTIVE_TIMEOUT_US * 1.0e-6f) {
  884. dt = 0.0f;
  885. }
  886. // check for ekf xy position reset
  887. check_for_ekf_xy_reset();
  888. // check if xy leash needs to be recalculated
  889. calc_leash_length_xy();
  890. // translate any adjustments from pilot to loiter target
  891. desired_vel_to_pos(dt);
  892. // run horizontal position controller
  893. run_xy_controller(dt);
  894. // update xy update time
  895. _last_update_xy_us = now_us;
  896. }
  897. float AC_PosControl::time_since_last_xy_update() const
  898. {
  899. const uint64_t now_us = AP_HAL::micros64();
  900. return (now_us - _last_update_xy_us) * 1.0e-6f;
  901. }
  902. // write log to dataflash
  903. void AC_PosControl::write_log()
  904. {
  905. const Vector3f &pos_target = get_pos_target();
  906. const Vector3f &vel_target = get_vel_target();
  907. const Vector3f &accel_target = get_accel_target();
  908. const Vector3f &position = _inav.get_position();
  909. const Vector3f &velocity = _inav.get_velocity();
  910. float accel_x, accel_y;
  911. lean_angles_to_accel(accel_x, accel_y);
  912. AP::logger().Write("PSC",
  913. "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
  914. "smmmmnnnnoooo",
  915. "F000000000000",
  916. "Qffffffffffff",
  917. AP_HAL::micros64(),
  918. double(pos_target.x * 0.01f),
  919. double(pos_target.y * 0.01f),
  920. double(position.x * 0.01f),
  921. double(position.y * 0.01f),
  922. double(vel_target.x * 0.01f),
  923. double(vel_target.y * 0.01f),
  924. double(velocity.x * 0.01f),
  925. double(velocity.y * 0.01f),
  926. double(accel_target.x * 0.01f),
  927. double(accel_target.y * 0.01f),
  928. double(accel_x * 0.01f),
  929. double(accel_y * 0.01f));
  930. }
  931. /// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
  932. void AC_PosControl::init_vel_controller_xyz()
  933. {
  934. // set roll, pitch lean angle targets to current attitude
  935. _roll_target = _ahrs.roll_sensor;
  936. _pitch_target = _ahrs.pitch_sensor;
  937. _pid_vel_xy.reset_filter();
  938. lean_angles_to_accel(_accel_target.x, _accel_target.y);
  939. _pid_vel_xy.set_integrator(_accel_target);
  940. // flag reset required in rate to accel step
  941. _flags.reset_desired_vel_to_pos = true;
  942. _flags.reset_accel_to_lean_xy = true;
  943. // set target position
  944. const Vector3f& curr_pos = _inav.get_position();
  945. set_xy_target(curr_pos.x, curr_pos.y);
  946. set_alt_target(curr_pos.z);
  947. // move current vehicle velocity into feed forward velocity
  948. const Vector3f& curr_vel = _inav.get_velocity();
  949. set_desired_velocity(curr_vel);
  950. // set vehicle acceleration to zero
  951. set_desired_accel_xy(0.0f, 0.0f);
  952. // initialise ekf reset handlers
  953. init_ekf_xy_reset();
  954. init_ekf_z_reset();
  955. }
  956. /// update_velocity_controller_xy - run the velocity controller - should be called at 100hz or higher
  957. /// velocity targets should we set using set_desired_velocity_xy() method
  958. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  959. /// throttle targets will be sent directly to the motors
  960. void AC_PosControl::update_vel_controller_xy()
  961. {
  962. // capture time since last iteration
  963. const uint64_t now_us = AP_HAL::micros64();
  964. float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
  965. // sanity check dt
  966. if (dt >= 0.2f) {
  967. dt = 0.0f;
  968. }
  969. // check for ekf xy position reset
  970. check_for_ekf_xy_reset();
  971. // check if xy leash needs to be recalculated
  972. calc_leash_length_xy();
  973. // apply desired velocity request to position target
  974. // TODO: this will need to be removed and added to the calling function.
  975. desired_vel_to_pos(dt);
  976. // run position controller
  977. run_xy_controller(dt);
  978. // update xy update time
  979. _last_update_xy_us = now_us;
  980. }
  981. /// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
  982. /// velocity targets should we set using set_desired_velocity_xyz() method
  983. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  984. /// throttle targets will be sent directly to the motors
  985. void AC_PosControl::update_vel_controller_xyz()
  986. {
  987. update_vel_controller_xy();
  988. // update altitude target
  989. set_alt_target_from_climb_rate_ff(_vel_desired.z, _dt, false);
  990. // run z-axis position controller
  991. update_z_controller();
  992. }
  993. float AC_PosControl::get_horizontal_error() const
  994. {
  995. return norm(_pos_error.x, _pos_error.y);
  996. }
  997. ///
  998. /// private methods
  999. ///
  1000. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration
  1001. /// should be called whenever the speed, acceleration or position kP is modified
  1002. void AC_PosControl::calc_leash_length_xy()
  1003. {
  1004. // todo: remove _flags.recalc_leash_xy or don't call this function after each variable change.
  1005. if (_flags.recalc_leash_xy) {
  1006. _leash = calc_leash_length(_speed_cms, _accel_cms, _p_pos_xy.kP());
  1007. _flags.recalc_leash_xy = false;
  1008. }
  1009. }
  1010. /// move velocity target using desired acceleration
  1011. void AC_PosControl::desired_accel_to_vel(float nav_dt)
  1012. {
  1013. // range check nav_dt
  1014. if (nav_dt < 0) {
  1015. return;
  1016. }
  1017. // update target velocity
  1018. if (_flags.reset_desired_vel_to_pos) {
  1019. _flags.reset_desired_vel_to_pos = false;
  1020. } else {
  1021. _vel_desired.x += _accel_desired.x * nav_dt;
  1022. _vel_desired.y += _accel_desired.y * nav_dt;
  1023. }
  1024. }
  1025. /// desired_vel_to_pos - move position target using desired velocities
  1026. void AC_PosControl::desired_vel_to_pos(float nav_dt)
  1027. {
  1028. // range check nav_dt
  1029. if (nav_dt < 0) {
  1030. return;
  1031. }
  1032. // update target position
  1033. if (_flags.reset_desired_vel_to_pos) {
  1034. _flags.reset_desired_vel_to_pos = false;
  1035. } else {
  1036. _pos_target.x += _vel_desired.x * nav_dt;
  1037. _pos_target.y += _vel_desired.y * nav_dt;
  1038. }
  1039. }
  1040. /// run horizontal position controller correcting position and velocity
  1041. /// converts position (_pos_target) to target velocity (_vel_target)
  1042. /// desired velocity (_vel_desired) is combined into final target velocity
  1043. /// converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  1044. /// converts desired accelerations provided in lat/lon frame to roll/pitch angles
  1045. void AC_PosControl::run_xy_controller(float dt)
  1046. {
  1047. float ekfGndSpdLimit, ekfNavVelGainScaler;
  1048. AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
  1049. Vector3f curr_pos = _inav.get_position();
  1050. float kP = ekfNavVelGainScaler * _p_pos_xy.kP(); // scale gains to compensate for noisy optical flow measurement in the EKF
  1051. // avoid divide by zero
  1052. if (kP <= 0.0f) {
  1053. _vel_target.x = 0.0f;
  1054. _vel_target.y = 0.0f;
  1055. } else {
  1056. // calculate distance error
  1057. _pos_error.x = _pos_target.x - curr_pos.x;
  1058. _pos_error.y = _pos_target.y - curr_pos.y;
  1059. // Constrain _pos_error and target position
  1060. // Constrain the maximum length of _vel_target to the maximum position correction velocity
  1061. // TODO: replace the leash length with a user definable maximum position correction
  1062. if (limit_vector_length(_pos_error.x, _pos_error.y, _leash)) {
  1063. _pos_target.x = curr_pos.x + _pos_error.x;
  1064. _pos_target.y = curr_pos.y + _pos_error.y;
  1065. }
  1066. _vel_target = sqrt_controller(_pos_error, kP, _accel_cms);
  1067. }
  1068. // add velocity feed-forward
  1069. _vel_target.x += _vel_desired.x;
  1070. _vel_target.y += _vel_desired.y;
  1071. // the following section converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  1072. Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
  1073. // check if vehicle velocity is being overridden
  1074. if (_flags.vehicle_horiz_vel_override) {
  1075. _flags.vehicle_horiz_vel_override = false;
  1076. } else {
  1077. _vehicle_horiz_vel.x = _inav.get_velocity().x;
  1078. _vehicle_horiz_vel.y = _inav.get_velocity().y;
  1079. }
  1080. // calculate velocity error
  1081. _vel_error.x = _vel_target.x - _vehicle_horiz_vel.x;
  1082. _vel_error.y = _vel_target.y - _vehicle_horiz_vel.y;
  1083. // TODO: constrain velocity error and velocity target
  1084. // call pi controller
  1085. _pid_vel_xy.set_input(_vel_error);
  1086. // get p
  1087. vel_xy_p = _pid_vel_xy.get_p();
  1088. // update i term if we have not hit the accel or throttle limits OR the i term will reduce
  1089. // TODO: move limit handling into the PI and PID controller
  1090. if (!_limit.accel_xy && !_motors.limit.throttle_upper) {
  1091. vel_xy_i = _pid_vel_xy.get_i();
  1092. } else {
  1093. vel_xy_i = _pid_vel_xy.get_i_shrink();
  1094. }
  1095. // get d
  1096. vel_xy_d = _pid_vel_xy.get_d();
  1097. // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise
  1098. accel_target.x = (vel_xy_p.x + vel_xy_i.x + vel_xy_d.x) * ekfNavVelGainScaler;
  1099. accel_target.y = (vel_xy_p.y + vel_xy_i.y + vel_xy_d.y) * ekfNavVelGainScaler;
  1100. // reset accel to current desired acceleration
  1101. if (_flags.reset_accel_to_lean_xy) {
  1102. _accel_target_filter.reset(Vector2f(accel_target.x, accel_target.y));
  1103. _flags.reset_accel_to_lean_xy = false;
  1104. }
  1105. // filter correction acceleration
  1106. _accel_target_filter.set_cutoff_frequency(MIN(_accel_xy_filt_hz, 5.0f * ekfNavVelGainScaler));
  1107. _accel_target_filter.apply(accel_target, dt);
  1108. // pass the correction acceleration to the target acceleration output
  1109. _accel_target.x = _accel_target_filter.get().x;
  1110. _accel_target.y = _accel_target_filter.get().y;
  1111. // Add feed forward into the target acceleration output
  1112. _accel_target.x += _accel_desired.x;
  1113. _accel_target.y += _accel_desired.y;
  1114. // the following section converts desired accelerations provided in lat/lon frame to roll/pitch angles
  1115. // limit acceleration using maximum lean angles
  1116. float angle_max = MIN(_attitude_control.get_althold_lean_angle_max(), get_lean_angle_max_cd());
  1117. float accel_max = MIN(GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)), POSCONTROL_ACCEL_XY_MAX);
  1118. _limit.accel_xy = limit_vector_length(_accel_target.x, _accel_target.y, accel_max);
  1119. // update angle targets that will be passed to stabilize controller
  1120. accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target);
  1121. }
  1122. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  1123. void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const
  1124. {
  1125. float accel_right, accel_forward;
  1126. // rotate accelerations into body forward-right frame
  1127. // todo: this should probably be based on the desired heading not the current heading
  1128. accel_forward = accel_x_cmss * _ahrs.cos_yaw() + accel_y_cmss * _ahrs.sin_yaw();
  1129. accel_right = -accel_x_cmss * _ahrs.sin_yaw() + accel_y_cmss * _ahrs.cos_yaw();
  1130. // update angle targets that will be passed to stabilize controller
  1131. pitch_target = atanf(-accel_forward / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  1132. float cos_pitch_target = cosf(pitch_target * M_PI / 18000.0f);
  1133. roll_target = atanf(accel_right * cos_pitch_target / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
  1134. }
  1135. // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  1136. void AC_PosControl::lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const
  1137. {
  1138. // rotate our roll, pitch angles into lat/lon frame
  1139. // todo: this should probably be based on the desired attitude not the current attitude
  1140. 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);
  1141. 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);
  1142. }
  1143. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and position kP gain
  1144. float AC_PosControl::calc_leash_length(float speed_cms, float accel_cms, float kP) const
  1145. {
  1146. float leash_length;
  1147. // sanity check acceleration and avoid divide by zero
  1148. if (accel_cms <= 0.0f) {
  1149. accel_cms = POSCONTROL_ACCELERATION_MIN;
  1150. }
  1151. // avoid divide by zero
  1152. if (kP <= 0.0f) {
  1153. return POSCONTROL_LEASH_LENGTH_MIN;
  1154. }
  1155. // calculate leash length 1/kP 为时间间隔dt
  1156. if (speed_cms <= accel_cms / kP) {
  1157. // linear leash length based on speed close in
  1158. leash_length = speed_cms / kP; //时间间隔很小的时候 V*dt
  1159. } else {
  1160. // leash length grows at sqrt of speed further out //时间间隔比较大的时候 1/2*a*dt^2+ v^2/2/a 这是根据开方器来的 看不懂
  1161. leash_length = (accel_cms / (2.0f * kP * kP)) + (speed_cms * speed_cms / (2.0f * accel_cms));
  1162. }
  1163. // ensure leash is at least 1m long
  1164. if (leash_length < POSCONTROL_LEASH_LENGTH_MIN) {
  1165. leash_length = POSCONTROL_LEASH_LENGTH_MIN;
  1166. }
  1167. return leash_length;
  1168. }
  1169. /// initialise ekf xy position reset check
  1170. void AC_PosControl::init_ekf_xy_reset()
  1171. {
  1172. Vector2f pos_shift;
  1173. _ekf_xy_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  1174. }
  1175. /// check for ekf position reset and adjust loiter or brake target position
  1176. void AC_PosControl::check_for_ekf_xy_reset()
  1177. {
  1178. // check for position shift
  1179. Vector2f pos_shift;
  1180. uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
  1181. if (reset_ms != _ekf_xy_reset_ms) {
  1182. shift_pos_xy_target(pos_shift.x * 100.0f, pos_shift.y * 100.0f);
  1183. _ekf_xy_reset_ms = reset_ms;
  1184. }
  1185. }
  1186. /// initialise ekf z axis reset check
  1187. void AC_PosControl::init_ekf_z_reset()
  1188. {
  1189. float alt_shift;
  1190. _ekf_z_reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  1191. }
  1192. /// check for ekf position reset and adjust loiter or brake target position
  1193. void AC_PosControl::check_for_ekf_z_reset()
  1194. {
  1195. // check for position shift
  1196. float alt_shift;
  1197. uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift);
  1198. if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) {
  1199. shift_alt_target(-alt_shift * 100.0f);
  1200. _ekf_z_reset_ms = reset_ms;
  1201. }
  1202. }
  1203. /// limit vector to a given length, returns true if vector was limited
  1204. bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
  1205. {
  1206. float vector_length = norm(vector_x, vector_y);
  1207. if ((vector_length > max_length) && is_positive(vector_length)) {
  1208. vector_x *= (max_length / vector_length);
  1209. vector_y *= (max_length / vector_length);
  1210. return true;
  1211. }
  1212. return false;
  1213. }
  1214. /// Proportional controller with piecewise sqrt sections to constrain second derivative
  1215. Vector3f AC_PosControl::sqrt_controller(const Vector3f& error, float p, float second_ord_lim)
  1216. {
  1217. if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {
  1218. return Vector3f(error.x * p, error.y * p, error.z);
  1219. }
  1220. float linear_dist = second_ord_lim / sq(p);
  1221. float error_length = norm(error.x, error.y);
  1222. if (error_length > linear_dist) {
  1223. float first_order_scale = safe_sqrt(2.0f * second_ord_lim * (error_length - (linear_dist * 0.5f))) / error_length;
  1224. return Vector3f(error.x * first_order_scale, error.y * first_order_scale, error.z);
  1225. } else {
  1226. return Vector3f(error.x * p, error.y * p, error.z);
  1227. }
  1228. }
  1229. bool AC_PosControl::pre_arm_checks(const char *param_prefix,
  1230. char *failure_msg,
  1231. const uint8_t failure_msg_len)
  1232. {
  1233. // validate AC_P members:
  1234. const struct {
  1235. const char *pid_name;
  1236. AC_P &p;
  1237. } ps[] = {
  1238. { "POSXY", get_pos_xy_p() },
  1239. { "POSZ", get_pos_z_p() },
  1240. { "VELZ", get_vel_z_p() },
  1241. };
  1242. for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
  1243. // all AC_P's must have a positive P value:
  1244. if (!is_positive(ps[i].p.kP())) {
  1245. hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
  1246. return false;
  1247. }
  1248. }
  1249. // z-axis acceleration control PID doesn't use FF, so P and I must be positive
  1250. if (!is_positive(get_accel_z_pid().kP())) {
  1251. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_P must be > 0", param_prefix);
  1252. return false;
  1253. }
  1254. if (!is_positive(get_accel_z_pid().kI())) {
  1255. hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_I must be > 0", param_prefix);
  1256. return false;
  1257. }
  1258. return true;
  1259. }