mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: allocate_heap_memory use single malloc
This commit is contained in:
parent
66cdfb015b
commit
af58ca52c1
|
@ -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 *buf = malloc(size);
|
||||
if (buf == nullptr) {
|
||||
memory_heap_t *heap = (memory_heap_t *)malloc(size + sizeof(memory_heap_t));
|
||||
if (heap == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
memory_heap_t *heap = (memory_heap_t *)malloc(sizeof(memory_heap_t));
|
||||
if (heap != nullptr) {
|
||||
chHeapObjectInit(heap, buf, size);
|
||||
}
|
||||
|
||||
chHeapObjectInit(heap, heap + 1U, size);
|
||||
return heap;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue