Skip to content

Commit

Permalink
Copter: cope with AHRS backends with no variances
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Aug 11, 2024
1 parent 37849e7 commit 7a111d4
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -480,7 +480,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)

// check EKF's compass, position, height and velocity variances are below failsafe threshold
if (copter.g.fs_ekf_thresh > 0.0f) {
float vel_variance, pos_variance, hgt_variance, tas_variance;
float vel_variance=0, pos_variance=0, hgt_variance=0, tas_variance=0;
Vector3f mag_variance;
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);
if (mag_variance.length() >= copter.g.fs_ekf_thresh) {
Expand Down

0 comments on commit 7a111d4

Please sign in to comment.