mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AC_Avoidance: fix BendyRuler when outside polygon fence
This commit is contained in:
parent
de5ace24fd
commit
cceab9c88f
@ -216,8 +216,11 @@ bool AP_OABendyRuler::calc_margin_from_polygon_fence(const Location &start, cons
|
||||
return false;
|
||||
}
|
||||
|
||||
// if outside the fence margin is the closest distance but with negative sign
|
||||
const float sign = Polygon_outside(start_NE, boundary, num_points) ? -1.0f : 1.0f;
|
||||
|
||||
// calculate min distance (in meters) from line to polygon
|
||||
margin = Polygon_closest_distance_line(boundary, num_points, start_NE, end_NE) * 0.01f;
|
||||
margin = sign * Polygon_closest_distance_line(boundary, num_points, start_NE, end_NE) * 0.01f;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user