mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: Activate the create flag.
This commit is contained in:
parent
0ab0658849
commit
c63a6a2738
|
@ -401,12 +401,13 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
|
|||
// check if we need to create array
|
||||
if (!_boundary_create_attempted) {
|
||||
_boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f));
|
||||
_boundary_create_attempted = true;
|
||||
}
|
||||
|
||||
// exit if we could not allocate RAM for the boundary
|
||||
if (_boundary == nullptr) {
|
||||
return false;
|
||||
// exit if we could not allocate RAM for the boundary
|
||||
if (_boundary == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
_boundary_create_attempted = true;
|
||||
}
|
||||
|
||||
// get current location from EKF
|
||||
|
|
Loading…
Reference in New Issue