mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: correct get_boundary_points to account for closing point
Also rename from get_polygon_points
This commit is contained in:
parent
36fe9a18a0
commit
2822c635ec
|
@ -460,13 +460,22 @@ void AC_Fence::manual_recovery_start()
|
|||
}
|
||||
|
||||
/// returns pointer to array of polygon points and num_points is filled in with the total number
|
||||
Vector2f* AC_Fence::get_polygon_points(uint16_t& num_points) const
|
||||
Vector2f* AC_Fence::get_boundary_points(uint16_t& num_points) const
|
||||
{
|
||||
// return array minus the first point which holds the return location
|
||||
num_points = (_boundary_num_points <= 1) ? 0 : _boundary_num_points - 1;
|
||||
if ((_boundary == nullptr) || (num_points == 0)) {
|
||||
if (_boundary == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!_boundary_valid) {
|
||||
return nullptr;
|
||||
}
|
||||
// minus one for return point, minus one for closing point
|
||||
// (_boundary_valid is not true unless we have a closing point AND
|
||||
// we have a minumum number of points)
|
||||
if (_boundary_num_points < 2) {
|
||||
return nullptr;
|
||||
}
|
||||
num_points = _boundary_num_points - 2;
|
||||
return &_boundary[1];
|
||||
}
|
||||
|
||||
|
|
|
@ -100,7 +100,7 @@ public:
|
|||
///
|
||||
|
||||
/// returns pointer to array of polygon points and num_points is filled in with the total number
|
||||
Vector2f* get_polygon_points(uint16_t& num_points) const;
|
||||
Vector2f* get_boundary_points(uint16_t& num_points) const;
|
||||
|
||||
/// returns true if we've breached the polygon boundary. simple passthrough to underlying _poly_loader object
|
||||
bool boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const;
|
||||
|
|
Loading…
Reference in New Issue