mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: fixed EKF threshold for arming
when EKF failsafe is disabled by setting threshold to zero we need to disable this arming check
This commit is contained in:
parent
5b434e814a
commit
7d5c36113d
@ -382,7 +382,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||||||
Vector3f mag_variance;
|
Vector3f mag_variance;
|
||||||
Vector2f offset;
|
Vector2f offset;
|
||||||
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
|
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
|
||||||
if (mag_variance.length() >= copter.g.fs_ekf_thresh) {
|
if (copter.g.fs_ekf_thresh > 0 && mag_variance.length() >= copter.g.fs_ekf_thresh) {
|
||||||
check_failed(ARMING_CHECK_NONE, display_failure, "EKF compass variance");
|
check_failed(ARMING_CHECK_NONE, display_failure, "EKF compass variance");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user