mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: Access EKF variance checks through AHRS object
Supports flight using EKF2
This commit is contained in:
parent
0722ebe8a0
commit
7c6b31b585
@ -107,7 +107,7 @@ bool Copter::ekf_over_threshold()
|
||||
Vector2f offset;
|
||||
float compass_variance;
|
||||
float vel_variance;
|
||||
ahrs.get_NavEKF().getVariances(vel_variance, posVar, hgtVar, magVar, tasVar, offset);
|
||||
ahrs.get_variances(vel_variance, posVar, hgtVar, magVar, tasVar, offset);
|
||||
compass_variance = magVar.length();
|
||||
|
||||
// return true if compass and velocity variance over the threshold
|
||||
|
@ -644,7 +644,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
||||
float vel_variance, pos_variance, hgt_variance, tas_variance;
|
||||
Vector3f mag_variance;
|
||||
Vector2f offset;
|
||||
ahrs.get_NavEKF().getVariances(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() >= g.fs_ekf_thresh) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: EKF compass variance"));
|
||||
|
Loading…
Reference in New Issue
Block a user