5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-03 14:38:30 -04:00

Rover: integrate ahrs.pre_arm_check

This commit is contained in:
Randy Mackay 2020-08-11 14:04:30 +09:00 committed by Peter Barker
parent 60b4953751
commit 161d235c8b

View File

@ -42,12 +42,9 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
const AP_AHRS &ahrs = AP::ahrs();
// always check if inertial nav has started and is ready
if (!ahrs.prearm_healthy()) {
const char *reason = ahrs.prearm_failure_reason();
if (reason == nullptr) {
reason = "AHRS not healthy";
}
check_failed(display_failure, "%s", reason);
char failure_msg[50] = {};
if (!ahrs.pre_arm_check(failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "AHRS: %s", failure_msg);
return false;
}
@ -59,11 +56,8 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
// ensure position esetimate is ok
if (!rover.ekf_position_ok()) {
const char *reason = ahrs.prearm_failure_reason();
if (reason == nullptr) {
reason = "Need Position Estimate";
}
check_failed(display_failure, "%s", reason);
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");
return false;
}