AC_Fence: pre-arm check requires GPS if polygon fence enabled

This commit is contained in:
Randy Mackay 2017-03-24 11:04:25 +09:00
parent 69925d8b27
commit 8171645876
1 changed files with 1 additions and 1 deletions

View File

@ -121,7 +121,7 @@ bool AC_Fence::pre_arm_check() const
}
// if we have horizontal limits enabled, check inertial nav position is ok
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE)!=0 && !_inav.get_filter_status().flags.horiz_pos_abs && !_inav.get_filter_status().flags.pred_horiz_pos_abs) {
if ((_enabled_fences & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON))>0 && !_inav.get_filter_status().flags.horiz_pos_abs && !_inav.get_filter_status().flags.pred_horiz_pos_abs) {
return false;
}