mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: integrate ahrs::get_variances change
offset is no longer returned
This commit is contained in:
parent
248d80eb37
commit
0362895720
@ -110,8 +110,7 @@ bool Plane::ekf_over_threshold()
|
||||
// A value above 1.0 means the EKF has rejected that sensor data
|
||||
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)) {
|
||||
return false;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user