/* APM_RC_QUAD.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. This is a special version of the library for use in Quadcopters Because we have modified servo outputs 0..3 to have a higher rate (300Hz) RC Input : PPM signal on IC4 pin RC Output : 8 servo Outputs, OUT0..OUT3 : 300Hz Servo output (for Quad ESCīs) OUT4..OUT7 : standard 50Hz servo outputs 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_QUAD.h" #include #include "WProgram.h" // Variable definition for Input Capture interrupt volatile unsigned int ICR4_old; volatile unsigned char PPM_Counter=0; volatile unsigned int PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400}; volatile unsigned char radio_status=0; /**************************************************** Input Capture Interrupt ICP4 => PPM signal read ****************************************************/ ISR(TIMER4_CAPT_vect) { unsigned int Pulse; unsigned int Pulse_Width; Pulse=ICR4; if (Pulse8000) // SYNC pulse? PPM_Counter=0; else { PPM_Counter &= 0x07; // For safety only (limit PPM_Counter to 7) PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse. if (PPM_Counter >= NUM_CHANNELS) radio_status = 1; } ICR4_old = Pulse; } // Constructors //////////////////////////////////////////////////////////////// APM_RC_QUAD_Class::APM_RC_QUAD_Class() { } // Public Methods ////////////////////////////////////////////////////////////// void APM_RC_QUAD_Class::Init(void) { // Init PWM Timer 1 //pinMode(11,OUTPUT); // (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 result2 = PWM_RAW[ch]>>1; if (result != result2) result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine) // Limit values to a valid range result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH); radio_status=0; // Radio channel read return(result); } unsigned char APM_RC_QUAD_Class::GetState(void) { return(radio_status); } // make one instance for the user to use APM_RC_QUAD_Class APM_RC_QUAD;