mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
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:
parent
3774aa6619
commit
b68a91d171
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user