AR_AttitudeControl.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <AP_Math/AP_Math.h>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include "AR_AttitudeControl.h"
  16. #include <AP_GPS/AP_GPS.h>
  17. extern const AP_HAL::HAL& hal;
  18. const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
  19. // @Param: _STR_RAT_P
  20. // @DisplayName: Steering control rate P gain
  21. // @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
  22. // @Range: 0.000 2.000
  23. // @Increment: 0.01
  24. // @User: Standard
  25. // @Param: _STR_RAT_I
  26. // @DisplayName: Steering control I gain
  27. // @Description: Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
  28. // @Range: 0.000 2.000
  29. // @Increment: 0.01
  30. // @User: Standard
  31. // @Param: _STR_RAT_IMAX
  32. // @DisplayName: Steering control I gain maximum
  33. // @Description: Steering control I gain maximum. Constraings the steering output (range -1 to +1) that the I term will generate
  34. // @Range: 0.000 1.000
  35. // @Increment: 0.01
  36. // @User: Standard
  37. // @Param: _STR_RAT_D
  38. // @DisplayName: Steering control D gain
  39. // @Description: Steering control D gain. Compensates for short-term change in desired turn rate vs actual
  40. // @Range: 0.000 0.400
  41. // @Increment: 0.001
  42. // @User: Standard
  43. // @Param: _STR_RAT_FF
  44. // @DisplayName: Steering control feed forward
  45. // @Description: Steering control feed forward
  46. // @Range: 0.000 3.000
  47. // @Increment: 0.001
  48. // @User: Standard
  49. // @Param: _STR_RAT_FILT
  50. // @DisplayName: Steering control filter frequency
  51. // @Description: Steering control input filter. Lower values reduce noise but add delay.
  52. // @Range: 0.000 100.000
  53. // @Increment: 0.1
  54. // @Units: Hz
  55. // @User: Standard
  56. AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
  57. // @Param: _SPEED_P
  58. // @DisplayName: Speed control P gain
  59. // @Description: Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
  60. // @Range: 0.010 2.000
  61. // @Increment: 0.01
  62. // @User: Standard
  63. // @Param: _SPEED_I
  64. // @DisplayName: Speed control I gain
  65. // @Description: Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
  66. // @Range: 0.000 2.000
  67. // @User: Standard
  68. // @Param: _SPEED_IMAX
  69. // @DisplayName: Speed control I gain maximum
  70. // @Description: Speed control I gain maximum. Constraings the maximum motor output (range -1 to +1) that the I term will generate
  71. // @Range: 0.000 1.000
  72. // @Increment: 0.01
  73. // @User: Standard
  74. // @Param: _SPEED_D
  75. // @DisplayName: Speed control D gain
  76. // @Description: Speed control D gain. Compensates for short-term change in desired speed vs actual
  77. // @Range: 0.000 0.400
  78. // @Increment: 0.001
  79. // @User: Standard
  80. // @Param: _SPEED_FF
  81. // @DisplayName: Speed control feed forward
  82. // @Description: Speed control feed forward
  83. // @Range: 0.000 0.500
  84. // @Increment: 0.001
  85. // @User: Standard
  86. // @Param: _SPEED_FILT
  87. // @DisplayName: Speed control filter frequency
  88. // @Description: Speed control input filter. Lower values reduce noise but add delay.
  89. // @Range: 0.000 100.000
  90. // @Increment: 0.1
  91. // @Units: Hz
  92. // @User: Standard
  93. AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
  94. // @Param: _ACCEL_MAX
  95. // @DisplayName: Speed control acceleration (and deceleration) maximum in m/s/s
  96. // @Description: Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
  97. // @Range: 0.0 10.0
  98. // @Increment: 0.1
  99. // @Units: m/s/s
  100. // @User: Standard
  101. AP_GROUPINFO("_ACCEL_MAX", 3, AR_AttitudeControl, _throttle_accel_max, AR_ATTCONTROL_THR_ACCEL_MAX),
  102. // @Param: _BRAKE
  103. // @DisplayName: Speed control brake enable/disable
  104. // @Description: Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
  105. // @Values: 0:Disable,1:Enable
  106. // @User: Standard
  107. AP_GROUPINFO("_BRAKE", 4, AR_AttitudeControl, _brake_enable, 1),
  108. // @Param: _STOP_SPEED
  109. // @DisplayName: Speed control stop speed
  110. // @Description: Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
  111. // @Range: 0.00 0.50
  112. // @Increment: 0.01
  113. // @Units: m/s
  114. // @User: Standard
  115. AP_GROUPINFO("_STOP_SPEED", 5, AR_AttitudeControl, _stop_speed, AR_ATTCONTROL_STOP_SPEED_DEFAULT),
  116. // @Param: _STR_ANG_P
  117. // @DisplayName: Steering control angle P gain
  118. // @Description: Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
  119. // @Range: 1.000 10.000
  120. // @Increment: 0.1
  121. // @User: Standard
  122. AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 6, AR_AttitudeControl, AC_P),
  123. // @Param: _STR_ACC_MAX
  124. // @DisplayName: Steering control angular acceleration maximum
  125. // @Description: Steering control angular acceleration maximum (in deg/s/s). 0 to disable acceleration limiting
  126. // @Range: 0 1000
  127. // @Increment: 0.1
  128. // @Units: deg/s/s
  129. // @User: Standard
  130. AP_GROUPINFO("_STR_ACC_MAX", 7, AR_AttitudeControl, _steer_accel_max, AR_ATTCONTROL_STEER_ACCEL_MAX),
  131. // @Param: _STR_RAT_MAX
  132. // @DisplayName: Steering control rotation rate maximum
  133. // @Description: Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
  134. // @Range: 0 1000
  135. // @Increment: 0.1
  136. // @Units: deg/s
  137. // @User: Standard
  138. AP_GROUPINFO("_STR_RAT_MAX", 8, AR_AttitudeControl, _steer_rate_max, AR_ATTCONTROL_STEER_RATE_MAX),
  139. // @Param: _DECEL_MAX
  140. // @DisplayName: Speed control deceleration maximum in m/s/s
  141. // @Description: Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
  142. // @Range: 0.0 10.0
  143. // @Increment: 0.1
  144. // @Units: m/s/s
  145. // @User: Standard
  146. AP_GROUPINFO("_DECEL_MAX", 9, AR_AttitudeControl, _throttle_decel_max, 0.00f),
  147. // @Param: _BAL_P
  148. // @DisplayName: Pitch control P gain
  149. // @Description: Pitch control P gain for BalanceBots. Converts the error between the desired pitch (in radians) and actual pitch to a motor output (in the range -1 to +1)
  150. // @Range: 0.000 2.000
  151. // @Increment: 0.01
  152. // @User: Standard
  153. // @Param: _BAL_I
  154. // @DisplayName: Pitch control I gain
  155. // @Description: Pitch control I gain for BalanceBots. Corrects long term error between the desired pitch (in radians) and actual pitch
  156. // @Range: 0.000 2.000
  157. // @User: Standard
  158. // @Param: _BAL_IMAX
  159. // @DisplayName: Pitch control I gain maximum
  160. // @Description: Pitch control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
  161. // @Range: 0.000 1.000
  162. // @Increment: 0.01
  163. // @User: Standard
  164. // @Param: _BAL_D
  165. // @DisplayName: Pitch control D gain
  166. // @Description: Pitch control D gain. Compensates for short-term change in desired pitch vs actual
  167. // @Range: 0.000 0.100
  168. // @Increment: 0.001
  169. // @User: Standard
  170. // @Param: _BAL_FF
  171. // @DisplayName: Pitch control feed forward
  172. // @Description: Pitch control feed forward
  173. // @Range: 0.000 0.500
  174. // @Increment: 0.001
  175. // @User: Standard
  176. // @Param: _BAL_FILT
  177. // @DisplayName: Pitch control filter frequency
  178. // @Description: Pitch control input filter. Lower values reduce noise but add delay.
  179. // @Range: 0.000 100.000
  180. // @Increment: 0.1
  181. // @Units: Hz
  182. // @User: Standard
  183. AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),
  184. // @Param: _BAL_SPD_FF
  185. // @DisplayName: Pitch control feed forward from speed
  186. // @Description: Pitch control feed forward from speed
  187. // @Range: 0.0 10.0
  188. // @Increment: 0.01
  189. // @User: Standard
  190. AP_GROUPINFO("_BAL_SPD_FF", 11, AR_AttitudeControl, _pitch_to_throttle_speed_ff, AR_ATTCONTROL_BAL_SPEED_FF),
  191. // @Param: _SAIL_P
  192. // @DisplayName: Sail Heel control P gain
  193. // @Description: Sail Heel control P gain for sailboats. Converts the error between the desired heel angle (in radians) and actual heel to a main sail output (in the range -1 to +1)
  194. // @Range: 0.000 2.000
  195. // @Increment: 0.01
  196. // @User: Standard
  197. // @Param: _SAIL_I
  198. // @DisplayName: Sail Heel control I gain
  199. // @Description: Sail Heel control I gain for sailboats. Corrects long term error between the desired heel angle (in radians) and actual
  200. // @Range: 0.000 2.000
  201. // @User: Standard
  202. // @Param: _SAIL_IMAX
  203. // @DisplayName: Sail Heel control I gain maximum
  204. // @Description: Sail Heel control I gain maximum. Constrains the maximum I term contribution to the main sail output (range -1 to +1)
  205. // @Range: 0.000 1.000
  206. // @Increment: 0.01
  207. // @User: Standard
  208. // @Param: _SAIL_D
  209. // @DisplayName: Sail Heel control D gain
  210. // @Description: Sail Heel control D gain. Compensates for short-term change in desired heel angle vs actual
  211. // @Range: 0.000 0.100
  212. // @Increment: 0.001
  213. // @User: Standard
  214. // @Param: _SAIL_FF
  215. // @DisplayName: Sail Heel control feed forward
  216. // @Description: Sail Heel control feed forward
  217. // @Range: 0.000 0.500
  218. // @Increment: 0.001
  219. // @User: Standard
  220. // @Param: _SAIL_FILT
  221. // @DisplayName: Sail Heel control filter frequency
  222. // @Description: Sail Heel control input filter. Lower values reduce noise but add delay.
  223. // @Range: 0.000 100.000
  224. // @Increment: 0.1
  225. // @Units: Hz
  226. // @User: Standard
  227. AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),
  228. AP_GROUPEND
  229. };
  230. AR_AttitudeControl::AR_AttitudeControl(AP_AHRS &ahrs) :
  231. _ahrs(ahrs),
  232. _steer_angle_p(AR_ATTCONTROL_STEER_ANG_P),
  233. _steer_rate_pid(AR_ATTCONTROL_STEER_RATE_P, AR_ATTCONTROL_STEER_RATE_I, AR_ATTCONTROL_STEER_RATE_D, AR_ATTCONTROL_STEER_RATE_FF, AR_ATTCONTROL_STEER_RATE_IMAX, 0.0f, AR_ATTCONTROL_STEER_RATE_FILT, 0.0f, AR_ATTCONTROL_DT),
  234. _throttle_speed_pid(AR_ATTCONTROL_THR_SPEED_P, AR_ATTCONTROL_THR_SPEED_I, AR_ATTCONTROL_THR_SPEED_D, 0.0f, AR_ATTCONTROL_THR_SPEED_IMAX, 0.0f, AR_ATTCONTROL_THR_SPEED_FILT, 0.0f, AR_ATTCONTROL_DT),
  235. _pitch_to_throttle_pid(AR_ATTCONTROL_PITCH_THR_P, AR_ATTCONTROL_PITCH_THR_I, AR_ATTCONTROL_PITCH_THR_D, 0.0f, AR_ATTCONTROL_PITCH_THR_IMAX, 0.0f, AR_ATTCONTROL_PITCH_THR_FILT, 0.0f, AR_ATTCONTROL_DT),
  236. _sailboat_heel_pid(AR_ATTCONTROL_HEEL_SAIL_P, AR_ATTCONTROL_HEEL_SAIL_I, AR_ATTCONTROL_HEEL_SAIL_D, 0.0f, AR_ATTCONTROL_HEEL_SAIL_IMAX, 0.0f, AR_ATTCONTROL_HEEL_SAIL_FILT, 0.0f, AR_ATTCONTROL_DT)
  237. {
  238. AP_Param::setup_object_defaults(this, var_info);
  239. }
  240. // return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
  241. // positive lateral acceleration is to the right.
  242. float AR_AttitudeControl::get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
  243. {
  244. // record desired accel for reporting purposes
  245. _steer_lat_accel_last_ms = AP_HAL::millis();
  246. _desired_lat_accel = desired_accel;
  247. // get speed forward
  248. float speed;
  249. if (!get_forward_speed(speed)) {
  250. // we expect caller will not try to control heading using rate control without a valid speed estimate
  251. // on failure to get speed we do not attempt to steer
  252. return 0.0f;
  253. }
  254. const float desired_rate = get_turn_rate_from_lat_accel(desired_accel, speed);
  255. return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
  256. }
  257. // return a steering servo output from -1 to +1 given a heading in radians
  258. // set rate_max_rads to a non-zero number to apply a limit on the desired turn rate
  259. // return value is normally in range -1.0 to +1.0 but can be higher or lower
  260. float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate_max_rads, bool motor_limit_left, bool motor_limit_right, float dt)
  261. {
  262. // calculate the desired turn rate (in radians) from the angle error (also in radians)
  263. float desired_rate = get_turn_rate_from_heading(heading_rad, rate_max_rads);
  264. return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
  265. }
  266. // return a desired turn-rate given a desired heading in radians
  267. float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const
  268. {
  269. const float yaw_error = wrap_PI(heading_rad - _ahrs.yaw);
  270. // Calculate the desired turn rate (in radians) from the angle error (also in radians)
  271. float desired_rate = _steer_angle_p.get_p(yaw_error);
  272. // limit desired_rate if a custom pivot turn rate is selected, otherwise use ATC_STR_RAT_MAX
  273. if (is_positive(rate_max_rads)) {
  274. desired_rate = constrain_float(desired_rate, -rate_max_rads, rate_max_rads);
  275. }
  276. return desired_rate;
  277. }
  278. // return a steering servo output from -1 to +1 given a
  279. // desired yaw rate in radians/sec. Positive yaw is to the right.
  280. float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
  281. {
  282. // sanity check dt
  283. dt = constrain_float(dt, 0.0f, 1.0f);
  284. // if not called recently, reset input filter and desired turn rate to actual turn rate (used for accel limiting)
  285. const uint32_t now = AP_HAL::millis();
  286. if ((_steer_turn_last_ms == 0) || ((now - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  287. _steer_rate_pid.reset_filter();
  288. _steer_rate_pid.reset_I();
  289. _desired_turn_rate = _ahrs.get_yaw_rate_earth();
  290. }
  291. _steer_turn_last_ms = now;
  292. // acceleration limit desired turn rate
  293. if (is_positive(_steer_accel_max)) {
  294. const float change_max = radians(_steer_accel_max) * dt;
  295. desired_rate = constrain_float(desired_rate, _desired_turn_rate - change_max, _desired_turn_rate + change_max);
  296. }
  297. _desired_turn_rate = desired_rate;
  298. // rate limit desired turn rate
  299. if (is_positive(_steer_rate_max)) {
  300. const float steer_rate_max_rad = radians(_steer_rate_max);
  301. _desired_turn_rate = constrain_float(_desired_turn_rate, -steer_rate_max_rad, steer_rate_max_rad);
  302. }
  303. // set PID's dt
  304. _steer_rate_pid.set_dt(dt);
  305. float output = _steer_rate_pid.update_all(_desired_turn_rate, _ahrs.get_yaw_rate_earth(), (motor_limit_left || motor_limit_right));
  306. output += _steer_rate_pid.get_ff();
  307. // constrain and return final output
  308. return output;
  309. }
  310. // get latest desired turn rate in rad/sec (recorded during calls to get_steering_out_rate)
  311. float AR_AttitudeControl::get_desired_turn_rate() const
  312. {
  313. // return zero if no recent calls to turn rate controller
  314. if ((_steer_turn_last_ms == 0) || ((AP_HAL::millis() - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  315. return 0.0f;
  316. }
  317. return _desired_turn_rate;
  318. }
  319. // get latest desired lateral acceleration in m/s/s (recorded during calls to get_steering_out_lat_accel)
  320. float AR_AttitudeControl::get_desired_lat_accel() const
  321. {
  322. // return zero if no recent calls to lateral acceleration controller
  323. if ((_steer_lat_accel_last_ms == 0) || ((AP_HAL::millis() - _steer_lat_accel_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  324. return 0.0f;
  325. }
  326. return _desired_lat_accel;
  327. }
  328. // get actual lateral acceleration in m/s/s. returns true on success
  329. bool AR_AttitudeControl::get_lat_accel(float &lat_accel) const
  330. {
  331. float speed;
  332. if (!get_forward_speed(speed)) {
  333. return false;
  334. }
  335. lat_accel = speed * _ahrs.get_yaw_rate_earth();
  336. return true;
  337. }
  338. // calculate the turn rate in rad/sec given a lateral acceleration (in m/s/s) and speed (in m/s)
  339. float AR_AttitudeControl::get_turn_rate_from_lat_accel(float lat_accel, float speed) const
  340. {
  341. // enforce minimum speed to stop oscillations when first starting to move
  342. if (fabsf(speed) < AR_ATTCONTROL_STEER_SPEED_MIN) {
  343. if (is_negative(speed)) {
  344. speed = -AR_ATTCONTROL_STEER_SPEED_MIN;
  345. } else {
  346. speed = AR_ATTCONTROL_STEER_SPEED_MIN;
  347. }
  348. }
  349. return lat_accel / speed;
  350. }
  351. // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
  352. // motor_limit should be true if motors have hit their upper or lower limits
  353. // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
  354. float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
  355. {
  356. // sanity check dt
  357. dt = constrain_float(dt, 0.0f, 1.0f);
  358. // get speed forward
  359. float speed;
  360. if (!get_forward_speed(speed)) {
  361. // we expect caller will not try to control heading using rate control without a valid speed estimate
  362. // on failure to get speed we do not attempt to steer
  363. return 0.0f;
  364. }
  365. // if not called recently, reset input filter and desired speed to actual speed (used for accel limiting)
  366. if (!speed_control_active()) {
  367. _throttle_speed_pid.reset_filter();
  368. _throttle_speed_pid.reset_I();
  369. _desired_speed = speed;
  370. }
  371. _speed_last_ms = AP_HAL::millis();
  372. // acceleration limit desired speed
  373. _desired_speed = get_desired_speed_accel_limited(desired_speed, dt);
  374. // set PID's dt
  375. _throttle_speed_pid.set_dt(dt);
  376. // calculate base throttle (protect against divide by zero)
  377. float throttle_base = 0.0f;
  378. if (is_positive(cruise_speed) && is_positive(cruise_throttle)) {
  379. throttle_base = desired_speed * (cruise_throttle / cruise_speed);
  380. }
  381. // calculate final output
  382. float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (_throttle_limit_low || _throttle_limit_high));
  383. throttle_out += _throttle_speed_pid.get_ff();
  384. throttle_out += throttle_base;
  385. // clear local limit flags used to stop i-term build-up as we stop reversed outputs going to motors
  386. _throttle_limit_low = false;
  387. _throttle_limit_high = false;
  388. // protect against reverse output being sent to the motors unless braking has been enabled
  389. if (!_brake_enable) {
  390. // if both desired speed and actual speed are positive, do not allow negative values
  391. if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
  392. throttle_out = 0.0f;
  393. _throttle_limit_low = true;
  394. } else if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
  395. throttle_out = 0.0f;
  396. _throttle_limit_high = true;
  397. }
  398. }
  399. // final output throttle in range -1 to 1
  400. return throttle_out;
  401. }
  402. // return a throttle output from -1 to +1 to perform a controlled stop. returns true once the vehicle has stopped
  403. float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
  404. {
  405. // get current system time
  406. const uint32_t now = AP_HAL::millis();
  407. // if we were stopped in the last 300ms, assume we are still stopped
  408. bool _stopped = (_stop_last_ms != 0) && (now - _stop_last_ms) < 300;
  409. // get deceleration limited speed
  410. float desired_speed_limited = get_desired_speed_accel_limited(0.0f, dt);
  411. // get speed forward
  412. float speed;
  413. if (!get_forward_speed(speed)) {
  414. // could not get speed so assume stopped
  415. _stopped = true;
  416. } else {
  417. // if desired speed is zero and vehicle drops below _stop_speed consider it stopped
  418. if (is_zero(desired_speed_limited) && fabsf(speed) <= fabsf(_stop_speed)) {
  419. _stopped = true;
  420. }
  421. }
  422. // set stopped status for caller
  423. stopped = _stopped;
  424. // if stopped return zero
  425. if (stopped) {
  426. // update last time we thought we were stopped
  427. _stop_last_ms = now;
  428. // set last time speed controller was run so accelerations are limited
  429. _speed_last_ms = now;
  430. return 0.0f;
  431. }
  432. // clear stopped system time
  433. _stop_last_ms = 0;
  434. // run speed controller to bring vehicle to stop
  435. return get_throttle_out_speed(desired_speed_limited, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle, dt);
  436. }
  437. // balancebot pitch to throttle controller
  438. // returns a throttle output from -100 to +100 given a desired pitch angle and vehicle's current speed (from wheel encoders)
  439. // desired_pitch is in radians, veh_speed_pct is supplied as a percentage (-100 to +100) of vehicle's top speed
  440. float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float vehicle_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt)
  441. {
  442. // sanity check dt
  443. dt = constrain_float(dt, 0.0f, 1.0f);
  444. // if not called recently, reset input filter
  445. const uint32_t now = AP_HAL::millis();
  446. if ((_balance_last_ms == 0) || ((now - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  447. _pitch_to_throttle_pid.reset_filter();
  448. _pitch_to_throttle_pid.reset_I();
  449. }
  450. _balance_last_ms = now;
  451. // set PID's dt
  452. _pitch_to_throttle_pid.set_dt(dt);
  453. // add feed forward from speed
  454. float output = vehicle_speed_pct * 0.01f * _pitch_to_throttle_speed_ff;
  455. output += _pitch_to_throttle_pid.update_all(desired_pitch, _ahrs.pitch, (motor_limit_low || motor_limit_high));
  456. output += _pitch_to_throttle_pid.get_ff();
  457. // constrain and return final output
  458. return output;
  459. }
  460. // get latest desired pitch in radians for reporting purposes
  461. float AR_AttitudeControl::get_desired_pitch() const
  462. {
  463. // if not called recently, return 0
  464. if ((_balance_last_ms == 0) || ((AP_HAL::millis() - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  465. return 0.0f;
  466. }
  467. return _pitch_to_throttle_pid.get_pid_info().target;
  468. }
  469. // Sailboat heel(roll) angle controller releases sail to keep at maximum heel angle
  470. // but does not attempt to reach maximum heel angle, ie only lets sails out, does not pull them in
  471. float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt)
  472. {
  473. // sanity check dt
  474. dt = constrain_float(dt, 0.0f, 1.0f);
  475. // if not called recently, reset input filter
  476. const uint32_t now = AP_HAL::millis();
  477. if ((_heel_controller_last_ms == 0) || ((now - _heel_controller_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  478. _sailboat_heel_pid.reset_filter();
  479. _sailboat_heel_pid.reset_I();
  480. }
  481. _heel_controller_last_ms = now;
  482. // set PID's dt
  483. _sailboat_heel_pid.set_dt(dt);
  484. _sailboat_heel_pid.update_all(desired_heel, fabsf(_ahrs.roll));
  485. // get feed-forward
  486. const float ff = _sailboat_heel_pid.get_ff();
  487. // get p, constrain to be zero or negative
  488. float p = _sailboat_heel_pid.get_p();
  489. if (is_positive(p)) {
  490. p = 0.0f;
  491. }
  492. // get i, constrain to be zero or negative
  493. float i = _sailboat_heel_pid.get_i();
  494. if (is_positive(i)) {
  495. i = 0.0f;
  496. _sailboat_heel_pid.reset_I();
  497. }
  498. // get d
  499. const float d = _sailboat_heel_pid.get_d();
  500. // constrain and return final output
  501. return (ff + p + i + d) * -1.0f;
  502. }
  503. // get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
  504. bool AR_AttitudeControl::get_forward_speed(float &speed) const
  505. {
  506. Vector3f velocity;
  507. if (!_ahrs.get_velocity_NED(velocity)) {
  508. // use less accurate GPS, assuming entire length is along forward/back axis of vehicle
  509. if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
  510. if (fabsf(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) {
  511. speed = AP::gps().ground_speed();
  512. } else {
  513. speed = -AP::gps().ground_speed();
  514. }
  515. return true;
  516. } else {
  517. return false;
  518. }
  519. }
  520. // calculate forward speed velocity into body frame
  521. speed = velocity.x*_ahrs.cos_yaw() + velocity.y*_ahrs.sin_yaw();
  522. return true;
  523. }
  524. float AR_AttitudeControl::get_decel_max() const
  525. {
  526. if (is_positive(_throttle_decel_max)) {
  527. return _throttle_decel_max;
  528. } else {
  529. return _throttle_accel_max;
  530. }
  531. }
  532. // check if speed controller active
  533. bool AR_AttitudeControl::speed_control_active() const
  534. {
  535. // active if there have been recent calls to speed controller
  536. if ((_speed_last_ms == 0) || ((AP_HAL::millis() - _speed_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
  537. return false;
  538. }
  539. return true;
  540. }
  541. // get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
  542. float AR_AttitudeControl::get_desired_speed() const
  543. {
  544. // return zero if no recent calls to speed controller
  545. if (!speed_control_active()) {
  546. return 0.0f;
  547. }
  548. return _desired_speed;
  549. }
  550. // get acceleration limited desired speed
  551. float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, float dt) const
  552. {
  553. // return input value if no recent calls to speed controller
  554. // apply no limiting when ATC_ACCEL_MAX is set to zero
  555. if (!speed_control_active() || !is_positive(_throttle_accel_max)) {
  556. return desired_speed;
  557. }
  558. // sanity check dt
  559. dt = constrain_float(dt, 0.0f, 1.0f);
  560. // use previous desired speed as basis for accel limiting
  561. float speed_prev = _desired_speed;
  562. // if no recent calls to speed controller limit based on current speed
  563. if (!speed_control_active()) {
  564. get_forward_speed(speed_prev);
  565. }
  566. // acceleration limit desired speed
  567. float speed_change_max;
  568. if (fabsf(desired_speed) < fabsf(_desired_speed) && is_positive(_throttle_decel_max)) {
  569. speed_change_max = _throttle_decel_max * dt;
  570. } else {
  571. speed_change_max = _throttle_accel_max * dt;
  572. }
  573. return constrain_float(desired_speed, speed_prev - speed_change_max, speed_prev + speed_change_max);
  574. }
  575. // get minimum stopping distance (in meters) given a speed (in m/s)
  576. float AR_AttitudeControl::get_stopping_distance(float speed) const
  577. {
  578. // get maximum vehicle deceleration
  579. const float accel_max = get_accel_max();
  580. // avoid divide by zero
  581. if ((accel_max <= 0.0f) || is_zero(speed)) {
  582. return 0.0f;
  583. }
  584. // assume linear deceleration
  585. return 0.5f * sq(speed) / accel_max;
  586. }
  587. // relax I terms of throttle and steering controllers
  588. void AR_AttitudeControl::relax_I()
  589. {
  590. _steer_rate_pid.reset_I();
  591. _throttle_speed_pid.reset_I();
  592. _pitch_to_throttle_pid.reset_I();
  593. }