mirror of https://github.com/ArduPilot/ardupilot
Sub: integrate ahrs::get_variances change
offset is no longer returned
This commit is contained in:
parent
b83ade2b07
commit
4bf4872504
|
@ -110,10 +110,9 @@ void Sub::failsafe_ekf_check()
|
|||
|
||||
float posVar, hgtVar, tasVar;
|
||||
Vector3f magVar;
|
||||
Vector2f offset;
|
||||
float compass_variance;
|
||||
float vel_variance;
|
||||
ahrs.get_variances(vel_variance, posVar, hgtVar, magVar, tasVar, offset);
|
||||
ahrs.get_variances(vel_variance, posVar, hgtVar, magVar, tasVar);
|
||||
compass_variance = magVar.length();
|
||||
|
||||
if (compass_variance < g.fs_ekf_thresh && vel_variance < g.fs_ekf_thresh) {
|
||||
|
|
Loading…
Reference in New Issue