From 17fc5499f845343c2fb4ae7a9141bee5680ff6c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 30 Jan 2022 00:07:20 +1100 Subject: [PATCH] AP_Mount: mark result of get_velocity as unused --- libraries/AP_Mount/SoloGimbalEKF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/SoloGimbalEKF.cpp b/libraries/AP_Mount/SoloGimbalEKF.cpp index d51bf374f1..37d0c1dada 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.cpp +++ b/libraries/AP_Mount/SoloGimbalEKF.cpp @@ -616,12 +616,12 @@ void SoloGimbalEKF::fuseVelocity() // Calculate the velocity measurement innovation using the SoloGimbalEKF estimate as the observation // if heading isn't aligned, use zero velocity (static assumption) if (YawAligned) { - Vector3f measVelNED = Vector3f(0,0,0); + Vector3f measVelNED; nav_filter_status main_ekf_status; if (_ahrs.get_filter_status(main_ekf_status)) { if (main_ekf_status.flags.horiz_vel) { - _ahrs.get_velocity_NED(measVelNED); + UNUSED_RESULT(_ahrs.get_velocity_NED(measVelNED)); } }