mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_NavEKF: Fix bug preventing opt flow scale factor estimation
Also removes un-used variable declarations
This commit is contained in:
parent
a78920761c
commit
8fb1d9cf8d
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user