mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AC_Fence: Activate the create flag.
This commit is contained in:
parent
0ab0658849
commit
c63a6a2738
@ -401,14 +401,15 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
|
|||||||
// check if we need to create array
|
// check if we need to create array
|
||||||
if (!_boundary_create_attempted) {
|
if (!_boundary_create_attempted) {
|
||||||
_boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f));
|
_boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f));
|
||||||
_boundary_create_attempted = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
// exit if we could not allocate RAM for the boundary
|
// exit if we could not allocate RAM for the boundary
|
||||||
if (_boundary == nullptr) {
|
if (_boundary == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_boundary_create_attempted = true;
|
||||||
|
}
|
||||||
|
|
||||||
// get current location from EKF
|
// get current location from EKF
|
||||||
Location temp_loc;
|
Location temp_loc;
|
||||||
if (!_inav.get_location(temp_loc)) {
|
if (!_inav.get_location(temp_loc)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user