AC_Fence: correct fence pre-arm position check

This commit is contained in:
Peter Barker 2019-03-06 14:04:58 +11:00 committed by Randy Mackay
parent 26fd334882
commit c04d2145a1
1 changed files with 1 additions and 1 deletions

View File

@ -166,7 +166,7 @@ bool AC_Fence::pre_arm_check(const char* &fail_msg) const
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
Vector2f position;
if (AP::ahrs().get_relative_position_NE_home(position)) {
if (!AP::ahrs().get_relative_position_NE_home(position)) {
fail_msg = "fence requires position";
return false;
}