AC_Fence: Activate the create flag.

This commit is contained in:
murata 2016-12-09 23:21:10 +09:00 committed by Francisco Ferreira
parent 0ab0658849
commit c63a6a2738
1 changed files with 6 additions and 5 deletions

View File

@ -401,14 +401,15 @@ 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;
}
_boundary_create_attempted = true;
}
// get current location from EKF
Location temp_loc;
if (!_inav.get_location(temp_loc)) {