AR_WPNav.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446
  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_WPNav.h"
  16. extern const AP_HAL::HAL& hal;
  17. #define AR_WPNAV_TIMEOUT_MS 100
  18. #define AR_WPNAV_SPEED_DEFAULT 2.0f
  19. #define AR_WPNAV_RADIUS_DEFAULT 2.0f
  20. #define AR_WPNAV_OVERSHOOT_DEFAULT 2.0f
  21. #define AR_WPNAV_PIVOT_ANGLE_DEFAULT 60
  22. #define AR_WPNAV_PIVOT_RATE_DEFAULT 90
  23. const AP_Param::GroupInfo AR_WPNav::var_info[] = {
  24. // @Param: SPEED
  25. // @DisplayName: Waypoint speed default
  26. // @Description: Waypoint speed default
  27. // @Units: m/s
  28. // @Range: 0 100
  29. // @Increment: 0.1
  30. // @User: Standard
  31. AP_GROUPINFO("SPEED", 1, AR_WPNav, _speed_max, AR_WPNAV_SPEED_DEFAULT),
  32. // @Param: RADIUS
  33. // @DisplayName: Waypoint radius
  34. // @Description: The distance in meters from a waypoint when we consider the waypoint has been reached. This determines when the vehicle will turn toward the next waypoint.
  35. // @Units: m
  36. // @Range: 0 100
  37. // @Increment: 0.1
  38. // @User: Standard
  39. AP_GROUPINFO("RADIUS", 2, AR_WPNav, _radius, AR_WPNAV_RADIUS_DEFAULT),
  40. // @Param: OVERSHOOT
  41. // @DisplayName: Waypoint overshoot maximum
  42. // @Description: Waypoint overshoot maximum in meters. The vehicle will attempt to stay within this many meters of the track as it completes one waypoint and moves to the next.
  43. // @Units: m
  44. // @Range: 0 10
  45. // @Increment: 0.1
  46. // @User: Standard
  47. AP_GROUPINFO("OVERSHOOT", 3, AR_WPNav, _overshoot, AR_WPNAV_OVERSHOOT_DEFAULT),
  48. // @Param: PIVOT_ANGLE
  49. // @DisplayName: Waypoint Pivot Angle
  50. // @Description: Pivot when the difference bewteen the vehicle's heading and it's target heading is more than this many degrees. Set to zero to disable pivot turns
  51. // @Units: deg
  52. // @Range: 0 360
  53. // @Increment: 1
  54. // @User: Standard
  55. AP_GROUPINFO("PIVOT_ANGLE", 4, AR_WPNav, _pivot_angle, AR_WPNAV_PIVOT_ANGLE_DEFAULT),
  56. // @Param: PIVOT_RATE
  57. // @DisplayName: Waypoint Pivot Turn Rate
  58. // @Description: Turn rate during pivot turns
  59. // @Units: deg/s
  60. // @Range: 0 360
  61. // @Increment: 1
  62. // @User: Standard
  63. AP_GROUPINFO("PIVOT_RATE", 5, AR_WPNav, _pivot_rate, AR_WPNAV_PIVOT_RATE_DEFAULT),
  64. // @Param: SPEED_MIN
  65. // @DisplayName: Waypoint speed minimum
  66. // @Description: Vehicle will not slow below this speed for corners. Should be set to boat's plane speed. Does not apply to pivot turns.
  67. // @Units: m/s
  68. // @Range: 0 100
  69. // @Increment: 0.1
  70. // @User: Standard
  71. AP_GROUPINFO("SPEED_MIN", 6, AR_WPNav, _speed_min, 0),
  72. AP_GROUPEND
  73. };
  74. AR_WPNav::AR_WPNav(AR_AttitudeControl& atc, AP_Navigation& nav_controller) :
  75. _atc(atc),
  76. _nav_controller(nav_controller)
  77. {
  78. AP_Param::setup_object_defaults(this, var_info);
  79. }
  80. // update navigation
  81. void AR_WPNav::update(float dt)
  82. {
  83. // exit immediately if no current location, origin or destination
  84. Location current_loc;
  85. float speed;
  86. if (!hal.util->get_soft_armed() || !_orig_and_dest_valid || !AP::ahrs().get_position(current_loc) || !_atc.get_forward_speed(speed)) {
  87. _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
  88. _desired_turn_rate_rads = 0.0f;
  89. return;
  90. }
  91. // if no recent calls initialise desired_speed_limited to current speed
  92. if (!is_active()) {
  93. _desired_speed_limited = speed;
  94. }
  95. _last_update_ms = AP_HAL::millis();
  96. // run path planning around obstacles
  97. bool stop_vehicle = false;
  98. AP_OAPathPlanner *oa = AP_OAPathPlanner::get_singleton();
  99. if (oa != nullptr) {
  100. const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, _origin, _destination, _oa_origin, _oa_destination);
  101. switch (oa_retstate) {
  102. case AP_OAPathPlanner::OA_NOT_REQUIRED:
  103. _oa_active = false;
  104. break;
  105. case AP_OAPathPlanner::OA_PROCESSING:
  106. case AP_OAPathPlanner::OA_ERROR:
  107. // during processing or in case of error, slow vehicle to a stop
  108. stop_vehicle = true;
  109. _oa_active = false;
  110. break;
  111. case AP_OAPathPlanner::OA_SUCCESS:
  112. _oa_active = true;
  113. break;
  114. }
  115. }
  116. if (!_oa_active) {
  117. _oa_origin = _origin;
  118. _oa_destination = _destination;
  119. }
  120. update_distance_and_bearing_to_destination();
  121. // check if vehicle has reached the destination
  122. const bool near_wp = _distance_to_destination <= _radius;
  123. const bool past_wp = !_oa_active && current_loc.past_interval_finish_line(_origin, _destination);
  124. if (!_reached_destination && (near_wp || past_wp)) {
  125. _reached_destination = true;
  126. }
  127. // handle stopping vehicle if avoidance has failed
  128. if (stop_vehicle) {
  129. // decelerate to speed to zero and set turn rate to zero
  130. _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
  131. _desired_lat_accel = 0.0f;
  132. _desired_turn_rate_rads = 0.0f;
  133. return;
  134. }
  135. // calculate the required turn of the wheels
  136. update_steering(current_loc, speed);
  137. // calculate desired speed
  138. update_desired_speed(dt);
  139. }
  140. // set desired location
  141. bool AR_WPNav::set_desired_location(const struct Location& destination, float next_leg_bearing_cd)
  142. {
  143. // set origin to last destination if waypoint controller active
  144. if (is_active() && _orig_and_dest_valid && _reached_destination) {
  145. _origin = _destination;
  146. } else {
  147. // otherwise use reasonable stopping point
  148. if (!get_stopping_location(_origin)) {
  149. return false;
  150. }
  151. }
  152. // initialise some variables
  153. _oa_origin = _origin;
  154. _oa_destination = _destination = destination;
  155. _orig_and_dest_valid = true;
  156. _reached_destination = false;
  157. update_distance_and_bearing_to_destination();
  158. // set final desired speed
  159. _desired_speed_final = 0.0f;
  160. if (!is_equal(next_leg_bearing_cd, AR_WPNAV_HEADING_UNKNOWN)) {
  161. const float curr_leg_bearing_cd = _origin.get_bearing_to(_destination);
  162. const float turn_angle_cd = wrap_180_cd(next_leg_bearing_cd - curr_leg_bearing_cd);
  163. if (fabsf(turn_angle_cd) < 10.0f) {
  164. // if turning less than 0.1 degrees vehicle can continue at full speed
  165. // we use 0.1 degrees instead of zero to avoid divide by zero in calcs below
  166. _desired_speed_final = _desired_speed;
  167. } else if (use_pivot_steering_at_next_WP(turn_angle_cd)) {
  168. // pivoting so we will stop
  169. _desired_speed_final = 0.0f;
  170. } else {
  171. // calculate maximum speed that keeps overshoot within bounds
  172. const float radius_m = fabsf(_overshoot / (cosf(radians(turn_angle_cd * 0.01f)) - 1.0f));
  173. _desired_speed_final = MIN(_desired_speed, safe_sqrt(_turn_max_mss * radius_m));
  174. // ensure speed does not fall below minimum
  175. apply_speed_min(_desired_speed_final);
  176. }
  177. }
  178. return true;
  179. }
  180. // set desired location to a reasonable stopping point, return true on success
  181. bool AR_WPNav::set_desired_location_to_stopping_location()
  182. {
  183. Location stopping_loc;
  184. if (!get_stopping_location(stopping_loc)) {
  185. return false;
  186. }
  187. return set_desired_location(stopping_loc);
  188. }
  189. // set desired location as offset from the EKF origin, return true on success
  190. bool AR_WPNav::set_desired_location_NED(const Vector3f& destination, float next_leg_bearing_cd)
  191. {
  192. // initialise destination to ekf origin
  193. Location destination_ned;
  194. if (!AP::ahrs().get_origin(destination_ned)) {
  195. return false;
  196. }
  197. // apply offset
  198. destination_ned.offset(destination.x, destination.y);
  199. return set_desired_location(destination_ned, next_leg_bearing_cd);
  200. }
  201. // calculate vehicle stopping point using current location, velocity and maximum acceleration
  202. bool AR_WPNav::get_stopping_location(Location& stopping_loc)
  203. {
  204. Location current_loc;
  205. if (!AP::ahrs().get_position(current_loc)) {
  206. return false;
  207. }
  208. // get current velocity vector and speed
  209. const Vector2f velocity = AP::ahrs().groundspeed_vector();
  210. const float speed = velocity.length();
  211. // avoid divide by zero
  212. if (!is_positive(speed)) {
  213. stopping_loc = current_loc;
  214. return true;
  215. }
  216. // get stopping distance in meters
  217. const float stopping_dist = _atc.get_stopping_distance(speed);
  218. // calculate stopping position from current location in meters
  219. const Vector2f stopping_offset = velocity.normalized() * stopping_dist;
  220. stopping_loc = current_loc;
  221. stopping_loc.offset(stopping_offset.x, stopping_offset.y);
  222. return true;
  223. }
  224. // returns true if vehicle should pivot turn at next waypoint
  225. bool AR_WPNav::use_pivot_steering_at_next_WP(float yaw_error_cd) const
  226. {
  227. // check cases where we clearly cannot use pivot steering
  228. if (!_pivot_possible || _pivot_angle <= 0) {
  229. return false;
  230. }
  231. // if error is larger than _pivot_angle then use pivot steering at next WP
  232. if (fabsf(yaw_error_cd) * 0.01f > _pivot_angle) {
  233. return true;
  234. }
  235. return false;
  236. }
  237. // returns true if vehicle should pivot immediately (because heading error is too large)
  238. bool AR_WPNav::use_pivot_steering(float yaw_error_cd)
  239. {
  240. // check cases where we clearly cannot use pivot steering
  241. if (!_pivot_possible || (_pivot_angle <= 0)) {
  242. _pivot_active = false;
  243. return false;
  244. }
  245. // calc bearing error
  246. const float yaw_error = fabsf(yaw_error_cd) * 0.01f;
  247. // if error is larger than _pivot_angle start pivot steering
  248. if (yaw_error > _pivot_angle) {
  249. _pivot_active = true;
  250. return true;
  251. }
  252. // if within 10 degrees of the target heading, exit pivot steering
  253. if (yaw_error < 10.0f) {
  254. _pivot_active = false;
  255. return false;
  256. }
  257. // by default stay in
  258. return _pivot_active;
  259. }
  260. // true if update has been called recently
  261. bool AR_WPNav::is_active() const
  262. {
  263. return ((AP_HAL::millis() - _last_update_ms) < AR_WPNAV_TIMEOUT_MS);
  264. }
  265. // update distance from vehicle's current position to destination
  266. void AR_WPNav::update_distance_and_bearing_to_destination()
  267. {
  268. // if no current location leave distance unchanged
  269. Location current_loc;
  270. if (!_orig_and_dest_valid || !AP::ahrs().get_position(current_loc)) {
  271. _distance_to_destination = 0.0f;
  272. _wp_bearing_cd = 0.0f;
  273. // update OA adjusted values
  274. _oa_distance_to_destination = 0.0f;
  275. _oa_wp_bearing_cd = 0.0f;
  276. return;
  277. }
  278. _distance_to_destination = current_loc.get_distance(_destination);
  279. _wp_bearing_cd = current_loc.get_bearing_to(_destination);
  280. // update OA adjusted values
  281. if (_oa_active) {
  282. _oa_distance_to_destination = current_loc.get_distance(_oa_destination);
  283. _oa_wp_bearing_cd = current_loc.get_bearing_to(_oa_destination);
  284. } else {
  285. _oa_distance_to_destination = _distance_to_destination;
  286. _oa_wp_bearing_cd = _wp_bearing_cd;
  287. }
  288. }
  289. // calculate steering output to drive along line from origin to destination waypoint
  290. // relies on update_distance_and_bearing_to_destination being called first so _wp_bearing_cd has been updated
  291. void AR_WPNav::update_steering(const Location& current_loc, float current_speed)
  292. {
  293. // calculate yaw error for determining if vehicle should pivot towards waypoint
  294. float yaw_cd = _reversed ? wrap_360_cd(_oa_wp_bearing_cd + 18000) : _oa_wp_bearing_cd;
  295. float yaw_error_cd = wrap_180_cd(yaw_cd - AP::ahrs().yaw_sensor);
  296. // calculate desired turn rate and update desired heading
  297. if (use_pivot_steering(yaw_error_cd)) {
  298. _cross_track_error = 0.0f;
  299. _desired_heading_cd = yaw_cd;
  300. _desired_lat_accel = 0.0f;
  301. _desired_turn_rate_rads = _atc.get_turn_rate_from_heading(radians(yaw_cd * 0.01f), radians(_pivot_rate));
  302. } else {
  303. // run L1 controller
  304. _nav_controller.set_reverse(_reversed);
  305. _nav_controller.update_waypoint(_reached_destination ? current_loc : _oa_origin, _oa_destination, _radius);
  306. // retrieve lateral acceleration, heading back towards line and crosstrack error
  307. _desired_lat_accel = constrain_float(_nav_controller.lateral_acceleration(), -_turn_max_mss, _turn_max_mss);
  308. _desired_heading_cd = wrap_360_cd(_nav_controller.nav_bearing_cd());
  309. if (_reversed) {
  310. _desired_lat_accel *= -1.0f;
  311. _desired_heading_cd = wrap_360_cd(_desired_heading_cd + 18000);
  312. }
  313. _cross_track_error = _nav_controller.crosstrack_error();
  314. _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, current_speed);
  315. }
  316. }
  317. // calculated desired speed(in m/s) based on yaw error and lateral acceleration and/or distance to a waypoint
  318. // relies on update_distance_and_bearing_to_destination and update_steering being run so these internal members
  319. // have been updated: _oa_wp_bearing_cd, _cross_track_error, _oa_distance_to_destination
  320. void AR_WPNav::update_desired_speed(float dt)
  321. {
  322. // reduce speed to zero during pivot turns
  323. if (_pivot_active) {
  324. // decelerate to zero
  325. _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
  326. return;
  327. }
  328. // accelerate desired speed towards max
  329. float des_speed_lim = _atc.get_desired_speed_accel_limited(_reversed ? -_desired_speed : _desired_speed, dt);
  330. // reduce speed to limit overshoot from line between origin and destination
  331. // calculate number of degrees vehicle must turn to face waypoint
  332. float ahrs_yaw_sensor = AP::ahrs().yaw_sensor;
  333. const float heading_cd = is_negative(des_speed_lim) ? wrap_180_cd(ahrs_yaw_sensor + 18000) : ahrs_yaw_sensor;
  334. const float wp_yaw_diff_cd = wrap_180_cd(_oa_wp_bearing_cd - heading_cd);
  335. const float turn_angle_rad = fabsf(radians(wp_yaw_diff_cd * 0.01f));
  336. // calculate distance from vehicle to line + wp_overshoot
  337. const float line_yaw_diff = wrap_180_cd(_oa_origin.get_bearing_to(_oa_destination) - heading_cd);
  338. const float dist_from_line = fabsf(_cross_track_error);
  339. const bool heading_away = is_positive(line_yaw_diff) == is_positive(_cross_track_error);
  340. const float wp_overshoot_adj = heading_away ? -dist_from_line : dist_from_line;
  341. // calculate radius of circle that touches vehicle's current position and heading and target position and heading
  342. float radius_m = 999.0f;
  343. const float radius_calc_denom = fabsf(1.0f - cosf(turn_angle_rad));
  344. if (!is_zero(radius_calc_denom)) {
  345. radius_m = MAX(0.0f, _overshoot + wp_overshoot_adj) / radius_calc_denom;
  346. }
  347. // calculate and limit speed to allow vehicle to stay on circle
  348. const float overshoot_speed_max = safe_sqrt(_turn_max_mss * MAX(_turn_radius, radius_m));
  349. des_speed_lim = constrain_float(des_speed_lim, -overshoot_speed_max, overshoot_speed_max);
  350. // ensure speed does not fall below minimum
  351. apply_speed_min(des_speed_lim);
  352. // limit speed based on distance to waypoint and max acceleration/deceleration
  353. if (is_positive(_oa_distance_to_destination) && is_positive(_atc.get_decel_max())) {
  354. const float dist_speed_max = safe_sqrt(2.0f * _oa_distance_to_destination * _atc.get_decel_max() + sq(_desired_speed_final));
  355. des_speed_lim = constrain_float(des_speed_lim, -dist_speed_max, dist_speed_max);
  356. }
  357. _desired_speed_limited = des_speed_lim;
  358. }
  359. // settor to allow vehicle code to provide turn related param values to this library (should be updated regularly)
  360. void AR_WPNav::set_turn_params(float turn_max_g, float turn_radius, bool pivot_possible)
  361. {
  362. _turn_max_mss = turn_max_g * GRAVITY_MSS;
  363. _turn_radius = turn_radius;
  364. _pivot_possible = pivot_possible;
  365. }
  366. // set default overshoot (used for sailboats)
  367. void AR_WPNav::set_default_overshoot(float overshoot)
  368. {
  369. _overshoot.set_default(overshoot);
  370. }
  371. // adjust speed to ensure it does not fall below value held in SPEED_MIN
  372. void AR_WPNav::apply_speed_min(float &desired_speed)
  373. {
  374. if (!is_positive(_speed_min)) {
  375. return;
  376. }
  377. float speed_min = MIN(_speed_min, _speed_max);
  378. // ensure speed does not fall below minimum
  379. if (fabsf(desired_speed) < speed_min) {
  380. desired_speed = is_negative(desired_speed) ? -speed_min : speed_min;
  381. }
  382. }