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).
This commit is contained in:
Pat Hickey 2012-02-06 22:11:01 -08:00
parent 80ccbabe63
commit 83326a9d62
1 changed files with 8 additions and 0 deletions

View File

@ -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<<COM3C1); break; // CH_6 : OC3C
case 6: TCCR3A |= (1<<COM3B1); break; // CH_7 : OC3B
case 7: TCCR3A |= (1<<COM3A1); break; // CH_8 : OC3A
case 9: TCCR5A |= (1<<COM5B1); break; // CH_10 : OC5B
case 10: TCCR5A |= (1<<COM5C1); break; // CH_11 : OC5C
}
}
@ -181,6 +187,8 @@ void APM_RC_APM2::disable_out(uint8_t ch)
case 5: TCCR3A &= ~(1<<COM3C1); break; // CH_6 : OC3C
case 6: TCCR3A &= ~(1<<COM3B1); break; // CH_7 : OC3B
case 7: TCCR3A &= ~(1<<COM3A1); break; // CH_8 : OC3A
case 9: TCCR5A &= ~(1<<COM5B1); break; // CH_10 : OC5B
case 10: TCCR5A &= ~(1<<COM5C1); break; // CH_11 : OC5C
}
}