From c90d3ff59e1008cd64ac7fbe2914980e98d39b5c Mon Sep 17 00:00:00 2001 From: Mike McCauley Date: Tue, 4 Mar 2014 10:36:02 +1000 Subject: [PATCH] Flymaple: RCOUtput disable_ch() now supports disabling outputs --- libraries/AP_HAL_FLYMAPLE/RCOutput.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp index 1f3d4ca51a..f6b1aafaa3 100644 --- a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp +++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp @@ -27,6 +27,8 @@ using namespace AP_HAL_FLYMAPLE_NS; +extern const AP_HAL::HAL& hal; + #define MAX_OVERFLOW ((1 << 16) - 1) void FLYMAPLERCOutput::init(void* machtnichts) {} @@ -74,7 +76,15 @@ void FLYMAPLERCOutput::disable_ch(uint8_t ch) { if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS) return; - // Nothing really to do + uint8_t pin = _channel_to_flymaple_pin(ch); + timer_dev *tdev = PIN_MAP[pin].timer_device; + + if (tdev == NULL) { + // don't reset any fields or ASSERT(0), to keep driving any + // previously attach()ed servo. + return; + } + pinMode(pin, INPUT); } void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)