Browse Source

AP_HAL_Linux: Fix bad check order on heap_realloc

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
1484a12f4b
  1. 10
      libraries/AP_HAL_Linux/Util.cpp

10
libraries/AP_HAL_Linux/Util.cpp

@ -257,17 +257,17 @@ void *Util::heap_realloc(void *h, void *ptr, size_t new_size) @@ -257,17 +257,17 @@ void *Util::heap_realloc(void *h, void *ptr, size_t new_size)
old_size = old_header->allocation_size;
}
if ((heapp->current_heap_usage + new_size - old_size) > heapp->max_heap_size) {
// fail the allocation as we don't have the memory. Note that we don't simulate fragmentation
return nullptr;
}
heapp->current_heap_usage -= old_size;
if (new_size == 0) {
free(old_header);
return nullptr;
}
if ((heapp->current_heap_usage + new_size - old_size) > heapp->max_heap_size) {
// fail the allocation as we don't have the memory. Note that we don't simulate fragmentation
return nullptr;
}
heap_allocation_header *new_header = (heap_allocation_header *)malloc(new_size + sizeof(heap_allocation_header));
if (new_header == nullptr) {
// total failure to allocate, this is very surprising in SITL

Loading…
Cancel
Save