mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: clear breach of disabled fence
skip breach checks if no fences correct initialisation of _num_fences in the case of no fences in eeprom
This commit is contained in:
parent
3fabec4158
commit
a4c7819117
|
@ -635,6 +635,7 @@ bool AC_Fence::check_fence_polygon()
|
|||
{
|
||||
if (!(get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
|
||||
// not enabled; no breach
|
||||
clear_breach(AC_FENCE_TYPE_POLYGON);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -227,7 +227,7 @@ bool AC_PolyFence_loader::breached() const
|
|||
// returns true if location is outside the boundary
|
||||
bool AC_PolyFence_loader::breached(const Location& loc) const
|
||||
{
|
||||
if (!loaded()) {
|
||||
if (!loaded() || total_fence_count() == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -493,13 +493,15 @@ bool AC_PolyFence_loader::index_eeprom()
|
|||
if (!count_eeprom_fences()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
void_index();
|
||||
|
||||
if (_eeprom_fence_count == 0) {
|
||||
_num_fences = 0;
|
||||
_load_attempted = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
void_index();
|
||||
|
||||
Debug("Fence: Allocating %u bytes for index",
|
||||
(unsigned)(_eeprom_fence_count*sizeof(FenceIndex)));
|
||||
_index = NEW_NOTHROW FenceIndex[_eeprom_fence_count];
|
||||
|
|
Loading…
Reference in New Issue