mirror of https://github.com/ArduPilot/ardupilot
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:
parent
3bcceb9420
commit
95a5a25909
|
@ -10,7 +10,7 @@ extern const AP_HAL::HAL& hal;
|
||||||
* RESET FUNCTIONS *
|
* 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
|
// Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
|
||||||
void NavEKF2_core::ResetVelocity(void)
|
void NavEKF2_core::ResetVelocity(void)
|
||||||
{
|
{
|
||||||
|
@ -23,7 +23,7 @@ void NavEKF2_core::ResetVelocity(void)
|
||||||
zeroCols(P,3,4);
|
zeroCols(P,3,4);
|
||||||
|
|
||||||
if (PV_AidingMode != AID_ABSOLUTE) {
|
if (PV_AidingMode != AID_ABSOLUTE) {
|
||||||
stateStruct.velocity.zero();
|
stateStruct.velocity.xy().zero();
|
||||||
// set the variances using the measurement noise parameter
|
// set the variances using the measurement noise parameter
|
||||||
P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
|
P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
|
||||||
} else {
|
} else {
|
||||||
|
|
Loading…
Reference in New Issue