AP_NavEKF: Let reported position whilst disarmed show inertial errors

Showing the positon states (which are nominally zero) in addition to the last known offset can provide useful log information.
This commit is contained in:
priseborough 2015-01-09 21:08:44 +11:00 committed by Randy Mackay
parent d26121036f
commit fb1962b111
1 changed files with 2 additions and 2 deletions

View File

@ -3528,8 +3528,8 @@ void NavEKF::getVelNED(Vector3f &vel) const
bool NavEKF::getPosNED(Vector3f &pos) const
{
if (constPosMode) {
pos.x = lastKnownPositionNE.x;
pos.y = lastKnownPositionNE.y;
pos.x = state.position.x + lastKnownPositionNE.x;
pos.y = state.position.y + lastKnownPositionNE.y;
} else {
pos.x = state.position.x;
pos.y = state.position.y;