mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Arming: add ahrs attitude check
This commit is contained in:
parent
f1a023c872
commit
b805c40bf7
@ -325,6 +325,12 @@ bool AP_Arming::ins_checks(bool report)
|
||||
check_failed(ARMING_CHECK_INS, report, "Gyros inconsistent");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check AHRS attitudes are consistent
|
||||
if (!AP::ahrs().attitudes_consistent()) {
|
||||
check_failed(ARMING_CHECK_INS, report, "Attitudes inconsistent");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
@ -336,13 +342,13 @@ bool AP_Arming::compass_checks(bool report)
|
||||
|
||||
// check if compass is calibrating
|
||||
if (_compass.is_calibrating()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, report, "Compass calibration running");
|
||||
check_failed(ARMING_CHECK_NONE, report, "Compass calibration running");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check if compass has calibrated and requires reboot
|
||||
if (_compass.compass_cal_requires_reboot()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, report, "Compass calibrated requires reboot");
|
||||
check_failed(ARMING_CHECK_NONE, report, "Compass calibrated requires reboot");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user