mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_HAL_ESP32: added old_size to heap_realloc
This commit is contained in:
parent
365de4b505
commit
e255bbbd40
@ -107,7 +107,7 @@ void *Util::allocate_heap_memory(size_t size)
|
||||
return heap;
|
||||
}
|
||||
|
||||
void *Util::heap_realloc(void *heap, void *ptr, size_t new_size)
|
||||
void *Util::heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size)
|
||||
{
|
||||
if (heap == nullptr) {
|
||||
return nullptr;
|
||||
|
@ -41,7 +41,7 @@ public:
|
||||
#ifdef ENABLE_HEAP
|
||||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||
virtual void *allocate_heap_memory(size_t size) override;
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_size) override;
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override;
|
||||
virtual void *std_realloc(void *ptr, size_t new_size) override;
|
||||
#endif // ENABLE_HEAP
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user