mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF2: set terrainState to zero on height datum reset
This commit is contained in:
parent
4d2e25fe5b
commit
dedbfccb5a
@ -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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user