Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tidy AP_DAL memory allocation and freeing #27962

Merged
merged 3 commits into from
Sep 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion libraries/AP_DAL/AP_DAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
9 changes: 5 additions & 4 deletions libraries/AP_DAL/AP_DAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,11 +121,12 @@ class AP_DAL {
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; }
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_NavEKF2/AP_NavEKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -675,7 +675,7 @@ bool NavEKF2::InitialiseFilter(void)
}

// try to allocate from CCM RAM, fallback to Normal RAM if not available or full
core = (NavEKF2_core*)AP::dal().malloc_type(sizeof(NavEKF2_core)*num_cores, AP_DAL::MEM_FAST);
core = (NavEKF2_core*)AP::dal().malloc_type(sizeof(NavEKF2_core)*num_cores, AP_DAL::MemoryType::FAST);
if (core == nullptr) {
initFailure = InitFailures::NO_MEM;
core_malloc_failed = true;
Expand All @@ -695,7 +695,7 @@ bool NavEKF2::InitialiseFilter(void)
if (_imuMask & (1U<<i)) {
if(!core[num_cores].setup_core(i, num_cores)) {
// if any core setup fails, free memory, zero the core pointer and abort
hal.util->free_type(core, sizeof(NavEKF2_core)*num_cores, AP_HAL::Util::MEM_FAST);
AP::dal().free_type(core, sizeof(NavEKF2_core)*num_cores, AP_DAL::MemoryType::FAST);
core = nullptr;
initFailure = InitFailures::NO_SETUP;
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "NavEKF2: core %d setup failed", num_cores);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -816,7 +816,7 @@ bool NavEKF3::InitialiseFilter(void)
}

//try to allocate from CCM RAM, fallback to Normal RAM if not available or full
core = (NavEKF3_core*)dal.malloc_type(sizeof(NavEKF3_core)*num_cores, dal.MEM_FAST);
core = (NavEKF3_core*)dal.malloc_type(sizeof(NavEKF3_core)*num_cores, AP_DAL::MemoryType::FAST);
if (core == nullptr) {
_enable.set(0);
num_cores = 0;
Expand Down
Loading