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

This commit is contained in:
Randy Mackay 2019-07-24 14:42:22 +09:00
parent bed21b43e1
commit 452be5fd94

View File

@ -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;