AP_NavEKF3: remove default clause in setAidingMode

All aiding modes should be covered in the switch statement; adding the
default clause squelches a potentially useful compiler warning
This commit is contained in:
Peter Barker 2018-10-03 09:42:55 +10:00 committed by Francisco Ferreira
parent 3774aa6619
commit b68a91d171

View File

@ -367,9 +367,6 @@ void NavEKF3_core::setAidingMode()
lastVelPassTime_ms = imuSampleTime_ms;
lastRngBcnPassTime_ms = imuSampleTime_ms;
break;
default:
break;
}
// Always reset the position and velocity when changing mode