AP_NavEKF2: set terrainState to zero on height datum reset

This commit is contained in:
Andrew Tridgell 2019-07-02 16:17:46 +10:00 committed by Randy Mackay
parent 4d2e25fe5b
commit dedbfccb5a

View File

@ -230,8 +230,9 @@ bool NavEKF2_core::resetHeightDatum(void)
} }
} }
// adjust the terrain state // set the terrain state to zero (on ground). The adjustment for
terrainState += oldHgt; // frame height will get added in the later constraints
terrainState = 0;
return true; return true;
} }