mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Arming: always run compass calibration checks
This commit is contained in:
parent
c290b1f3b5
commit
72fabb5cd3
@ -332,11 +332,23 @@ bool AP_Arming::ins_checks(bool report)
|
||||
|
||||
bool AP_Arming::compass_checks(bool report)
|
||||
{
|
||||
Compass &_compass = AP::compass();
|
||||
|
||||
// check if compass is calibrating
|
||||
if (_compass.is_calibrating()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, 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");
|
||||
return false;
|
||||
}
|
||||
|
||||
if ((checks_to_perform) & ARMING_CHECK_ALL ||
|
||||
(checks_to_perform) & ARMING_CHECK_COMPASS) {
|
||||
|
||||
Compass &_compass = AP::compass();
|
||||
|
||||
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
|
||||
// incorrectly skip the remaining checks, pass the primary instance directly
|
||||
if (!_compass.use_for_yaw(_compass.get_primary())) {
|
||||
@ -354,18 +366,6 @@ bool AP_Arming::compass_checks(bool report)
|
||||
return false;
|
||||
}
|
||||
|
||||
//check if compass is calibrating
|
||||
if (_compass.is_calibrating()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, 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");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for unreasonable compass offsets
|
||||
const Vector3f offsets = _compass.get_offsets();
|
||||
if (offsets.length() > _compass.get_offsets_max()) {
|
||||
|
Loading…
Reference in New Issue
Block a user