AP_NavEKF: added position observations to static mode

This commit is contained in:
Paul Riseborough 2014-01-05 20:05:48 +11:00 committed by Andrew Tridgell
parent da2c341914
commit cdbc5a3f35

View File

@ -1091,7 +1091,7 @@ void NavEKF::FuseVelPosNED()
observation[5] = -hgtMea; observation[5] = -hgtMea;
// zero observations if in static mode (used for pre-arm and bench testing) // zero observations if in static mode (used for pre-arm and bench testing)
if (staticMode) { if (staticMode) {
for (uint8_t i=0; i<=2; i++) observation[i] = 0.0f; for (uint8_t i=0; i<=5; i++) observation[i] = 0.0f;
// cancel static mode (it needs to be set every frame if required) // cancel static mode (it needs to be set every frame if required)
staticMode = false; staticMode = false;
} }