mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF3: handle core setup failure
ensure num_cores is left as zero so that calls such as Log_Write don't de-reference nullptr
This commit is contained in:
parent
5a5c9d10a9
commit
52cb59e61d
@ -803,6 +803,7 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
if (AP::dal().available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) {
|
if (AP::dal().available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 not enough memory");
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 not enough memory");
|
||||||
_enable.set(0);
|
_enable.set(0);
|
||||||
|
num_cores = 0;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -810,6 +811,7 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
core = (NavEKF3_core*)AP::dal().malloc_type(sizeof(NavEKF3_core)*num_cores, AP::dal().MEM_FAST);
|
core = (NavEKF3_core*)AP::dal().malloc_type(sizeof(NavEKF3_core)*num_cores, AP::dal().MEM_FAST);
|
||||||
if (core == nullptr) {
|
if (core == nullptr) {
|
||||||
_enable.set(0);
|
_enable.set(0);
|
||||||
|
num_cores = 0;
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 allocation failed");
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 allocation failed");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user