mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Revert "AC_Fence: Activate the create flag."
This reverts commit c63a6a2738
.
This commit is contained in:
parent
be9ac273ce
commit
b48ea53f60
@ -401,15 +401,14 @@ 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));
|
||||
|
||||
// exit if we could not allocate RAM for the boundary
|
||||
if (_boundary == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
_boundary_create_attempted = true;
|
||||
}
|
||||
|
||||
// exit if we could not allocate RAM for the boundary
|
||||
if (_boundary == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// get current location from EKF
|
||||
Location temp_loc;
|
||||
if (!_inav.get_location(temp_loc)) {
|
||||
|
Loading…
Reference in New Issue
Block a user