AC_Avoidance: cope with polyfence holding boundary points

This commit is contained in:
Peter Barker 2019-05-29 23:31:14 +10:00 committed by Randy Mackay
parent 74aed5aef8
commit 3a7f1b882e

View File

@ -399,7 +399,7 @@ void AC_Avoid::adjust_velocity_polygon_fence(float kP, float accel_cmss, Vector2
// get polygon boundary
uint16_t num_points;
const Vector2f* boundary = _fence.get_boundary_points(num_points);
const Vector2f* boundary = _fence.polyfence().get_boundary_points(num_points);
// adjust velocity using polygon
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, true, _fence.get_margin(), dt);