mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF: Fix bug affecting in-flight GPS acquisition
This bug caused velocities to be reset to zero
This commit is contained in:
parent
b9b6938b1d
commit
1c244af3d8
@ -4014,6 +4014,7 @@ void NavEKF::readGpsData()
|
||||
if (vehicleArmed && _fusionModeGPS != 3) {
|
||||
constPosMode = false;
|
||||
PV_AidingMode = AID_ABSOLUTE;
|
||||
gpsNotAvailable = false;
|
||||
// Initialise EKF position and velocity states
|
||||
ResetPosition();
|
||||
ResetVelocity();
|
||||
|
Loading…
Reference in New Issue
Block a user