From fb76aa9ca92b4713851f1d2e0da5644761139f51 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Mon, 6 Feb 2012 22:11:01 -0800 Subject: [PATCH] APM_RC_APM2: Add support for CH_10 and CH_11 * CH_10 is on APM2 pin A10 (based on A1..A8 convention) * CH_11 is on APM2 pin A11 * Only the code in enable_out, disable_out, and OutputCh needed to change. * CH_10 and CH_11 always have an output period of 20ms (50Hz). --- libraries/APM_RC/APM_RC_APM2.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/APM_RC/APM_RC_APM2.cpp b/libraries/APM_RC/APM_RC_APM2.cpp index 2253294990..d0a480a0e9 100644 --- a/libraries/APM_RC/APM_RC_APM2.cpp +++ b/libraries/APM_RC/APM_RC_APM2.cpp @@ -122,6 +122,8 @@ void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg ) //--------------- TIMER5: PPM INPUT --------------------------------- // Init PPM input on Timer 5 pinMode(48, INPUT); // PPM Input (PL1/ICP5) + pinMode(45, OUTPUT); // OUT10 (PL4/OC5B) + pinMode(44, OUTPUT); // OUT11 (PL5/OC5C) // WGM: 1 1 1 1. Fast PWM, TOP is OCR5A // COM all disabled. @@ -153,6 +155,8 @@ void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm) case 5: OCR3C=pwm; break; // out6 case 6: OCR3B=pwm; break; // out7 case 7: OCR3A=pwm; break; // out8 + case 9: OCR5B=pwm; break; // out10 + case 10: OCR5C=pwm; break; // out11 } } @@ -167,6 +171,8 @@ void APM_RC_APM2::enable_out(uint8_t ch) case 5: TCCR3A |= (1<