AC_Fence: use NEW_NOTHROW for new(std::nothrow)

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:08 +10:00
parent 18e5da78d2
commit c95624a040

View File

@ -502,7 +502,7 @@ bool AC_PolyFence_loader::index_eeprom()
Debug("Fence: Allocating %u bytes for index", Debug("Fence: Allocating %u bytes for index",
(unsigned)(_eeprom_fence_count*sizeof(FenceIndex))); (unsigned)(_eeprom_fence_count*sizeof(FenceIndex)));
_index = new FenceIndex[_eeprom_fence_count]; _index = NEW_NOTHROW FenceIndex[_eeprom_fence_count];
if (_index == nullptr) { if (_index == nullptr) {
return false; return false;
} }
@ -636,8 +636,8 @@ bool AC_PolyFence_loader::load_from_eeprom()
const uint16_t count = sum_of_polygon_point_counts_and_returnpoint(); const uint16_t count = sum_of_polygon_point_counts_and_returnpoint();
Debug("Fence: Allocating %u bytes for points", Debug("Fence: Allocating %u bytes for points",
(unsigned)(count * sizeof(Vector2f))); (unsigned)(count * sizeof(Vector2f)));
_loaded_offsets_from_origin = new Vector2f[count]; _loaded_offsets_from_origin = NEW_NOTHROW Vector2f[count];
_loaded_points_lla = new Vector2l[count]; _loaded_points_lla = NEW_NOTHROW Vector2l[count];
if (_loaded_offsets_from_origin == nullptr || _loaded_points_lla == nullptr) { if (_loaded_offsets_from_origin == nullptr || _loaded_points_lla == nullptr) {
unload(); unload();
get_loaded_fence_semaphore().give(); get_loaded_fence_semaphore().give();
@ -651,7 +651,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION); const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION);
Debug("Fence: Allocating %u bytes for inc. fences", Debug("Fence: Allocating %u bytes for inc. fences",
(unsigned)(count * sizeof(InclusionBoundary))); (unsigned)(count * sizeof(InclusionBoundary)));
_loaded_inclusion_boundary = new InclusionBoundary[count]; _loaded_inclusion_boundary = NEW_NOTHROW InclusionBoundary[count];
if (_loaded_inclusion_boundary == nullptr) { if (_loaded_inclusion_boundary == nullptr) {
unload(); unload();
get_loaded_fence_semaphore().give(); get_loaded_fence_semaphore().give();
@ -663,7 +663,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION); const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION);
Debug("Fence: Allocating %u bytes for exc. fences", Debug("Fence: Allocating %u bytes for exc. fences",
(unsigned)(count * sizeof(ExclusionBoundary))); (unsigned)(count * sizeof(ExclusionBoundary)));
_loaded_exclusion_boundary = new ExclusionBoundary[count]; _loaded_exclusion_boundary = NEW_NOTHROW ExclusionBoundary[count];
if (_loaded_exclusion_boundary == nullptr) { if (_loaded_exclusion_boundary == nullptr) {
unload(); unload();
get_loaded_fence_semaphore().give(); get_loaded_fence_semaphore().give();
@ -676,7 +676,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT) count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT)
Debug("Fence: Allocating %u bytes for circ. inc. fences", Debug("Fence: Allocating %u bytes for circ. inc. fences",
(unsigned)(count * sizeof(InclusionCircle))); (unsigned)(count * sizeof(InclusionCircle)));
_loaded_circle_inclusion_boundary = new InclusionCircle[count]; _loaded_circle_inclusion_boundary = NEW_NOTHROW InclusionCircle[count];
if (_loaded_circle_inclusion_boundary == nullptr) { if (_loaded_circle_inclusion_boundary == nullptr) {
unload(); unload();
get_loaded_fence_semaphore().give(); get_loaded_fence_semaphore().give();
@ -689,7 +689,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT) count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT)
Debug("Fence: Allocating %u bytes for circ. exc. fences", Debug("Fence: Allocating %u bytes for circ. exc. fences",
(unsigned)(count * sizeof(ExclusionCircle))); (unsigned)(count * sizeof(ExclusionCircle)));
_loaded_circle_exclusion_boundary = new ExclusionCircle[count]; _loaded_circle_exclusion_boundary = NEW_NOTHROW ExclusionCircle[count];
if (_loaded_circle_exclusion_boundary == nullptr) { if (_loaded_circle_exclusion_boundary == nullptr) {
unload(); unload();
get_loaded_fence_semaphore().give(); get_loaded_fence_semaphore().give();