From bd768a0c0cecc09f5988eeabcce08a25ac39e79b Mon Sep 17 00:00:00 2001 From: Mike McCauley Date: Tue, 18 Feb 2014 08:19:38 +1000 Subject: [PATCH] AP_HAL_FLYMAPLE RCOutput.cpp: enable_ch no longer resets servo FLYMAPLERCOutput::enable_ch incorrectly reset the servo to 0, which caused servo twitching once per second when RC_Channel_aux::enable_aux_servos enabled each channel. --- libraries/AP_HAL_FLYMAPLE/RCOutput.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp index fdcd1e6132..1f3d4ca51a 100644 --- a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp +++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp @@ -68,14 +68,13 @@ void FLYMAPLERCOutput::enable_ch(uint8_t ch) } pinMode(pin, PWM); _set_freq(ch, 50); // Default to 50 Hz - write(ch, 0); } void FLYMAPLERCOutput::disable_ch(uint8_t ch) { if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS) return; - // TODO + // Nothing really to do } void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)