AP_NavEKF2: fixed velocity reset on AID_NONE

The ResetVelocity() function is only supposed to reset XY states, not
Z state. Resetting the Z state for velocity results in a large
velocity glitch if a vehicle is descending or ascending when aiding
switches to AID_NONE

this fixes #19386
This commit is contained in:
Andrew Tridgell 2023-06-23 14:45:36 +10:00 committed by Randy Mackay
parent fba9098f8f
commit 6db228900b
1 changed files with 2 additions and 2 deletions

View File

@ -10,7 +10,7 @@ extern const AP_HAL::HAL& hal;
* RESET FUNCTIONS *
********************************************************/
// Reset velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
// Reset XY velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
// Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
void NavEKF2_core::ResetVelocity(void)
{
@ -23,7 +23,7 @@ void NavEKF2_core::ResetVelocity(void)
zeroCols(P,3,4);
if (PV_AidingMode != AID_ABSOLUTE) {
stateStruct.velocity.zero();
stateStruct.velocity.xy().zero();
// set the variances using the measurement noise parameter
P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
} else {