AP_HAL_Linux: implement new scripting heap APIs

This commit is contained in:
Andrew Tridgell 2024-11-17 15:56:45 +11:00
parent de49c9b1bc
commit a124d66110
2 changed files with 0 additions and 77 deletions

View File

@ -241,65 +241,6 @@ int Util::get_hw_arm32()
return -ENOENT;
}
#if ENABLE_HEAP
void *Util::allocate_heap_memory(size_t size)
{
struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap));
if (new_heap != nullptr) {
new_heap->max_heap_size = size;
new_heap->current_heap_usage = 0;
}
return (void *)new_heap;
}
void *Util::heap_realloc(void *h, void *ptr, size_t old_size, size_t new_size)
{
if (h == nullptr) {
return nullptr;
}
struct heap *heapp = (struct heap*)h;
// extract appropriate headers. We use the old_size from the
// header not from the caller. We use SITL to catch cases they
// don't match (which would be a lua bug)
old_size = 0;
heap_allocation_header *old_header = nullptr;
if (ptr != nullptr) {
old_header = ((heap_allocation_header *)ptr) - 1;
old_size = old_header->allocation_size;
}
if ((heapp->current_heap_usage + new_size - old_size) > heapp->max_heap_size) {
// fail the allocation as we don't have the memory. Note that we don't simulate fragmentation
return nullptr;
}
heapp->current_heap_usage -= old_size;
if (new_size == 0) {
free(old_header);
return nullptr;
}
heap_allocation_header *new_header = (heap_allocation_header *)malloc(new_size + sizeof(heap_allocation_header));
if (new_header == nullptr) {
// total failure to allocate, this is very surprising in SITL
return nullptr;
}
heapp->current_heap_usage += new_size;
new_header->allocation_size = new_size;
void *new_mem = new_header + 1;
if (ptr == nullptr) {
return new_mem;
}
memcpy(new_mem, ptr, old_size > new_size ? new_size : old_size);
free(old_header);
return new_mem;
}
#endif // ENABLE_HEAP
/**
* This method will read random values with set size.
*/

View File

@ -71,12 +71,6 @@ public:
bool get_system_id(char buf[50]) override;
bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override;
#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 *h, void *ptr, size_t old_size, size_t new_size) override;
#endif // ENABLE_HEAP
/*
* Write a string as specified by @fmt to the file in @path. Note this
* should not be used on hot path since it will open, write and close the
@ -115,18 +109,6 @@ private:
const char *custom_storage_directory = nullptr;
const char *custom_defaults = HAL_PARAM_DEFAULTS_PATH;
static const char *_hw_names[UTIL_NUM_HARDWARES];
#if ENABLE_HEAP
struct heap_allocation_header {
size_t allocation_size; // size of allocated block, not including this header
};
struct heap {
size_t max_heap_size;
size_t current_heap_usage;
};
#endif // ENABLE_HEAP
};
}