mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_OABendyRuler: cope with polyfence holding boundary points
This commit is contained in:
parent
3a7f1b882e
commit
dfca32a2af
@ -206,13 +206,13 @@ bool AP_OABendyRuler::calc_margin_from_polygon_fence(const Location &start, cons
|
|||||||
if (fence == nullptr) {
|
if (fence == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) || !fence->is_polygon_valid()) {
|
if (((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) || !fence->polyfence_const().valid_const()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get polygon boundary
|
// get polygon boundary
|
||||||
uint16_t num_points;
|
uint16_t num_points;
|
||||||
const Vector2f* boundary = fence->get_boundary_points(num_points);
|
const Vector2f* boundary = fence->polyfence_const().get_boundary_points(num_points);
|
||||||
if (num_points < 3) {
|
if (num_points < 3) {
|
||||||
// this should have already been checked by is_polygon_valid() but just in case
|
// this should have already been checked by is_polygon_valid() but just in case
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user