mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Beacon: fix get_boundary_points num_points
Thanks @OXINARF for finding this!
This commit is contained in:
parent
b6816285e5
commit
a199604348
@ -365,7 +365,7 @@ const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
num_points = boundary_num_points + 1;
|
||||
num_points = boundary_num_points;
|
||||
return boundary;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user