diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 3177ba126a..3c37d8fd7e 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -140,9 +140,7 @@ void RCOutput::init() // setup default output rate of 50Hz set_freq(0xFFFF ^ ((1U<pinMode(54, 1);