mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_HAL_SITL: added old_size to heap_realloc
This commit is contained in:
parent
deb86be1da
commit
12c24df476
@ -89,7 +89,7 @@ void *HALSITL::Util::allocate_heap_memory(size_t size)
|
|||||||
return (void *)new_heap;
|
return (void *)new_heap;
|
||||||
}
|
}
|
||||||
|
|
||||||
void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t new_size)
|
void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t old_size, size_t new_size)
|
||||||
{
|
{
|
||||||
if (heap_ptr == nullptr) {
|
if (heap_ptr == nullptr) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -98,11 +98,16 @@ void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t new_size)
|
|||||||
struct heap *heapp = (struct heap*)heap_ptr;
|
struct heap *heapp = (struct heap*)heap_ptr;
|
||||||
|
|
||||||
// extract appropriate headers
|
// extract appropriate headers
|
||||||
size_t old_size = 0;
|
size_t old_size_header = 0;
|
||||||
heap_allocation_header *old_header = nullptr;
|
heap_allocation_header *old_header = nullptr;
|
||||||
if (ptr != nullptr) {
|
if (ptr != nullptr) {
|
||||||
old_header = ((heap_allocation_header *)ptr) - 1;
|
old_header = ((heap_allocation_header *)ptr) - 1;
|
||||||
old_size = old_header->allocation_size;
|
old_size_header = old_header->allocation_size;
|
||||||
|
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||||
|
if (old_size_header != old_size && new_size != 0) {
|
||||||
|
INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((heapp->current_heap_usage + new_size - old_size) > heapp->scripting_max_heap_size) {
|
if ((heapp->current_heap_usage + new_size - old_size) > heapp->scripting_max_heap_size) {
|
||||||
@ -110,7 +115,7 @@ void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t new_size)
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
heapp->current_heap_usage -= old_size;
|
heapp->current_heap_usage -= old_size_header;
|
||||||
if (new_size == 0) {
|
if (new_size == 0) {
|
||||||
free(old_header);
|
free(old_header);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -49,7 +49,7 @@ public:
|
|||||||
#ifdef ENABLE_HEAP
|
#ifdef ENABLE_HEAP
|
||||||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||||
void *allocate_heap_memory(size_t size) override;
|
void *allocate_heap_memory(size_t size) override;
|
||||||
void *heap_realloc(void *heap, void *ptr, size_t new_size) override;
|
void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override;
|
||||||
#endif // ENABLE_HEAP
|
#endif // ENABLE_HEAP
|
||||||
|
|
||||||
#ifdef WITH_SITL_TONEALARM
|
#ifdef WITH_SITL_TONEALARM
|
||||||
|
Loading…
Reference in New Issue
Block a user