ArduCopter: fix FALLTHROUGH

This commit is contained in:
Pierre Kancir 2018-03-20 15:52:42 +01:00 committed by Randy Mackay
parent e5a9ac84e7
commit 9c23aa5ec3

View File

@ -54,7 +54,7 @@ void Copter::motor_test_output()
case MOTOR_TEST_COMPASS_CAL:
compass.set_voltage(battery.voltage());
compass.per_motor_calibration_update();
// fall through
FALLTHROUGH;
case MOTOR_TEST_THROTTLE_PERCENT:
// sanity check motor_test_throttle value