mirror of https://github.com/ArduPilot/ardupilot
Copter: integrate ahrs::get_variances change
offset is no longer returned
This commit is contained in:
parent
6a72805f07
commit
248d80eb37
|
@ -556,8 +556,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
|
|||
// check EKF compass variance is below failsafe threshold
|
||||
float vel_variance, pos_variance, hgt_variance, tas_variance;
|
||||
Vector3f mag_variance;
|
||||
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);
|
||||
if (copter.g.fs_ekf_thresh > 0 && mag_variance.length() >= copter.g.fs_ekf_thresh) {
|
||||
check_failed(display_failure, "EKF compass variance");
|
||||
return false;
|
||||
|
|
|
@ -108,8 +108,7 @@ bool Copter::ekf_over_threshold()
|
|||
// use EKF to get variance
|
||||
float position_variance, vel_variance, height_variance, tas_variance;
|
||||
Vector3f mag_variance;
|
||||
Vector2f offset;
|
||||
ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance, offset);
|
||||
ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance);
|
||||
|
||||
const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);
|
||||
|
||||
|
@ -237,8 +236,7 @@ void Copter::check_vibration()
|
|||
// check if vertical velocity variance is at least 1 (NK4.SV >= 1.0)
|
||||
float position_variance, vel_variance, height_variance, tas_variance;
|
||||
Vector3f mag_variance;
|
||||
Vector2f offset;
|
||||
if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance, offset)) {
|
||||
if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance)) {
|
||||
checks_succeeded = false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue