AP_NavEKF3: set terrainState to zero on height datum reset

This commit is contained in:
Andrew Tridgell 2019-07-02 16:17:46 +10:00
parent f5fd38aef2
commit 3f9e48951b
1 changed files with 4 additions and 2 deletions

View File

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