AP_NavEKF: make position and velocity resets consistent with GPS usage

This commit is contained in:
priseborough 2014-12-22 08:23:50 +11:00 committed by Randy Mackay
parent 0dc2356175
commit bab1a69f1c
1 changed files with 2 additions and 2 deletions

View File

@ -453,7 +453,7 @@ bool NavEKF::healthy(void) const
// resets position states to last GPS measurement or to zero if in position hold mode
void NavEKF::ResetPosition(void)
{
if (posHoldMode) {
if (posHoldMode || gpsInhibitMode != 0) {
state.position.x = 0;
state.position.y = 0;
} else if (_ahrs->get_gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
@ -472,7 +472,7 @@ void NavEKF::ResetPosition(void)
// Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
void NavEKF::ResetVelocity(void)
{
if (posHoldMode) {
if (posHoldMode || gpsInhibitMode != 0) {
state.velocity.zero();
state.vel1.zero();
state.vel2.zero();