From fb1962b111ff315a2422403f8876ea6ebd0c9f84 Mon Sep 17 00:00:00 2001 From: priseborough Date: Fri, 9 Jan 2015 21:08:44 +1100 Subject: [PATCH] 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. --- libraries/AP_NavEKF/AP_NavEKF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 33bd18fcb0..09edea49c9 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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;