mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_NavEKF2: pre-arm return failure message for correct core
This commit is contained in:
parent
29d5d5a300
commit
0b8bc4798a
@ -878,7 +878,7 @@ bool NavEKF2::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
|
|||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < num_cores; i++) {
|
for (uint8_t i = 0; i < num_cores; i++) {
|
||||||
if (!core[i].healthy()) {
|
if (!core[i].healthy()) {
|
||||||
const char *failure = core[primary].prearm_failure_reason();
|
const char *failure = core[i].prearm_failure_reason();
|
||||||
if (failure != nullptr) {
|
if (failure != nullptr) {
|
||||||
AP::dal().snprintf(failure_msg, failure_msg_len, failure);
|
AP::dal().snprintf(failure_msg, failure_msg_len, failure);
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user