AP_DAL: use enum class for DAL MemoryType

This commit is contained in:
Peter Barker 2024-08-31 08:05:41 +10:00 committed by Peter Barker
parent 8d672ca7f8
commit e3e350427e
2 changed files with 10 additions and 5 deletions

View File

@ -272,10 +272,14 @@ int AP_DAL::snprintf(char* str, size_t size, const char *format, ...) const
return res;
}
void *AP_DAL::malloc_type(size_t size, Memory_Type mem_type) const
void *AP_DAL::malloc_type(size_t size, MemoryType mem_type) const
{
return hal.util->malloc_type(size, AP_HAL::Util::Memory_Type(mem_type));
}
void AP_DAL::free_type(void *ptr, size_t size, MemoryType mem_type) const
{
return hal.util->free_type(ptr, size, AP_HAL::Util::Memory_Type(mem_type));
}
// map core number for replay
uint8_t AP_DAL::logging_core(uint8_t c) const

View File

@ -121,11 +121,12 @@ public:
int snprintf(char* str, size_t size, const char *format, ...) const;
// copied in AP_HAL/Util.h
enum Memory_Type {
MEM_DMA_SAFE,
MEM_FAST
enum class MemoryType : uint8_t {
DMA_SAFE = 0,
FAST = 1,
};
void *malloc_type(size_t size, enum Memory_Type mem_type) const;
void *malloc_type(size_t size, MemoryType mem_type) const;
void free_type(void *ptr, size_t size, MemoryType memtype) const;
AP_DAL_InertialSensor &ins() { return _ins; }
AP_DAL_Baro &baro() { return _baro; }