diff --git a/libraries/APM_RC/APM_RC.cpp b/libraries/APM_RC/APM_RC.cpp deleted file mode 100644 index 87c2d32b98..0000000000 --- a/libraries/APM_RC/APM_RC.cpp +++ /dev/null @@ -1,9 +0,0 @@ -/* - * APM_RC_.cpp - Radio Control Library for Ardupilot Mega. Arduino - * Code by Jordi Muñoz and Jose Julio. DIYDrones.com - * - */ -#include "APM_RC.h" - -volatile uint32_t APM_RC_Class::_last_update; - diff --git a/libraries/APM_RC/APM_RC.h b/libraries/APM_RC/APM_RC.h deleted file mode 100644 index 48ac4c4721..0000000000 --- a/libraries/APM_RC/APM_RC.h +++ /dev/null @@ -1,77 +0,0 @@ -#ifndef __APM_RC_H__ -#define __APM_RC_H__ - - -#include - - -// Radio channels - -// Note channels are from 0! - -#define CH_1 0 -#define CH_2 1 -#define CH_3 2 -#define CH_4 3 -#define CH_5 4 -#define CH_6 5 -#define CH_7 6 -#define CH_8 7 -#define CH_9 8 -#define CH_10 9 -#define CH_11 10 - - -#define NUM_CHANNELS 8 -#define MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet - - - -class Arduino_Mega_ISR_Registry; - -class APM_RC_Class - -{ - -public: - - virtual void Init( Arduino_Mega_ISR_Registry * isr_reg ) = 0; - virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0; - virtual uint16_t OutputCh_current(uint8_t ch) = 0; - virtual uint16_t InputCh(uint8_t ch) = 0; - virtual uint8_t GetState() = 0; - virtual void clearOverride(void) = 0; - virtual void Force_Out() = 0; - virtual void SetFastOutputChannels( uint32_t channelmask, uint16_t speed_hz = 400 ) = 0; - virtual void enable_out(uint8_t) = 0; - virtual void disable_out(uint8_t) = 0; - - virtual void Force_Out0_Out1(void) = 0; - virtual void Force_Out2_Out3(void) = 0; - virtual void Force_Out6_Out7(void) = 0; - - // get the time of the last radio update (_last_update modified by interrupt, so reading of variable must be interrupt safe) - virtual uint32_t get_last_update() { - - uint32_t _tmp = _last_update; - while( _tmp != _last_update ) _tmp = _last_update; - - return _tmp; - }; - -protected: - uint16_t _map_speed(uint16_t speed_hz) { - return 2000000UL / speed_hz; - } - static volatile uint32_t _last_update; // Modified by interrupt - -}; - - - -#include "APM_RC_APM1.h" -#include "APM_RC_APM2.h" - - -#endif - diff --git a/libraries/APM_RC/APM_RC_APM1.cpp b/libraries/APM_RC/APM_RC_APM1.cpp deleted file mode 100644 index 7f648e50f6..0000000000 --- a/libraries/APM_RC/APM_RC_APM1.cpp +++ /dev/null @@ -1,336 +0,0 @@ -/* - * APM_RC_APM1.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_APM1.h" - -#include -#if defined(ARDUINO) && ARDUINO >= 100 - #include "Arduino.h" -#else - #include "WProgram.h" -#endif - -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) && !defined(DESKTOP_BUILD) - # 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 APM_RC_APM1::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400}; -volatile uint8_t APM_RC_APM1::_radio_status=0; - -/**************************************************** -* Input Capture Interrupt ICP4 => PPM signal read -****************************************************/ -void APM_RC_APM1::_timer4_capt_cb(void) -{ - static uint16_t ICR4_old; - static uint8_t PPM_Counter=0; - - uint16_t Pulse; - uint16_t Pulse_Width; - - Pulse=ICR4; - if (Pulse8000) { // SYNC pulse? - // pass through values if at least a minimum number of channels received - if( PPM_Counter >= MIN_CHANNELS ) { - _radio_status = 1; - _last_update = millis(); - } - PPM_Counter=0; - } - else { - if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel? - _PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse. - } - } - ICR4_old = Pulse; -} - - -// Constructors //////////////////////////////////////////////////////////////// - -APM_RC_APM1::APM_RC_APM1() -{ -} - -// Public Methods ////////////////////////////////////////////////////////////// -void APM_RC_APM1::Init( Arduino_Mega_ISR_Registry * isr_reg ) -{ - - isr_reg->register_signal(ISR_REGISTRY_TIMER4_CAPT, _timer4_capt_cb ); - - // 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; -} - -void APM_RC_APM1::enable_out(uint8_t ch) -{ - switch(ch) { - case 0: TCCR5A |= (1<>= 1; - - // 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_APM1::GetState(void) -{ - return(_radio_status); -} - - -// InstantPWM implementation -void APM_RC_APM1::Force_Out(void) -{ - Force_Out0_Out1(); - Force_Out2_Out3(); - Force_Out6_Out7(); -} -// This function forces the PWM output (reset PWM) on Out0 and Out1 (Timer5). For quadcopters use -void APM_RC_APM1::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_APM1::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_APM1::Force_Out6_Out7(void) -{ - if (TCNT3>5000) - TCNT3=39990; -} - -/* --------------------- OUTPUT SPEED CONTROL --------------------- */ - -void APM_RC_APM1::SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz) -{ - uint16_t icr = _map_speed(speed_hz); - - if ((chmask & ( _BV(CH_1) | _BV(CH_2) | _BV(CH_9))) != 0) { - ICR5 = icr; - } - - if ((chmask & ( _BV(CH_3) | _BV(CH_4) | _BV(CH_10))) != 0) { - ICR1 = icr; - } - - #if 0 - if ((chmask & ( _BV(CH_5) | _BV(CH_6))) != 0) { - /* These channels intentionally left blank: - * Can't change output speed of ch5 (OCR4B) and ch6 (OCR4C). - * Timer 4 period controlled by OCR4A, and used for input - * capture on ICR4. - * If the period of Timer 4 must be changed, the input capture - * code will have to be adjusted as well - */ - } - #endif - - if ((chmask & ( _BV(CH_7) | _BV(CH_8) | _BV(CH_11))) != 0) { - ICR3 = icr; - } - -} - -// 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_APM1::setHIL(int16_t v[NUM_CHANNELS]) -{ - uint8_t sum = 0; - for (uint8_t i=0; i New radio frame to process - * Automatically resets when we call InputCh to read channels - * - */ -#include "APM_RC_APM2.h" - -#include -#if defined(ARDUINO) && ARDUINO >= 100 - #include "Arduino.h" -#else - #include "WProgram.h" -#endif - -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) && !defined(DESKTOP_BUILD) - # 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 APM_RC_APM2::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400}; -volatile uint8_t APM_RC_APM2::_radio_status=0; - -/**************************************************** -* Input Capture Interrupt ICP5 => PPM signal read -****************************************************/ -void APM_RC_APM2::_timer5_capt_cb(void) -{ - static uint16_t prev_icr; - static uint8_t frame_idx; - uint16_t icr; - uint16_t pwidth; - - icr = ICR5; - // Calculate pulse width assuming timer overflow TOP = 40000 - if ( icr < prev_icr ) { - pwidth = ( icr + 40000 ) - prev_icr; - } else { - pwidth = icr - prev_icr; - } - - // Was it a sync pulse? If so, reset frame. - if ( pwidth > 8000 ) { - // pass through values if at least a minimum number of channels received - if( frame_idx >= MIN_CHANNELS ) { - _radio_status = 1; - _last_update = millis(); - } - frame_idx=0; - } else { - // Save pulse into _PWM_RAW array. - if ( frame_idx < NUM_CHANNELS ) { - _PWM_RAW[ frame_idx++ ] = pwidth; - } - } - // Save icr for next call. - prev_icr = icr; -} - - -// Constructors //////////////////////////////////////////////////////////////// - -APM_RC_APM2::APM_RC_APM2() -{ -} - -// Public Methods ////////////////////////////////////////////////////////////// -void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg ) -{ - // --------------------- TIMER1: OUT1 and OUT2 ----------------------- - digitalWrite(12,HIGH); // pulling high before changing to output avoids a momentary drop of the pin to low because the ESCs have a pull-down resistor it seems - digitalWrite(11,HIGH); - pinMode(12,OUTPUT); // OUT1 (PB6/OC1B) - pinMode(11,OUTPUT); // OUT2 (PB5/OC1A) - digitalWrite(12,HIGH); // pulling high before changing to output avoids a momentary drop of the pin to low because the ESCs have a pull-down resistor it seems - digitalWrite(11,HIGH); - - // WGM: 1 1 1 0. Clear Timer on Compare, TOP is ICR1. - // CS11: prescale by 8 => 0.5us tick - TCCR1A =((1< 50hz freq - OCR1A = 0xFFFF; // Init OCR registers to nil output signal - OCR1B = 0xFFFF; - - // --------------- TIMER4: OUT3, OUT4, and OUT5 --------------------- - digitalWrite(8,HIGH); - digitalWrite(7,HIGH); - digitalWrite(6,HIGH); - pinMode(8,OUTPUT); // OUT3 (PH5/OC4C) - pinMode(7,OUTPUT); // OUT4 (PH4/OC4B) - pinMode(6,OUTPUT); // OUT5 (PH3/OC4A) - digitalWrite(8,HIGH); - digitalWrite(7,HIGH); - digitalWrite(6,HIGH); - - // WGM: 1 1 1 0. Clear Timer on Compare, TOP is ICR4. - // CS41: prescale by 8 => 0.5us tick - TCCR4A =((1< 50hz freq - - //--------------- TIMER3: OUT6, OUT7, and OUT8 ---------------------- - digitalWrite(3,HIGH); - digitalWrite(2,HIGH); - digitalWrite(5,HIGH); - pinMode(3,OUTPUT); // OUT6 (PE5/OC3C) - pinMode(2,OUTPUT); // OUT7 (PE4/OC3B) - pinMode(5,OUTPUT); // OUT8 (PE3/OC3A) - digitalWrite(3,HIGH); - digitalWrite(2,HIGH); - digitalWrite(5,HIGH); - - // WGM: 1 1 1 0. Clear timer on Compare, TOP is ICR3 - // CS31: prescale by 8 => 0.5us tick - TCCR3A =((1< 50hz freq - - //--------------- TIMER5: PPM INPUT, OUT10, and OUT11 --------------- - // Init PPM input on Timer 5 - pinMode(48, INPUT); // PPM Input (PL1/ICP5) - - digitalWrite(45,HIGH); - digitalWrite(44,HIGH); - pinMode(45, OUTPUT); // OUT10 (PL4/OC5B) - pinMode(44, OUTPUT); // OUT11 (PL5/OC5C) - digitalWrite(45,HIGH); - digitalWrite(44,HIGH); - - // WGM: 1 1 1 1. Fast PWM, TOP is OCR5A - // COM all disabled. - // CS51: prescale by 8 => 0.5us tick - // ICES5: Input Capture on rising edge - TCCR5A =((1< 50hz freq. The input capture routine - // assumes this 40000 for TOP. - - isr_reg->register_signal( ISR_REGISTRY_TIMER5_CAPT, _timer5_capt_cb ); - // Enable Input Capture interrupt - TIMSK5 |= (1<>1; -} - -void APM_RC_APM2::enable_out(uint8_t ch) -{ - switch(ch) { - case 0: TCCR1A |= (1<>= 1; - - // 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_APM2::GetState(void) -{ - return(_radio_status); -} - -// InstantPWM is not implemented! - -void APM_RC_APM2::Force_Out(void) { -} -void APM_RC_APM2::Force_Out0_Out1(void) { -} -void APM_RC_APM2::Force_Out2_Out3(void) { -} -void APM_RC_APM2::Force_Out6_Out7(void) { -} - -/* ---------------- OUTPUT SPEED CONTROL ------------------ */ - -void APM_RC_APM2::SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz) -{ - uint16_t icr = _map_speed(speed_hz); - - if ((chmask & ( _BV(CH_1) | _BV(CH_2))) != 0) { - ICR1 = icr; - } - - if ((chmask & ( _BV(CH_3) | _BV(CH_4) | _BV(CH_5))) != 0) { - ICR4 = icr; - } - - if ((chmask & ( _BV(CH_6) | _BV(CH_7) | _BV(CH_8))) != 0) { - ICR3 = icr; - } -} - -// 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_APM2::setHIL(int16_t v[NUM_CHANNELS]) -{ - uint8_t sum = 0; - for (unsigned char i=0; i -#include -#include // ArduPilot Mega RC Library - -FastSerialPort0(Serial); - -Arduino_Mega_ISR_Registry isr_registry; -APM_RC_APM1 APM_RC; - -void setup() -{ - isr_registry.init(); - APM_RC.Init(&isr_registry); // APM Radio initialization - APM_RC.enable_out(CH_1); - APM_RC.enable_out(CH_2); - APM_RC.enable_out(CH_3); - APM_RC.enable_out(CH_4); - APM_RC.enable_out(CH_5); - APM_RC.enable_out(CH_6); - APM_RC.enable_out(CH_7); - APM_RC.enable_out(CH_8); - - Serial.begin(115200); - Serial.println("ArduPilot Mega RC library test"); - delay(1000); -} - -void loop() -{ - // New radio frame? (we could use also if((millis()- timer) > 20) - if (APM_RC.GetState() == 1) { - Serial.print("CH:"); - for(int i = 0; i < 8; i++) { - Serial.print(APM_RC.InputCh(i)); // Print channel values - Serial.print(","); - APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos - } - Serial.println(); - } -} diff --git a/libraries/APM_RC/examples/APM1_radio/Makefile b/libraries/APM_RC/examples/APM1_radio/Makefile deleted file mode 100644 index a5d5e7918b..0000000000 --- a/libraries/APM_RC/examples/APM1_radio/Makefile +++ /dev/null @@ -1,2 +0,0 @@ -BOARD = mega2560 -include ../../../AP_Common/Arduino.mk diff --git a/libraries/APM_RC/examples/APM2_radio/APM2_radio.pde b/libraries/APM_RC/examples/APM2_radio/APM2_radio.pde deleted file mode 100644 index debdbb3019..0000000000 --- a/libraries/APM_RC/examples/APM2_radio/APM2_radio.pde +++ /dev/null @@ -1,46 +0,0 @@ -/* - * Example of APM_RC library. - * Code by Jordi MuÃ’oz and Jose Julio. DIYDrones.com - * - * Print Input values and send Output to the servos - * (Works with last PPM_encoder firmware) - */ - -#include -#include // ArduPilot Mega RC Library - -Arduino_Mega_ISR_Registry isr_registry; -APM_RC_APM2 APM_RC; - -void setup() -{ - isr_registry.init(); - APM_RC.Init(&isr_registry); // APM Radio initialization - - APM_RC.enable_out(CH_1); - APM_RC.enable_out(CH_2); - APM_RC.enable_out(CH_3); - APM_RC.enable_out(CH_4); - APM_RC.enable_out(CH_5); - APM_RC.enable_out(CH_6); - APM_RC.enable_out(CH_7); - APM_RC.enable_out(CH_8); - - Serial.begin(115200); - Serial.println("ArduPilot Mega RC library test"); - delay(1000); -} - -void loop() -{ - // New radio frame? (we could use also if((millis()- timer) > 20) - if (APM_RC.GetState() == 1) { - Serial.print("CH:"); - for(int i = 0; i < 8; i++) { - Serial.print(APM_RC.InputCh(i)); // Print channel values - Serial.print(","); - APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos - } - Serial.println(); - } -} diff --git a/libraries/APM_RC/examples/APM2_radio/Makefile b/libraries/APM_RC/examples/APM2_radio/Makefile deleted file mode 100644 index a5d5e7918b..0000000000 --- a/libraries/APM_RC/examples/APM2_radio/Makefile +++ /dev/null @@ -1,2 +0,0 @@ -BOARD = mega2560 -include ../../../AP_Common/Arduino.mk diff --git a/libraries/APM_RC/examples/ISR_Mask/ISR_Mask.pde b/libraries/APM_RC/examples/ISR_Mask/ISR_Mask.pde deleted file mode 100644 index 02bf8a6ee7..0000000000 --- a/libraries/APM_RC/examples/ISR_Mask/ISR_Mask.pde +++ /dev/null @@ -1,63 +0,0 @@ -/* - test interrupt masking methods on APM1 - */ - -#include -#include -#include -#include -#include - -FastSerialPort0(Serial); - -Arduino_Mega_ISR_Registry isr_registry; -APM_RC_APM1 APM_RC; - -void setup() -{ - Serial.begin(115200); - isr_registry.init(); - APM_RC.Init(&isr_registry); - Serial.println("Interrupt masking test"); - delay(10); -} - -static uint16_t last_values[8]; - -#define USE_CLI 0 -#define USE_MASK 1 - -void loop() -{ - if (APM_RC.GetState() == 1) { - bool changed = false; - for (uint8_t i = 0; i < 8; i++) { - uint16_t v = APM_RC.InputCh(i); - if (abs(v - last_values[i]) > 10) { - changed = true; - } - last_values[i] = v; - } - if (changed) { - for (uint8_t i = 0; i < 8; i++) { - Serial.printf("%u:%4u ", (unsigned)i, (unsigned)last_values[i]); - } - Serial.println(); - delayMicroseconds(500); - } - } - -#if USE_CLI - uint8_t oldSREG = SREG; - cli(); - delayMicroseconds(100); - SREG = oldSREG; -#endif - -#if USE_MASK - uint8_t _timsk4 = TIMSK4; - TIMSK4 &= ~(1<