APM_RC_APM2: Remove OutputCh from ::Init()

* These calls were off by one anyway, by using the channel numbers
  as ints ant not CH_n macros, and that caused an ESC cal problem.
This commit is contained in:
Pat Hickey 2011-12-15 13:47:43 -08:00
parent ae1c6ebde3
commit 291aaffdd9
1 changed files with 0 additions and 10 deletions

View File

@ -87,8 +87,6 @@ void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg )
ICR1 = 40000; // 0.5us tick => 50hz freq
OCR1A = 0xFFFF; // Init OCR registers to nil output signal
OCR1B = 0xFFFF;
OutputCh(1, 1100);
OutputCh(2, 1100);
// --------------- TIMER4: OUT3, OUT4, and OUT5 ---------------------
pinMode(8,OUTPUT); // OUT3 (PH5/OC4C)
@ -105,10 +103,6 @@ void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg )
OCR4C = 0xFFFF;
ICR4 = 40000; // 0.5us tick => 50hz freq
OutputCh(3, 1100);
OutputCh(4, 1100);
OutputCh(5, 1100);
//--------------- TIMER3: OUT6, OUT7, and OUT8 ----------------------
pinMode(3,OUTPUT); // OUT6 (PE5/OC3C)
pinMode(2,OUTPUT); // OUT7 (PE4/OC3B)
@ -124,10 +118,6 @@ void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg )
OCR3C = 0xFFFF;
ICR3 = 40000; // 0.5us tick => 50hz freq
OutputCh(6, 1100);
OutputCh(7, 1100);
OutputCh(8, 1100);
//--------------- TIMER5: PPM INPUT ---------------------------------
// Init PPM input on Timer 5
pinMode(48, INPUT); // PPM Input (PL1/ICP5)