Browse Source

ArduPlane: Fix spiralling loiters when no fence return point can be found

zr-v5.1
James O'Shannessy 4 years ago committed by Peter Barker
parent
commit
5253b8a3ee
  1. 8
      ArduPlane/fence.cpp

8
ArduPlane/fence.cpp

@ -92,9 +92,11 @@ void Plane::fence_check() @@ -92,9 +92,11 @@ void Plane::fence_check()
guided_WP_loc.lat = return_point[0];
guided_WP_loc.lng = return_point[1];
} else {
// should. not. happen.
guided_WP_loc.lat = current_loc.lat;
guided_WP_loc.lng = current_loc.lng;
// When no fence return point is found (ie. no inclusion fence uploaded, but exclusion is)
// we fail to obtain a valid fence return point. In this case, home is considered a safe
// return point.
guided_WP_loc.lat = home.lat;
guided_WP_loc.lng = home.lng;
}
}

Loading…
Cancel
Save