Browse Source

AC_Avoidance: Dijkstra skips calcs if current loc is same as destination

mission-4.1.18
Randy Mackay 6 years ago
parent
commit
452be5fd94
  1. 5
      libraries/AC_Avoidance/AP_OADijkstra.cpp

5
libraries/AC_Avoidance/AP_OADijkstra.cpp

@ -47,6 +47,11 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location &current @@ -47,6 +47,11 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location &current
return DIJKSTRA_STATE_NOT_REQUIRED;
}
// no avoidance required if destination is same as current location
if (current_loc.same_latlon_as(destination)) {
return DIJKSTRA_STATE_NOT_REQUIRED;
}
// check for fence updates
if (check_polygon_fence_updated()) {
_polyfence_with_margin_ok = false;

Loading…
Cancel
Save