Skip to content

Commit bc06501

Browse files
committed
AC_Fence: fixed pre-arm check for polygon fences
for polygon fences we need to check if the vehicle has a position and is inside the polygon
1 parent 0a32cca commit bc06501

File tree

1 file changed

+11
-0
lines changed

1 file changed

+11
-0
lines changed

libraries/AC_Fence/AC_Fence.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -388,6 +388,17 @@ bool AC_Fence::pre_arm_check_polygon(char *failure_msg, const uint8_t failure_ms
388388
return false;
389389
}
390390

391+
Location loc;
392+
if (!AP::ahrs().get_location(loc)) {
393+
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
394+
return false;
395+
}
396+
397+
if (_poly_loader.breached(loc)) {
398+
hal.util->snprintf(failure_msg, failure_msg_len, "Vehicle outside fence");
399+
return false;
400+
}
401+
391402
return true;
392403
}
393404

0 commit comments

Comments
 (0)