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.
This commit is contained in:
Peter Barker 2018-10-03 09:39:05 +10:00 committed by Francisco Ferreira
parent 53e36931fb
commit 3774aa6619

View File

@ -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