Copter: bypass compass healthy check when ext nav data is available for heading
This commit is contained in:
parent
fc9ff2b09a
commit
6d8a1bbe81
@ -456,12 +456,15 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
||||
}
|
||||
|
||||
#ifndef ALLOW_ARM_NO_COMPASS
|
||||
// if external source of heading is available, we can skip compass health check
|
||||
if (!ahrs.is_ext_nav_used_for_yaw()) {
|
||||
const Compass &_compass = AP::compass();
|
||||
// check compass health
|
||||
if (!_compass.healthy()) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "Compass not healthy");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
control_mode_t control_mode = copter.control_mode;
|
||||
|
Loading…
Reference in New Issue
Block a user