AP_OABendyRuler.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277
  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_OABendyRuler.h"
  14. #include <AC_Avoidance/AP_OADatabase.h>
  15. #include <AC_Fence/AC_Fence.h>
  16. #include <AP_AHRS/AP_AHRS.h>
  17. #include <AP_Logger/AP_Logger.h>
  18. const int16_t OA_BENDYRULER_BEARING_INC = 5; // check every 5 degrees around vehicle
  19. const float OA_BENDYRULER_LOOKAHEAD_STEP2_RATIO = 1.0f; // step2's lookahead length as a ratio of step1's lookahead length
  20. const float OA_BENDYRULER_LOOKAHEAD_STEP2_MIN = 2.0f; // step2 checks at least this many meters past step1's location
  21. const float OA_BENDYRULER_LOOKAHEAD_PAST_DEST = 2.0f; // lookahead length will be at least this many meters past the destination
  22. const float OA_BENDYRULER_LOW_SPEED_SQUARED = (0.2f * 0.2f); // when ground course is below this speed squared, vehicle's heading will be used
  23. // run background task to find best path and update avoidance_results
  24. // returns true and updates origin_new and destination_new if a best path has been found
  25. bool AP_OABendyRuler::update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new)
  26. {
  27. // bendy ruler always sets origin to current_loc
  28. origin_new = current_loc;
  29. // calculate bearing and distance to final destination
  30. const float bearing_to_dest = current_loc.get_bearing_to(destination) * 0.01f;
  31. const float distance_to_dest = current_loc.get_distance(destination);
  32. // lookahead distance is adjusted dynamically based on avoidance results
  33. _current_lookahead = constrain_float(_current_lookahead, _lookahead * 0.5f, _lookahead);
  34. // calculate lookahead dist and time for step1. distance can be slightly longer than
  35. // the distance to the destination to allow room to dodge after reaching the destination
  36. const float lookahead_step1_dist = MIN(_current_lookahead, distance_to_dest + OA_BENDYRULER_LOOKAHEAD_PAST_DEST);
  37. // calculate lookahead dist for step2
  38. const float lookahead_step2_dist = _current_lookahead * OA_BENDYRULER_LOOKAHEAD_STEP2_RATIO;
  39. // get ground course
  40. float ground_course_deg;
  41. if (ground_speed_vec.length_squared() < OA_BENDYRULER_LOW_SPEED_SQUARED) {
  42. // with zero ground speed use vehicle's heading
  43. ground_course_deg = AP::ahrs().yaw_sensor * 0.01f;
  44. } else {
  45. ground_course_deg = degrees(ground_speed_vec.angle());
  46. }
  47. // check OA_BEARING_INC definition allows checking in all directions
  48. static_assert(360 % OA_BENDYRULER_BEARING_INC == 0, "check 360 is a multiple of OA_BEARING_INC");
  49. // search in OA_BENDYRULER_BEARING_INC degree increments around the vehicle alternating left
  50. // and right. For each direction check if vehicle would avoid all obstacles
  51. float best_bearing = bearing_to_dest;
  52. bool have_best_bearing = false;
  53. float best_margin = -FLT_MAX;
  54. float best_margin_bearing = best_bearing;
  55. for (uint8_t i = 0; i <= (170 / OA_BENDYRULER_BEARING_INC); i++) {
  56. for (uint8_t bdir = 0; bdir <= 1; bdir++) {
  57. // skip duplicate check of bearing straight towards destination
  58. if ((i==0) && (bdir > 0)) {
  59. continue;
  60. }
  61. // bearing that we are probing
  62. const float bearing_delta = i * OA_BENDYRULER_BEARING_INC * (bdir == 0 ? -1.0f : 1.0f);
  63. const float bearing_test = wrap_180(bearing_to_dest + bearing_delta);
  64. // ToDo: add effective groundspeed calculations using airspeed
  65. // ToDo: add prediction of vehicle's position change as part of turn to desired heading
  66. // test location is projected from current location at test bearing
  67. Location test_loc = current_loc;
  68. test_loc.offset_bearing(bearing_test, lookahead_step1_dist);
  69. // calculate margin from fence for this scenario
  70. float margin = calc_avoidance_margin(current_loc, test_loc);
  71. if (margin > best_margin) {
  72. best_margin_bearing = bearing_test;
  73. best_margin = margin;
  74. }
  75. if (margin > _margin_max) {
  76. // this bearing avoids obstacles out to the lookahead_step1_dist
  77. // now check in there is a clear path in three directions towards the destination
  78. if (!have_best_bearing) {
  79. best_bearing = bearing_test;
  80. have_best_bearing = true;
  81. } else if (fabsf(wrap_180(ground_course_deg - bearing_test)) <
  82. fabsf(wrap_180(ground_course_deg - best_bearing))) {
  83. // replace bearing with one that is closer to our current ground course
  84. best_bearing = bearing_test;
  85. }
  86. // perform second stage test in three directions looking for obstacles
  87. const float test_bearings[] { 0.0f, 45.0f, -45.0f };
  88. const float bearing_to_dest2 = test_loc.get_bearing_to(destination) * 0.01f;
  89. float distance2 = constrain_float(lookahead_step2_dist, OA_BENDYRULER_LOOKAHEAD_STEP2_MIN, test_loc.get_distance(destination));
  90. for (uint8_t j = 0; j < ARRAY_SIZE(test_bearings); j++) {
  91. float bearing_test2 = wrap_180(bearing_to_dest2 + test_bearings[j]);
  92. Location test_loc2 = test_loc;
  93. test_loc2.offset_bearing(bearing_test2, distance2);
  94. // calculate minimum margin to fence and obstacles for this scenario
  95. float margin2 = calc_avoidance_margin(test_loc, test_loc2);
  96. if (margin2 > _margin_max) {
  97. // all good, now project in the chosen direction by the full distance
  98. destination_new = current_loc;
  99. destination_new.offset_bearing(bearing_test, distance_to_dest);
  100. _current_lookahead = MIN(_lookahead, _current_lookahead * 1.1f);
  101. // if the chosen direction is directly towards the destination turn off avoidance
  102. const bool active = (i != 0 || j != 0);
  103. AP::logger().Write_OABendyRuler(active, bearing_to_dest, margin, destination, destination_new);
  104. return active;
  105. }
  106. }
  107. }
  108. }
  109. }
  110. float chosen_bearing;
  111. if (have_best_bearing) {
  112. // none of the directions tested were OK for 2-step checks. Choose the direction
  113. // that was best for the first step
  114. chosen_bearing = best_bearing;
  115. _current_lookahead = MIN(_lookahead, _current_lookahead * 1.05f);
  116. } else {
  117. // none of the possible paths had a positive margin. Choose
  118. // the one with the highest margin
  119. chosen_bearing = best_margin_bearing;
  120. _current_lookahead = MAX(_lookahead * 0.5f, _current_lookahead * 0.9f);
  121. }
  122. // calculate new target based on best effort
  123. destination_new = current_loc;
  124. destination_new.offset_bearing(chosen_bearing, distance_to_dest);
  125. // log results
  126. AP::logger().Write_OABendyRuler(true, chosen_bearing, best_margin, destination, destination_new);
  127. return true;
  128. }
  129. // calculate minimum distance between a segment and any obstacle
  130. float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Location &end)
  131. {
  132. float circular_fence_margin;
  133. if (!calc_margin_from_circular_fence(start, end, circular_fence_margin)) {
  134. circular_fence_margin = FLT_MAX;
  135. }
  136. float polygon_fence_margin;
  137. if (!calc_margin_from_polygon_fence(start, end, polygon_fence_margin)) {
  138. polygon_fence_margin = FLT_MAX;
  139. }
  140. float proximity_margin;
  141. if (!calc_margin_from_object_database(start, end, proximity_margin)) {
  142. proximity_margin = FLT_MAX;
  143. }
  144. // return smallest margin from any obstacle
  145. return MIN(MIN(circular_fence_margin, polygon_fence_margin), proximity_margin);
  146. }
  147. // calculate minimum distance between a path and the circular fence (centered on home)
  148. // on success returns true and updates margin
  149. bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, const Location &end, float &margin)
  150. {
  151. // exit immediately if polygon fence is not enabled
  152. const AC_Fence *fence = AC_Fence::get_singleton();
  153. if (fence == nullptr) {
  154. return false;
  155. }
  156. if ((fence->get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {
  157. return false;
  158. }
  159. // calculate start and end point's distance from home
  160. const Location &ahrs_home = AP::ahrs().get_home();
  161. const float start_dist_sq = ahrs_home.get_distance_NE(start).length_squared();
  162. const float end_dist_sq = ahrs_home.get_distance_NE(end).length_squared();
  163. // get circular fence radius
  164. const float fence_radius = fence->get_radius();
  165. // margin is fence radius minus the longer of start or end distance
  166. margin = fence_radius - sqrtf(MAX(start_dist_sq, end_dist_sq));
  167. return true;
  168. }
  169. // calculate minimum distance between a path and the polygon fence
  170. // on success returns true and updates margin
  171. bool AP_OABendyRuler::calc_margin_from_polygon_fence(const Location &start, const Location &end, float &margin)
  172. {
  173. // exit immediately if polygon fence is not enabled
  174. const AC_Fence *fence = AC_Fence::get_singleton();
  175. if (fence == nullptr) {
  176. return false;
  177. }
  178. if (((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) || !fence->is_polygon_valid()) {
  179. return false;
  180. }
  181. // get polygon boundary
  182. uint16_t num_points;
  183. const Vector2f* boundary = fence->get_boundary_points(num_points);
  184. if (num_points < 3) {
  185. // this should have already been checked by is_polygon_valid() but just in case
  186. return false;
  187. }
  188. // convert start and end to offsets from EKF origin
  189. Vector2f start_NE, end_NE;
  190. if (!start.get_vector_xy_from_origin_NE(start_NE) || !end.get_vector_xy_from_origin_NE(end_NE)) {
  191. return false;
  192. }
  193. // if outside the fence margin is the closest distance but with negative sign
  194. const float sign = Polygon_outside(start_NE, boundary, num_points) ? -1.0f : 1.0f;
  195. // calculate min distance (in meters) from line to polygon
  196. margin = sign * Polygon_closest_distance_line(boundary, num_points, start_NE, end_NE) * 0.01f;
  197. return true;
  198. }
  199. // calculate minimum distance between a path and proximity sensor obstacles
  200. // on success returns true and updates margin
  201. bool AP_OABendyRuler::calc_margin_from_object_database(const Location &start, const Location &end, float &margin)
  202. {
  203. #if !HAL_MINIMIZE_FEATURES
  204. // exit immediately if db is empty
  205. AP_OADatabase *oaDb = AP::oadatabase();
  206. if (oaDb == nullptr || !oaDb->healthy()) {
  207. return false;
  208. }
  209. // convert start and end to offsets (in cm) from EKF origin
  210. Vector2f start_NE, end_NE;
  211. if (!start.get_vector_xy_from_origin_NE(start_NE) || !end.get_vector_xy_from_origin_NE(end_NE)) {
  212. return false;
  213. }
  214. // check each obstacle's distance from segment
  215. float smallest_margin = FLT_MAX;
  216. for (uint16_t i=0; i<oaDb->database_count(); i++) {
  217. // convert obstacle's location to offset (in cm) from EKF origin
  218. Vector2f point;
  219. if (!oaDb->get_item(i).loc.get_vector_xy_from_origin_NE(point)) {
  220. continue;
  221. }
  222. // margin is distance between line segment and obstacle minus obstacle's radius
  223. const float m = Vector2f::closest_distance_between_line_and_point(start_NE, end_NE, point) * 0.01f - oaDb->get_accuracy();
  224. if (m < smallest_margin) {
  225. smallest_margin = m;
  226. }
  227. }
  228. // return smallest margin
  229. if (smallest_margin < FLT_MAX) {
  230. margin = smallest_margin;
  231. return true;
  232. }
  233. #endif
  234. return false;
  235. }