AC_Fence: correct handling of more than 256 fence items

This commit is contained in:
Peter Barker 2024-11-20 12:21:00 +11:00 committed by Peter Barker
parent ef18e9bc84
commit 8b8bc026db
1 changed files with 6 additions and 6 deletions

View File

@ -306,7 +306,7 @@ bool AC_PolyFence_loader::formatted() const
uint16_t AC_PolyFence_loader::max_items() const
{
// this is 84 items on PixHawk
return MIN(255U, fence_storage.size() / sizeof(Vector2l));
return fence_storage.size() / sizeof(Vector2l);
}
bool AC_PolyFence_loader::format()
@ -650,7 +650,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
// FIXME: find some way of factoring out all of these allocation routines.
{ // allocate storage for inclusion polyfences:
const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION);
const auto count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION);
Debug("Fence: Allocating %u bytes for inc. fences",
(unsigned)(count * sizeof(InclusionBoundary)));
_loaded_inclusion_boundary = NEW_NOTHROW InclusionBoundary[count];
@ -662,7 +662,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
}
{ // allocate storage for exclusion polyfences:
const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION);
const auto count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION);
Debug("Fence: Allocating %u bytes for exc. fences",
(unsigned)(count * sizeof(ExclusionBoundary)));
_loaded_exclusion_boundary = NEW_NOTHROW ExclusionBoundary[count];
@ -674,7 +674,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
}
{ // allocate storage for circular inclusion fences:
uint8_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION);
uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION);
count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT)
Debug("Fence: Allocating %u bytes for circ. inc. fences",
(unsigned)(count * sizeof(InclusionCircle)));
@ -687,7 +687,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
}
{ // allocate storage for circular exclusion fences:
uint8_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION);
uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION);
count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT)
Debug("Fence: Allocating %u bytes for circ. exc. fences",
(unsigned)(count * sizeof(ExclusionCircle)));
@ -1060,7 +1060,7 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_
return false;
}
uint8_t total_vertex_count = 0;
uint16_t total_vertex_count = 0;
uint16_t offset = 4; // skipping magic
uint8_t vertex_count = 0;
for (uint16_t i=0; i<count; i++) {