mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: implement new scripting heap APIs
This commit is contained in:
parent
c999340786
commit
de49c9b1bc
|
@ -93,35 +93,10 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
|
|||
|
||||
#if ENABLE_HEAP
|
||||
|
||||
void *Util::allocate_heap_memory(size_t size)
|
||||
{
|
||||
void *buf = calloc(1, size);
|
||||
if (buf == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
multi_heap_handle_t *heap = (multi_heap_handle_t *)calloc(1, sizeof(multi_heap_handle_t));
|
||||
if (heap != nullptr) {
|
||||
auto hp = multi_heap_register(buf, size);
|
||||
memcpy(heap, &hp, sizeof(multi_heap_handle_t));
|
||||
}
|
||||
|
||||
return heap;
|
||||
}
|
||||
|
||||
void *Util::heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size)
|
||||
{
|
||||
if (heap == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return multi_heap_realloc(*(multi_heap_handle_t *)heap, ptr, new_size);
|
||||
}
|
||||
|
||||
/*
|
||||
realloc implementation thanks to wolfssl, used by AP_Scripting
|
||||
*/
|
||||
void *Util::std_realloc(void *addr, size_t size)
|
||||
void *Util::std_realloc(void *addr, uint32_t size)
|
||||
{
|
||||
if (size == 0) {
|
||||
free(addr);
|
||||
|
|
|
@ -36,9 +36,7 @@ public:
|
|||
|
||||
#if ENABLE_HEAP
|
||||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||
virtual void *allocate_heap_memory(size_t size) override;
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override;
|
||||
virtual void *std_realloc(void *ptr, size_t new_size) override;
|
||||
virtual void *std_realloc(void *ptr, uint32_t new_size) override;
|
||||
#endif // ENABLE_HEAP
|
||||
|
||||
/*
|
||||
|
@ -85,10 +83,6 @@ private:
|
|||
FlashBootloader flash_bootloader() override;
|
||||
#endif
|
||||
|
||||
#if ENABLE_HEAP
|
||||
// static memory_heap_t scripting_heap;
|
||||
#endif // ENABLE_HEAP
|
||||
|
||||
// stm32F4 and F7 have 20 total RTC backup registers. We use the first one for boot type
|
||||
// flags, so 19 available for persistent data
|
||||
static_assert(sizeof(persistent_data) <= 19*4, "watchdog persistent data too large");
|
||||
|
|
Loading…
Reference in New Issue