mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: pre-arm check requires GPS if polygon fence enabled
This commit is contained in:
parent
69925d8b27
commit
8171645876
|
@ -121,7 +121,7 @@ bool AC_Fence::pre_arm_check() const
|
||||||
}
|
}
|
||||||
|
|
||||||
// if we have horizontal limits enabled, check inertial nav position is ok
|
// 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;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue