From 056a2de260847c4feb63e490e26b9bcf7dbd4809 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Aug 2020 12:05:12 +0900 Subject: [PATCH] AP_NavEKF3: wheelOdmDataNew member made local this variable is never used outside the writeWheelOdom method --- libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp | 1 + libraries/AP_NavEKF3/AP_NavEKF3_core.h | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 0580adedba..b27aea9b4f 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -162,6 +162,7 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam return; } + wheel_odm_elements wheelOdmDataNew = {}; wheelOdmDataNew.hub_offset = &posOffset; wheelOdmDataNew.delAng = delAng; wheelOdmDataNew.radius = radius; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 12c740f475..ed7f12d345 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -1262,7 +1262,6 @@ private: // wheel sensor fusion uint32_t wheelOdmMeasTime_ms; // time wheel odometry measurements were accepted for input to the data buffer (msec) obs_ring_buffer_t storedWheelOdm; // body velocity data buffer - wheel_odm_elements wheelOdmDataNew; // Body frame odometry data at the current time horizon wheel_odm_elements wheelOdmDataDelayed; // Body frame odometry data at the fusion time horizon // yaw sensor fusion