diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 5a6e43d8c6..85cf01a817 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -57,14 +57,6 @@ static void init_rc_out() APM_RC.Init( &isr_registry ); // APM Radio initialization init_motors_out(); - // fix for crazy output - OCR1B = 0xFFFF; // PB6, OUT3 - OCR1C = 0xFFFF; // PB7, OUT4 - OCR5B = 0xFFFF; // PL4, OUT1 - OCR5C = 0xFFFF; // PL5, OUT2 - OCR4B = 0xFFFF; // PH4, OUT6 - OCR4C = 0xFFFF; // PH5, OUT5 - // this is the camera pitch5 and roll6 APM_RC.OutputCh(CH_5, 1500); APM_RC.OutputCh(CH_6, 1500); diff --git a/libraries/APM_RC/APM_RC_APM1.cpp b/libraries/APM_RC/APM_RC_APM1.cpp index 5b82afc3bb..3f17efd7b2 100644 --- a/libraries/APM_RC/APM_RC_APM1.cpp +++ b/libraries/APM_RC/APM_RC_APM1.cpp @@ -86,9 +86,9 @@ void APM_RC_APM1::Init( Arduino_Mega_ISR_Registry * isr_reg ) //Remember the registers not declared here remains zero by default... TCCR1A =((1< 50hz freq - + OCR1A = 0xFFFF; // Init OCR registers to nil output signal + OCR1B = 0xFFFF; OutputCh(1, 1100); OutputCh(2, 1100); @@ -99,6 +100,9 @@ void APM_RC_Purple::Init( Arduino_Mega_ISR_Registry * isr_reg ) // CS41: prescale by 8 => 0.5us tick TCCR4A =((1< 50hz freq OutputCh(3, 1100); @@ -115,6 +119,9 @@ void APM_RC_Purple::Init( Arduino_Mega_ISR_Registry * isr_reg ) // CS31: prescale by 8 => 0.5us tick TCCR3A =((1< 50hz freq OutputCh(6, 1100);