AP_OADijkstra.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551
  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_OADijkstra.h"
  14. #include <AC_Fence/AC_Fence.h>
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <AP_Logger/AP_Logger.h>
  17. #define OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK 32 // expanding arrays for inner polygon fence and paths to destination will grow in increments of 20 elements
  18. #define OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX 255 // index use to indicate we do not have a tentative short path for a node
  19. /// Constructor
  20. AP_OADijkstra::AP_OADijkstra() :
  21. _polyfence_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),
  22. _short_path_data(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),
  23. _path(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK)
  24. {
  25. }
  26. // calculate a destination to avoid the polygon fence
  27. // returns DIJKSTRA_STATE_SUCCESS and populates origin_new and destination_new if avoidance is required
  28. AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location &current_loc, const Location &destination, Location& origin_new, Location& destination_new)
  29. {
  30. // require ekf origin to have been set
  31. struct Location ekf_origin {};
  32. if (!AP::ahrs().get_origin(ekf_origin)) {
  33. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, destination, destination);
  34. return DIJKSTRA_STATE_NOT_REQUIRED;
  35. }
  36. // no avoidance required if fence is disabled
  37. if (!polygon_fence_enabled()) {
  38. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, destination, destination);
  39. return DIJKSTRA_STATE_NOT_REQUIRED;
  40. }
  41. // no avoidance required if destination is same as current location
  42. if (current_loc.same_latlon_as(destination)) {
  43. return DIJKSTRA_STATE_NOT_REQUIRED;
  44. }
  45. // check for fence updates
  46. if (check_polygon_fence_updated()) {
  47. _polyfence_with_margin_ok = false;
  48. _polyfence_visgraph_ok = false;
  49. _shortest_path_ok = false;
  50. }
  51. // create inner polygon fence
  52. if (!_polyfence_with_margin_ok) {
  53. _polyfence_with_margin_ok = create_polygon_fence_with_margin(_polyfence_margin * 100.0f);
  54. if (!_polyfence_with_margin_ok) {
  55. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_ERROR, 0, 0, destination, destination);
  56. return DIJKSTRA_STATE_ERROR;
  57. }
  58. }
  59. // create visgraph for inner polygon fence
  60. if (!_polyfence_visgraph_ok) {
  61. _polyfence_visgraph_ok = create_polygon_fence_visgraph();
  62. if (!_polyfence_visgraph_ok) {
  63. _shortest_path_ok = false;
  64. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_ERROR, 0, 0, destination, destination);
  65. return DIJKSTRA_STATE_ERROR;
  66. }
  67. }
  68. // rebuild path if destination has changed
  69. if (!destination.same_latlon_as(_destination_prev)) {
  70. _destination_prev = destination;
  71. _shortest_path_ok = false;
  72. }
  73. // calculate shortest path from current_loc to destination
  74. if (!_shortest_path_ok) {
  75. _shortest_path_ok = calc_shortest_path(current_loc, destination);
  76. if (!_shortest_path_ok) {
  77. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_ERROR, 0, 0, destination, destination);
  78. return DIJKSTRA_STATE_ERROR;
  79. }
  80. // start from 2nd point on path (first is the original origin)
  81. _path_idx_returned = 1;
  82. }
  83. // path has been created, return latest point
  84. Vector2f dest_pos;
  85. if (get_shortest_path_point(_path_idx_returned, dest_pos)) {
  86. // for the first point return origin as current_loc
  87. Vector2f origin_pos;
  88. if ((_path_idx_returned > 0) && get_shortest_path_point(_path_idx_returned-1, origin_pos)) {
  89. // convert offset from ekf origin to Location
  90. Location temp_loc(Vector3f(origin_pos.x, origin_pos.y, 0.0f));
  91. origin_new = temp_loc;
  92. } else {
  93. // for first point use current loc as origin
  94. origin_new = current_loc;
  95. }
  96. // convert offset from ekf origin to Location
  97. Location temp_loc(Vector3f(dest_pos.x, dest_pos.y, 0.0f));
  98. destination_new = destination;
  99. destination_new.lat = temp_loc.lat;
  100. destination_new.lng = temp_loc.lng;
  101. // check if we should advance to next point for next iteration
  102. const bool near_oa_wp = current_loc.get_distance(destination_new) <= 2.0f;
  103. const bool past_oa_wp = current_loc.past_interval_finish_line(origin_new, destination_new);
  104. if (near_oa_wp || past_oa_wp) {
  105. _path_idx_returned++;
  106. }
  107. // log success
  108. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_SUCCESS, _path_idx_returned, _path_numpoints, destination, destination_new);
  109. return DIJKSTRA_STATE_SUCCESS;
  110. }
  111. // we have reached the destination so avoidance is no longer required
  112. AP::logger().Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, destination, destination);
  113. return DIJKSTRA_STATE_NOT_REQUIRED;
  114. }
  115. // returns true if polygon fence is enabled
  116. bool AP_OADijkstra::polygon_fence_enabled() const
  117. {
  118. const AC_Fence *fence = AC_Fence::get_singleton();
  119. if (fence == nullptr) {
  120. return false;
  121. }
  122. if (!fence->is_polygon_valid()) {
  123. return false;
  124. }
  125. return ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) > 0);
  126. }
  127. // check if polygon fence has been updated since we created the inner fence. returns true if changed
  128. bool AP_OADijkstra::check_polygon_fence_updated() const
  129. {
  130. // exit immediately if polygon fence is not enabled
  131. const AC_Fence *fence = AC_Fence::get_singleton();
  132. if (fence == nullptr) {
  133. return false;
  134. }
  135. return (_polyfence_update_ms != fence->get_boundary_update_ms());
  136. }
  137. // create a smaller polygon fence within the existing polygon fence
  138. // returns true on success
  139. bool AP_OADijkstra::create_polygon_fence_with_margin(float margin_cm)
  140. {
  141. // exit immediately if polygon fence is not enabled
  142. const AC_Fence *fence = AC_Fence::get_singleton();
  143. if (fence == nullptr) {
  144. return false;
  145. }
  146. // get polygon boundary
  147. uint16_t num_points;
  148. const Vector2f* boundary = fence->get_boundary_points(num_points);
  149. if ((boundary == nullptr) || (num_points < 3)) {
  150. return false;
  151. }
  152. // expand fence point array if required
  153. if (!_polyfence_pts.expand_to_hold(num_points)) {
  154. return false;
  155. }
  156. // for each point on polygon fence
  157. // Note: boundary is "unclosed" meaning the last point is *not* the same as the first
  158. for (uint8_t i=0; i<num_points; i++) {
  159. // find points before and after current point (relative to current point)
  160. const uint8_t before_idx = (i == 0) ? num_points-1 : i-1;
  161. const uint8_t after_idx = (i == num_points-1) ? 0 : i+1;
  162. Vector2f before_pt = boundary[before_idx] - boundary[i];
  163. Vector2f after_pt = boundary[after_idx] - boundary[i];
  164. // if points are overlapping fail
  165. if (before_pt.is_zero() || after_pt.is_zero() || (before_pt == after_pt)) {
  166. return false;
  167. }
  168. // scale points to be unit vectors
  169. before_pt.normalize();
  170. after_pt.normalize();
  171. // calculate intermediate point and scale to margin
  172. Vector2f intermediate_pt = (after_pt + before_pt) * 0.5f;
  173. float intermediate_len = intermediate_pt.length();
  174. intermediate_pt *= (margin_cm / intermediate_len);
  175. // find final point which is inside the original polygon
  176. _polyfence_pts[i] = boundary[i] + intermediate_pt;
  177. if (Polygon_outside(_polyfence_pts[i], boundary, num_points)) {
  178. _polyfence_pts[i] = boundary[i] - intermediate_pt;
  179. if (Polygon_outside(_polyfence_pts[i], boundary, num_points)) {
  180. // could not find a point on either side that was within the fence so fail
  181. // this can happen if fence lines are closer than margin_cm
  182. return false;
  183. }
  184. }
  185. }
  186. // update number of fence points
  187. _polyfence_numpoints = num_points;
  188. // record fence update time so we don't process this exact fence again
  189. _polyfence_update_ms = fence->get_boundary_update_ms();
  190. return true;
  191. }
  192. // create a visibility graph of the polygon fence
  193. // returns true on success
  194. // requires create_polygon_fence_with_margin to have been run
  195. bool AP_OADijkstra::create_polygon_fence_visgraph()
  196. {
  197. // exit immediately if no polygon fence (with margin)
  198. if (_polyfence_numpoints == 0) {
  199. return false;
  200. }
  201. // exit immediately if polygon fence is not enabled
  202. const AC_Fence *fence = AC_Fence::get_singleton();
  203. if (fence == nullptr) {
  204. return false;
  205. }
  206. // get polygon boundary
  207. uint16_t num_points;
  208. const Vector2f* boundary = fence->get_boundary_points(num_points);
  209. if ((boundary == nullptr) || (num_points < 3)) {
  210. return false;
  211. }
  212. // fail if more than number of polygon points algorithm can handle
  213. if (num_points >= OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX) {
  214. return false;
  215. }
  216. // clear polygon visibility graph
  217. _polyfence_visgraph.clear();
  218. // calculate distance from each polygon fence point to all other points
  219. for (uint8_t i=0; i<_polyfence_numpoints-1; i++) {
  220. const Vector2f &start1 = _polyfence_pts[i];
  221. for (uint8_t j=i+1; j<_polyfence_numpoints; j++) {
  222. const Vector2f &end1 = _polyfence_pts[j];
  223. Vector2f intersection;
  224. // ToDo: calculation below could be sped up by removing unused intersection and
  225. // skipping segments we know are parallel to our fence-with-margin segments
  226. if (!Polygon_intersects(boundary, num_points, start1, end1, intersection)) {
  227. // line segment does not intersect with original fence so add to visgraph
  228. _polyfence_visgraph.add_item({AP_OAVisGraph::OATYPE_FENCE_POINT, i},
  229. {AP_OAVisGraph::OATYPE_FENCE_POINT, j},
  230. (_polyfence_pts[i] - _polyfence_pts[j]).length());
  231. }
  232. }
  233. }
  234. return true;
  235. }
  236. // updates visibility graph for a given position which is an offset (in cm) from the ekf origin
  237. // to add an additional position (i.e. the destination) set add_extra_position = true and provide the position in the extra_position argument
  238. // requires create_polygon_fence_with_margin to have been run
  239. // returns true on success
  240. bool AP_OADijkstra::update_visgraph(AP_OAVisGraph& visgraph, const AP_OAVisGraph::OAItemID& oaid, const Vector2f &position, bool add_extra_position, Vector2f extra_position)
  241. {
  242. // exit immediately if no polygon fence (with margin)
  243. if (_polyfence_numpoints == 0) {
  244. return false;
  245. }
  246. // exit immediately if polygon fence is not enabled
  247. const AC_Fence *fence = AC_Fence::get_singleton();
  248. if (fence == nullptr) {
  249. return false;
  250. }
  251. // get polygon boundary
  252. uint16_t num_points;
  253. const Vector2f* boundary = fence->get_boundary_points(num_points);
  254. if ((boundary == nullptr) || (num_points < 3)) {
  255. return false;
  256. }
  257. // clear visibility graph
  258. visgraph.clear();
  259. // calculate distance from extra_position to all fence points
  260. for (uint8_t i=0; i<_polyfence_numpoints; i++) {
  261. Vector2f intersection;
  262. if (!Polygon_intersects(boundary, num_points, position, _polyfence_pts[i], intersection)) {
  263. // line segment does not intersect with original fence so add to visgraph
  264. visgraph.add_item(oaid, {AP_OAVisGraph::OATYPE_FENCE_POINT, i}, (position - _polyfence_pts[i]).length());
  265. }
  266. // ToDo: store infinity when there is no clear path between points to allow faster search later
  267. }
  268. // add extra point to visibility graph if it doesn't intersect with polygon fence
  269. if (add_extra_position) {
  270. Vector2f intersection;
  271. if (!Polygon_intersects(boundary, num_points, position, extra_position, intersection)) {
  272. visgraph.add_item(oaid, {AP_OAVisGraph::OATYPE_DESTINATION, 0}, (position - extra_position).length());
  273. }
  274. }
  275. return true;
  276. }
  277. // update total distance for all nodes visible from current node
  278. // curr_node_idx is an index into the _short_path_data array
  279. void AP_OADijkstra::update_visible_node_distances(node_index curr_node_idx)
  280. {
  281. // sanity check
  282. if (curr_node_idx > _short_path_data_numpoints) {
  283. return;
  284. }
  285. // get current node for convenience
  286. const ShortPathNode &curr_node = _short_path_data[curr_node_idx];
  287. // for each visibility graph
  288. const AP_OAVisGraph* visgraphs[] = {&_polyfence_visgraph, &_destination_visgraph};
  289. for (uint8_t v=0; v<ARRAY_SIZE(visgraphs); v++) {
  290. // skip if empty
  291. const AP_OAVisGraph &curr_visgraph = *visgraphs[v];
  292. if (curr_visgraph.num_items() == 0) {
  293. continue;
  294. }
  295. // search visibility graph for items visible from current_node
  296. for (uint8_t i=0; i<curr_visgraph.num_items(); i++) {
  297. const AP_OAVisGraph::VisGraphItem &item = curr_visgraph[i];
  298. // match if current node's id matches either of the id's in the graph (i.e. either end of the vector)
  299. if ((curr_node.id == item.id1) || (curr_node.id == item.id2)) {
  300. AP_OAVisGraph::OAItemID matching_id = (curr_node.id == item.id1) ? item.id2 : item.id1;
  301. // find item's id in node array
  302. node_index item_node_idx;
  303. if (find_node_from_id(matching_id, item_node_idx)) {
  304. // if current node's distance + distance to item is less than item's current distance, update item's distance
  305. const float dist_to_item_via_current_node = _short_path_data[curr_node_idx].distance_cm + item.distance_cm;
  306. if (dist_to_item_via_current_node < _short_path_data[item_node_idx].distance_cm) {
  307. // update item's distance and set "distance_from_idx" to current node's index
  308. _short_path_data[item_node_idx].distance_cm = dist_to_item_via_current_node;
  309. _short_path_data[item_node_idx].distance_from_idx = curr_node_idx;
  310. }
  311. }
  312. }
  313. }
  314. }
  315. }
  316. // find a node's index into _short_path_data array from it's id (i.e. id type and id number)
  317. // returns true if successful and node_idx is updated
  318. bool AP_OADijkstra::find_node_from_id(const AP_OAVisGraph::OAItemID &id, node_index &node_idx) const
  319. {
  320. switch (id.id_type) {
  321. case AP_OAVisGraph::OATYPE_SOURCE:
  322. // source node is always the first node
  323. if (_short_path_data_numpoints > 0) {
  324. node_idx = 0;
  325. return true;
  326. }
  327. break;
  328. case AP_OAVisGraph::OATYPE_DESTINATION:
  329. // destination is always the 2nd node
  330. if (_short_path_data_numpoints > 1) {
  331. node_idx = 1;
  332. return true;
  333. }
  334. break;
  335. case AP_OAVisGraph::OATYPE_FENCE_POINT:
  336. // must be a fence node which start from 3rd node
  337. if (_short_path_data_numpoints > id.id_num + 2) {
  338. node_idx = id.id_num + 2;
  339. return true;
  340. }
  341. break;
  342. }
  343. // could not find node
  344. return false;
  345. }
  346. // find index of node with lowest tentative distance (ignore visited nodes)
  347. // returns true if successful and node_idx argument is updated
  348. bool AP_OADijkstra::find_closest_node_idx(node_index &node_idx) const
  349. {
  350. node_index lowest_idx = 0;
  351. float lowest_dist = FLT_MAX;
  352. // scan through all nodes looking for closest
  353. for (node_index i=0; i<_short_path_data_numpoints; i++) {
  354. const ShortPathNode &node = _short_path_data[i];
  355. if (!node.visited && (node.distance_cm < lowest_dist)) {
  356. lowest_idx = i;
  357. lowest_dist = node.distance_cm;
  358. }
  359. }
  360. if (lowest_dist < FLT_MAX) {
  361. node_idx = lowest_idx;
  362. return true;
  363. }
  364. return false;
  365. }
  366. // calculate shortest path from origin to destination
  367. // returns true on success
  368. // requires create_polygon_fence_with_margin and create_polygon_fence_visgraph to have been run
  369. // resulting path is stored in _shortest_path array as vector offsets from EKF origin
  370. bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &destination)
  371. {
  372. // convert origin and destination to offsets from EKF origin
  373. Vector2f origin_NE, destination_NE;
  374. if (!origin.get_vector_xy_from_origin_NE(origin_NE) || !destination.get_vector_xy_from_origin_NE(destination_NE)) {
  375. return false;
  376. }
  377. // create origin and destination visgraphs of polygon points
  378. update_visgraph(_source_visgraph, {AP_OAVisGraph::OATYPE_SOURCE, 0}, origin_NE, true, destination_NE);
  379. update_visgraph(_destination_visgraph, {AP_OAVisGraph::OATYPE_DESTINATION, 0}, destination_NE);
  380. // expand _short_path_data if necessary
  381. if (!_short_path_data.expand_to_hold(2 + _polyfence_numpoints)) {
  382. return false;
  383. }
  384. // add origin and destination (node_type, id, visited, distance_from_idx, distance_cm) to short_path_data array
  385. _short_path_data[0] = {{AP_OAVisGraph::OATYPE_SOURCE, 0}, false, 0, 0};
  386. _short_path_data[1] = {{AP_OAVisGraph::OATYPE_DESTINATION, 0}, false, OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX, FLT_MAX};
  387. _short_path_data_numpoints = 2;
  388. // add fence points to short_path_data array (node_type, id, visited, distance_from_idx, distance_cm)
  389. for (uint8_t i=0; i<_polyfence_numpoints; i++) {
  390. _short_path_data[_short_path_data_numpoints++] = {{AP_OAVisGraph::OATYPE_FENCE_POINT, i}, false, OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX, FLT_MAX};
  391. }
  392. // start algorithm from source point
  393. node_index current_node_idx = 0;
  394. // update nodes visible from source point
  395. for (uint8_t i=0; i<_source_visgraph.num_items(); i++) {
  396. node_index node_idx;
  397. if (find_node_from_id(_source_visgraph[i].id2, node_idx)) {
  398. _short_path_data[node_idx].distance_cm = _source_visgraph[i].distance_cm;
  399. _short_path_data[node_idx].distance_from_idx = current_node_idx;
  400. } else {
  401. return false;
  402. }
  403. }
  404. // mark source node as visited
  405. _short_path_data[current_node_idx].visited = true;
  406. // move current_node_idx to node with lowest distance
  407. while (find_closest_node_idx(current_node_idx)) {
  408. // update distances to all neighbours of current node
  409. update_visible_node_distances(current_node_idx);
  410. // mark current node as visited
  411. _short_path_data[current_node_idx].visited = true;
  412. }
  413. // extract path starting from destination
  414. bool success = false;
  415. node_index nidx;
  416. if (!find_node_from_id({AP_OAVisGraph::OATYPE_DESTINATION,0}, nidx)) {
  417. return false;
  418. }
  419. _path_numpoints = 0;
  420. while (true) {
  421. // fail if out of space
  422. if (_path_numpoints >= _path.max_items()) {
  423. if (!_path.expand()) {
  424. break;
  425. }
  426. }
  427. // fail if newest node has invalid distance_from_index
  428. if ((_short_path_data[nidx].distance_from_idx == OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX) ||
  429. (_short_path_data[nidx].distance_cm >= FLT_MAX)) {
  430. break;
  431. } else {
  432. // add node's id to path array
  433. _path[_path_numpoints] = _short_path_data[nidx].id;
  434. _path_numpoints++;
  435. // we are done if node is the source
  436. if (_short_path_data[nidx].id.id_type == AP_OAVisGraph::OATYPE_SOURCE) {
  437. success = true;
  438. break;
  439. } else {
  440. // follow node's "distance_from_idx" to previous node on path
  441. nidx = _short_path_data[nidx].distance_from_idx;
  442. }
  443. }
  444. }
  445. // update source and destination for by get_shortest_path_point
  446. if (success) {
  447. _path_source = origin_NE;
  448. _path_destination = destination_NE;
  449. }
  450. return success;
  451. }
  452. // return point from final path as an offset (in cm) from the ekf origin
  453. bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos)
  454. {
  455. if ((_path_numpoints == 0) || (point_num >= _path_numpoints)) {
  456. return false;
  457. }
  458. // get id from path
  459. AP_OAVisGraph::OAItemID id = _path[_path_numpoints - point_num - 1];
  460. // convert id to a position offset from EKF origin
  461. switch (id.id_type) {
  462. case AP_OAVisGraph::OATYPE_SOURCE:
  463. pos = _path_source;
  464. return true;
  465. case AP_OAVisGraph::OATYPE_DESTINATION:
  466. pos = _path_destination;
  467. return true;
  468. case AP_OAVisGraph::OATYPE_FENCE_POINT:
  469. // sanity check polygon fence has the point
  470. if (id.id_num < _polyfence_numpoints) {
  471. pos = _polyfence_pts[id.id_num];
  472. return true;
  473. }
  474. return false;
  475. }
  476. // we should never reach here but just in case
  477. return false;
  478. }