mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: implement standard realloc method
This commit is contained in:
parent
88de9572aa
commit
c615bd9874
|
@ -159,8 +159,10 @@ public:
|
|||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||
virtual void *allocate_heap_memory(size_t size) = 0;
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_size) = 0;
|
||||
virtual void *std_realloc(void *ptr, size_t new_size) { return realloc(ptr, new_size); }
|
||||
#endif // ENABLE_HEAP
|
||||
|
||||
|
||||
/**
|
||||
how much free memory do we have in bytes. If unknown return 4096
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue