Browse Source

Revert "AC_Fence: Activate the create flag."

This reverts commit c63a6a2738.
mission-4.1.18
murata 8 years ago committed by Francisco Ferreira
parent
commit
b48ea53f60
  1. 11
      libraries/AC_Fence/AC_Fence.cpp

11
libraries/AC_Fence/AC_Fence.cpp

@ -401,15 +401,14 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload) @@ -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…
Cancel
Save