AP_HAL_SITL: implement new scripting heap APIs

This commit is contained in:
Andrew Tridgell 2024-11-17 15:56:45 +11:00
parent 70c19b264a
commit bfeed7cc32
2 changed files with 2 additions and 70 deletions

View File

@ -85,68 +85,6 @@ bool HALSITL::Util::get_system_id(char buf[50])
return get_system_id_unformatted((uint8_t *)buf, len); return get_system_id_unformatted((uint8_t *)buf, len);
} }
#if ENABLE_HEAP
void *HALSITL::Util::allocate_heap_memory(size_t size)
{
struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap));
if (new_heap != nullptr) {
new_heap->scripting_max_heap_size = size;
new_heap->current_heap_usage = 0;
}
return (void *)new_heap;
}
void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t old_size, size_t new_size)
{
if (heap_ptr == nullptr) {
return nullptr;
}
struct heap *heapp = (struct heap*)heap_ptr;
// extract appropriate headers
size_t old_size_header = 0;
heap_allocation_header *old_header = nullptr;
if (ptr != nullptr) {
old_header = ((heap_allocation_header *)ptr) - 1;
old_size_header = old_header->allocation_size;
#if !defined(HAL_BUILD_AP_PERIPH)
if (old_size_header != old_size && new_size != 0) {
INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result);
}
#endif
}
if ((heapp->current_heap_usage + new_size - old_size) > heapp->scripting_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_header;
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
#if !defined(HAL_BUILD_AP_PERIPH) #if !defined(HAL_BUILD_AP_PERIPH)
enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void) enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void)
{ {

View File

@ -21,8 +21,8 @@ public:
how much free memory do we have in bytes. how much free memory do we have in bytes.
*/ */
uint32_t available_memory(void) override { uint32_t available_memory(void) override {
// SITL is assumed to always have plenty of memory. Return 128k for now // SITL is assumed to always have plenty of memory. Return 512k for now
return 0x20000; return 512*1024;
} }
// get path to custom defaults file for AP_Param // get path to custom defaults file for AP_Param
@ -43,12 +43,6 @@ public:
bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override;
void dump_stack_trace(); void dump_stack_trace();
#if ENABLE_HEAP
// heap functions, note that a heap once alloc'd cannot be dealloc'd
void *allocate_heap_memory(size_t size) override;
void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override;
#endif // ENABLE_HEAP
#ifdef WITH_SITL_TONEALARM #ifdef WITH_SITL_TONEALARM
bool toneAlarm_init(uint8_t types) override { return _toneAlarm.init(); } bool toneAlarm_init(uint8_t types) override { return _toneAlarm.init(); }
void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override { void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override {