mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: added old_size to heap_realloc
This commit is contained in:
parent
b45be75a98
commit
365de4b505
|
@ -118,7 +118,7 @@ void *Util::std_realloc(void *addr, size_t size)
|
|||
return new_mem;
|
||||
}
|
||||
|
||||
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;
|
||||
|
@ -134,7 +134,13 @@ void *Util::heap_realloc(void *heap, void *ptr, size_t new_size)
|
|||
}
|
||||
void *new_mem = chHeapAlloc((memory_heap_t *)heap, new_size);
|
||||
if (new_mem != nullptr) {
|
||||
memcpy(new_mem, ptr, chHeapGetSize(ptr) > new_size ? new_size : chHeapGetSize(ptr));
|
||||
const size_t old_size2 = chHeapGetSize(ptr);
|
||||
#ifdef HAL_DEBUG_BUILD
|
||||
if (new_size != 0 && old_size2 != old_size) {
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result);
|
||||
}
|
||||
#endif
|
||||
memcpy(new_mem, ptr, old_size2 > new_size ? new_size : old_size2);
|
||||
chHeapFree(ptr);
|
||||
}
|
||||
return new_mem;
|
||||
|
|
|
@ -46,7 +46,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