From 3774aa66197daf1db63e1c99ad52353c05496495 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Oct 2018 09:39:05 +1000 Subject: [PATCH] AP_NavEKF2: remove default clause in setAidingMode All values from the enumeration should be handled in this switch; adding a default will hide a compiler warning which may be useful. --- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index e1a68c6418..dfa0cde7c1 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -257,12 +257,9 @@ void NavEKF2_core::setAidingMode() rngBcnTimeout = true; gpsNotAvailable = true; } - } - break; - - default: break; } + } // check to see if we are starting or stopping aiding and set states and modes as required if (PV_AidingMode != PV_AidingModePrev) { @@ -332,9 +329,6 @@ void NavEKF2_core::setAidingMode() lastRngBcnPassTime_ms = imuSampleTime_ms; } break; - - default: - break; } // Always reset the position and velocity when changing mode