Browse Source

AP_NavEKF2: set terrainState to zero on height datum reset

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
f5fd38aef2
  1. 5
      libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp

5
libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp

@ -230,8 +230,9 @@ bool NavEKF2_core::resetHeightDatum(void) @@ -230,8 +230,9 @@ bool NavEKF2_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…
Cancel
Save