mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 16:33:58 -04:00
AP_MultiHeap: initialize only if heap allocation succeeded
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
df24d3a61d
commit
f7d5f0f8f1
@ -36,9 +36,9 @@ void *MultiHeap::heap_create(uint32_t size)
|
|||||||
{
|
{
|
||||||
struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap));
|
struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap));
|
||||||
if (new_heap != nullptr) {
|
if (new_heap != nullptr) {
|
||||||
|
new_heap->magic = HEAP_MAGIC;
|
||||||
new_heap->max_heap_size = size;
|
new_heap->max_heap_size = size;
|
||||||
}
|
}
|
||||||
new_heap->magic = HEAP_MAGIC;
|
|
||||||
return (void *)new_heap;
|
return (void *)new_heap;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user