mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: allocate from MEM_FAST region
This commit is contained in:
parent
b1213a522d
commit
ea2a880d8a
|
@ -5,6 +5,7 @@
|
|||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <new>
|
||||
|
||||
/*
|
||||
parameter defaults for different types of vehicle. The
|
||||
|
@ -697,15 +698,18 @@ bool NavEKF3::InitialiseFilter(void)
|
|||
_enable.set(0);
|
||||
return false;
|
||||
}
|
||||
|
||||
// create the cores
|
||||
core = new NavEKF3_core[num_cores];
|
||||
if (core == nullptr) {
|
||||
|
||||
//try to allocate from CCM RAM, fallback to Normal RAM if not available or full
|
||||
core = (NavEKF3_core*)hal.util->malloc_type(sizeof(NavEKF3_core)*num_cores, AP_HAL::Util::MEM_FAST);
|
||||
if (core == nullptr) {
|
||||
_enable.set(0);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: allocation failed");
|
||||
return false;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < num_cores; i++) {
|
||||
//Call Constructors
|
||||
new (&core[i]) NavEKF3_core();
|
||||
}
|
||||
}
|
||||
|
||||
// Set up any cores that have been created
|
||||
|
|
Loading…
Reference in New Issue