mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: set terrainState to zero on height datum reset
This commit is contained in:
parent
f5fd38aef2
commit
3f9e48951b
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue