From 6bf2057712ac78ad8c44435fdb0e0f9e5bf117f5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Aug 2020 12:17:50 +0900 Subject: [PATCH] AP_NavEKF3: minor formatting fixes --- libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp | 1 - libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp index 51676dc173..e33cb54e64 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp @@ -446,7 +446,6 @@ bool NavEKF3_core::readyToUseOptFlow(void) const // return true if the filter is ready to start using body frame odometry measurements bool NavEKF3_core::readyToUseBodyOdm(void) const { - // Check for fresh visual odometry data that meets the accuracy required for alignment bool visoDataGood = (imuSampleTime_ms - bodyOdmMeasTime_ms < 200) && (bodyOdmDataNew.velErr < 1.0f); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index c6fc55e982..7e380765db 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -173,7 +173,6 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam wheelOdmDataNew.time_ms = timeStamp_ms - (uint32_t)(500.0f * delTime); storedWheelOdm.push(wheelOdmDataNew); - } // write the raw optical flow measurements