mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Avoidance: Dijkstra's exits early if polygon fence disabled
This commit is contained in:
parent
23f5fabbcf
commit
bba81b2794
@ -37,6 +37,11 @@ bool AP_OADijkstra::update(const Location ¤t_loc, const Location &destinat
|
||||
return false;
|
||||
}
|
||||
|
||||
// no avoidance required if fence is disabled
|
||||
if (!polygon_fence_enabled()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for fence updates
|
||||
if (check_polygon_fence_updated()) {
|
||||
_polyfence_with_margin_ok = false;
|
||||
@ -110,6 +115,16 @@ bool AP_OADijkstra::update(const Location ¤t_loc, const Location &destinat
|
||||
return false;
|
||||
}
|
||||
|
||||
// returns true if polygon fence is enabled
|
||||
bool AP_OADijkstra::polygon_fence_enabled() const
|
||||
{
|
||||
const AC_Fence *fence = AC_Fence::get_singleton();
|
||||
if (fence == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) > 0);
|
||||
}
|
||||
|
||||
// check if polygon fence has been updated since we created the inner fence. returns true if changed
|
||||
bool AP_OADijkstra::check_polygon_fence_updated() const
|
||||
{
|
||||
|
@ -31,6 +31,9 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
// returns true if polygon fence is enabled
|
||||
bool polygon_fence_enabled() const;
|
||||
|
||||
// check if polygon fence has been updated since we created the inner fence. returns true if changed
|
||||
bool check_polygon_fence_updated() const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user