mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_HAL: implement standard realloc method
This commit is contained in:
parent
2ce899c54f
commit
faeb9c063f
@ -151,8 +151,10 @@ public:
|
|||||||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||||
virtual void *allocate_heap_memory(size_t size) = 0;
|
virtual void *allocate_heap_memory(size_t size) = 0;
|
||||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_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
|
#endif // ENABLE_HEAP
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
how much free memory do we have in bytes. If unknown return 4096
|
how much free memory do we have in bytes. If unknown return 4096
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user