/* APM_RC.cpp - Radio Control Library for Ardupilot Mega. Arduino Code by Jordi Muņoz and Jose Julio. DIYDrones.com This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2.1 of the License, or (at your option) any later version. RC Input : PPM signal on IC4 pin RC Output : 11 Servo outputs (standard 20ms frame) Methods: Init() : Initialization of interrupts an Timers OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10 InputCh(ch) : Read a channel input value. ch=0..7 GetState() : Returns the state of the input. 1 => New radio frame to process Automatically resets when we call InputCh to read channels */ #include "APM_RC.h" #include #include "WProgram.h" #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) # error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target. #else // Variable definition for Input Capture interrupt //volatile uint16_t ICR4_old; //volatile uint8_t PPM_Counter=0; volatile uint16_t PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400}; volatile uint8_t radio_status=0; /**************************************************** Input Capture Interrupt ICP4 => PPM signal read ****************************************************/ ISR(TIMER4_CAPT_vect) { static uint16_t ICR4_old; static uint8_t PPM_Counter=0; uint16_t Pulse; uint16_t Pulse_Width; Pulse=ICR4; if (Pulse8000) { // SYNC pulse? PPM_Counter=0; } else { if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel? PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse. if (PPM_Counter >= NUM_CHANNELS) { radio_status = 1; } } } ICR4_old = Pulse; } // Constructors //////////////////////////////////////////////////////////////// APM_RC_Class::APM_RC_Class() { } // Public Methods ////////////////////////////////////////////////////////////// void APM_RC_Class::Init(void) { // Init PWM Timer 1 pinMode(11,OUTPUT); //OUT9 (PB5/OC1A) pinMode(12,OUTPUT); //OUT2 (PB6/OC1B) pinMode(13,OUTPUT); //OUT3 (PB7/OC1C) //Remember the registers not declared here remains zero by default... TCCR1A =((1<>= 1; // Because timer runs at 0.5us we need to do value/2 // Limit values to a valid range result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH); radio_status=0; // Radio channel read return(result); } uint8_t APM_RC_Class::GetState(void) { return(radio_status); } // InstantPWM implementation // This function forces the PWM output (reset PWM) on Out0 and Out1 (Timer5). For quadcopters use void APM_RC_Class::Force_Out0_Out1(void) { if (TCNT5>5000) // We take care that there are not a pulse in the output TCNT5=39990; // This forces the PWM output to reset in 5us (10 counts of 0.5us). The counter resets at 40000 } // This function forces the PWM output (reset PWM) on Out2 and Out3 (Timer1). For quadcopters use void APM_RC_Class::Force_Out2_Out3(void) { if (TCNT1>5000) TCNT1=39990; } // This function forces the PWM output (reset PWM) on Out6 and Out7 (Timer3). For quadcopters use void APM_RC_Class::Force_Out6_Out7(void) { if (TCNT3>5000) TCNT3=39990; } // allow HIL override of RC values // A value of -1 means no change // A value of 0 means no override, use the real RC values bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS]) { uint8_t sum = 0; for (uint8_t i=0; i