AP_HAL_ChibiOS: allocate_heap_memory use single malloc

This commit is contained in:
Iampete1 2022-05-17 01:35:39 +01:00 committed by Andrew Tridgell
parent 66cdfb015b
commit af58ca52c1
1 changed files with 3 additions and 8 deletions

View File

@ -86,16 +86,11 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
void *Util::allocate_heap_memory(size_t size) void *Util::allocate_heap_memory(size_t size)
{ {
void *buf = malloc(size); memory_heap_t *heap = (memory_heap_t *)malloc(size + sizeof(memory_heap_t));
if (buf == nullptr) { if (heap == nullptr) {
return nullptr; return nullptr;
} }
chHeapObjectInit(heap, heap + 1U, size);
memory_heap_t *heap = (memory_heap_t *)malloc(sizeof(memory_heap_t));
if (heap != nullptr) {
chHeapObjectInit(heap, buf, size);
}
return heap; return heap;
} }