mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL: added old_size to heap_realloc
This commit is contained in:
parent
e255bbbd40
commit
13cbccc016
@ -153,7 +153,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
|
||||||
virtual void *allocate_heap_memory(size_t size) = 0;
|
virtual void *allocate_heap_memory(size_t size) = 0;
|
||||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_size) = 0;
|
virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) = 0;
|
||||||
#if USE_LIBC_REALLOC
|
#if USE_LIBC_REALLOC
|
||||||
virtual void *std_realloc(void *ptr, size_t new_size) { return realloc(ptr, new_size); }
|
virtual void *std_realloc(void *ptr, size_t new_size) { return realloc(ptr, new_size); }
|
||||||
#else
|
#else
|
||||||
|
Loading…
Reference in New Issue
Block a user