AC_PosControl.cpp 58 KB

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