From 9b9934ac061f32d0c91b6cdae068276ff65592c7 Mon Sep 17 00:00:00 2001 From: priseborough Date: Sat, 1 Nov 2014 19:53:46 +1100 Subject: [PATCH] AP_NavEKF : fix velocity timeout bug during optical flow operation --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 33b3c15e9f..23ffd651c9 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -3011,6 +3011,8 @@ void NavEKF::FuseOptFlow() // Check the innovation for consistency and don't fuse if out of bounds if (flowTestRatio[obsIndex] < 1.0f) { + // Reset the timer for velocity fusion timeout. This prevents a velocity timeout from being declared if we have to momentarily go into velocity hold mode. + velFailTime = imuSampleTime_ms; // correct the state vector for (uint8_t j = 0; j <= 21; j++) {