mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF3: use enum class for DAL MemoryType
This commit is contained in:
parent
7d1e1ef924
commit
6cfecaa86d
@ -816,7 +816,7 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
//try to allocate from CCM RAM, fallback to Normal RAM if not available or full
|
//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) {
|
if (core == nullptr) {
|
||||||
_enable.set(0);
|
_enable.set(0);
|
||||||
num_cores = 0;
|
num_cores = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user