AP_NavEKF: Fix bug preventing opt flow scale factor estimation

Also removes un-used variable declarations
This commit is contained in:
priseborough 2014-11-12 20:30:16 +11:00 committed by Andrew Tridgell
parent a78920761c
commit 8fb1d9cf8d
2 changed files with 1 additions and 3 deletions

View File

@ -2588,7 +2588,7 @@ void NavEKF::RunAuxiliaryEKF()
inhibitGndState = false;
}
// Don't update focal length offset if there is no range finder or not using GPS, or we are not flying fast enough to generate a useful LOS rate
if (!fuseRngData || _fusionModeGPS == 3 || losRateSq < 0.1f || gpsGndSpd < 5.0f) {
if (!fuseRngData || _fusionModeGPS == 3 || losRateSq < 0.01f) {
fScaleInhibit = true;
} else {
fScaleInhibit = false;

View File

@ -502,8 +502,6 @@ private:
Vector3f velDotNEDfilt; // low pass filtered velDotNED
uint32_t lastAirspeedUpdate; // last time airspeed was updated
uint32_t imuSampleTime_ms; // time that the last IMU value was taken
ftype gpsCourse; // GPS ground course angle(rad)
ftype gpsGndSpd; // GPS ground speed (m/s)
bool newDataGps; // true when new GPS data has arrived
bool newDataMag; // true when new magnetometer data has arrived
bool newDataTas; // true when new airspeed data has arrived