Browse Source

remove APM_RC, deprecated by AP_HAL

master
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
d4e350f574
  1. 9
      libraries/APM_RC/APM_RC.cpp
  2. 77
      libraries/APM_RC/APM_RC.h
  3. 336
      libraries/APM_RC/APM_RC_APM1.cpp
  4. 41
      libraries/APM_RC/APM_RC_APM1.h
  5. 328
      libraries/APM_RC/APM_RC_APM2.cpp
  6. 42
      libraries/APM_RC/APM_RC_APM2.h
  7. 48
      libraries/APM_RC/examples/APM1_radio/APM1_radio.pde
  8. 2
      libraries/APM_RC/examples/APM1_radio/Makefile
  9. 46
      libraries/APM_RC/examples/APM2_radio/APM2_radio.pde
  10. 2
      libraries/APM_RC/examples/APM2_radio/Makefile
  11. 63
      libraries/APM_RC/examples/ISR_Mask/ISR_Mask.pde
  12. 2
      libraries/APM_RC/examples/ISR_Mask/Makefile
  13. 8
      libraries/APM_RC/keywords.txt

9
libraries/APM_RC/APM_RC.cpp

@ -1,9 +0,0 @@ @@ -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;

77
libraries/APM_RC/APM_RC.h

@ -1,77 +0,0 @@ @@ -1,77 +0,0 @@
#ifndef __APM_RC_H__
#define __APM_RC_H__
#include <inttypes.h>
// 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

336
libraries/APM_RC/APM_RC_APM1.cpp

@ -1,336 +0,0 @@ @@ -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 <avr/interrupt.h>
#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 (Pulse<ICR4_old) { // Take care of the overflow of Timer4 (TOP=40000)
Pulse_Width=(Pulse + 40000)-ICR4_old; // Calculating pulse
}
else {
Pulse_Width=Pulse-ICR4_old; // Calculating pulse
}
if (Pulse_Width>8000) { // 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<<WGM11)); //Please read page 131 of DataSheet, we are changing the registers settings of WGM11,COM1B1,COM1A1 to 1 thats all...
TCCR1B = (1<<WGM13)|(1<<WGM12)|(1<<CS11); //Prescaler set to 8, that give us a resolution of 0.5us, read page 134 of data sheet
OCR1A = 0xFFFF; // Init ODR registers to nil output signal
OCR1B = 0xFFFF;
OCR1C = 0xFFFF;
ICR1 = 40000; //50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
// Init PWM Timer 3
pinMode(2,OUTPUT); //OUT7 (PE4/OC3B)
pinMode(3,OUTPUT); //OUT6 (PE5/OC3C)
pinMode(5,OUTPUT); //OUT10(PE3/OC3A)
TCCR3A =((1<<WGM31));
TCCR3B = (1<<WGM33)|(1<<WGM32)|(1<<CS31);
OCR3A = 0xFFFF; // Init ODR registers to nil output signal
OCR3B = 0xFFFF;
OCR3C = 0xFFFF;
ICR3 = 40000; //50hz freq
// Init PWM Timer 5
pinMode(44,OUTPUT); //OUT1 (PL5/OC5C)
pinMode(45,OUTPUT); //OUT0 (PL4/OC5B)
pinMode(46,OUTPUT); //OUT8 (PL3/OC5A)
TCCR5A =((1<<WGM51));
TCCR5B = (1<<WGM53)|(1<<WGM52)|(1<<CS51);
OCR5A = 0xFFFF; // Init ODR registers to nil output signal
OCR5B = 0xFFFF;
OCR5C = 0xFFFF;
ICR5 = 40000; //50hz freq
// Init PPM input and PWM Timer 4
pinMode(49, INPUT); // ICP4 pin (PL0) (PPM input)
pinMode(7,OUTPUT); //OUT5 (PH4/OC4B)
pinMode(8,OUTPUT); //OUT4 (PH5/OC4C)
TCCR4A =((1<<WGM40)|(1<<WGM41));
//Prescaler set to 8, that give us a resolution of 0.5us
// Input Capture rising edge
TCCR4B = ((1<<WGM43)|(1<<WGM42)|(1<<CS41)|(1<<ICES4));
OCR4B = 0xFFFF; // Init OCR registers to nil output signal
OCR4C = 0xFFFF;
OCR4A = 40000; ///50hz freq.
//TCCR4B |=(1<<ICES4); //Changing edge detector (rising edge).
//TCCR4B &=(~(1<<ICES4)); //Changing edge detector. (falling edge)
TIMSK4 |= (1<<ICIE4); // Enable Input Capture interrupt. Timer interrupt mask
}
void APM_RC_APM1::OutputCh(uint8_t ch, uint16_t pwm)
{
pwm=constrain(pwm,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
pwm<<=1; // pwm*2;
switch(ch)
{
case 0: OCR5B=pwm; break; //ch1
case 1: OCR5C=pwm; break; //ch2
case 2: OCR1B=pwm; break; //ch3
case 3: OCR1C=pwm; break; //ch4
case 4: OCR4C=pwm; break; //ch5
case 5: OCR4B=pwm; break; //ch6
case 6: OCR3C=pwm; break; //ch7
case 7: OCR3B=pwm; break; //ch8
case 8: OCR5A=pwm; break; //ch9, PL3
case 9: OCR1A=pwm; break; //ch10, PB5
case 10: OCR3A=pwm; break; //ch11, PE3
}
}
uint16_t APM_RC_APM1::OutputCh_current(uint8_t ch)
{
uint16_t pwm=0;
switch(ch) {
case 0: pwm=OCR5B; break; //ch1
case 1: pwm=OCR5C; break; //ch2
case 2: pwm=OCR1B; break; //ch3
case 3: pwm=OCR1C; break; //ch4
case 4: pwm=OCR4C; break; //ch5
case 5: pwm=OCR4B; break; //ch6
case 6: pwm=OCR3C; break; //ch7
case 7: pwm=OCR3B; break; //ch8
case 8: pwm=OCR5A; break; //ch9, PL3
case 9: pwm=OCR1A; break; //ch10, PB5
case 10: pwm=OCR3A; break; //ch11, PE3
}
return pwm>>1;
}
void APM_RC_APM1::enable_out(uint8_t ch)
{
switch(ch) {
case 0: TCCR5A |= (1<<COM5B1); break; // CH_1 : OC5B
case 1: TCCR5A |= (1<<COM5C1); break; // CH_2 : OC5C
case 2: TCCR1A |= (1<<COM1B1); break; // CH_3 : OC1B
case 3: TCCR1A |= (1<<COM1C1); break; // CH_4 : OC1C
case 4: TCCR4A |= (1<<COM4C1); break; // CH_5 : OC4C
case 5: TCCR4A |= (1<<COM4B1); break; // CH_6 : OC4B
case 6: TCCR3A |= (1<<COM3C1); break; // CH_7 : OC3C
case 7: TCCR3A |= (1<<COM3B1); break; // CH_8 : OC3B
case 8: TCCR5A |= (1<<COM5A1); break; // CH_9 : OC5A
case 9: TCCR1A |= (1<<COM1A1); break; // CH_10: OC1A
case 10: TCCR3A |= (1<<COM3A1); break; // CH_11: OC3A
}
}
void APM_RC_APM1::disable_out(uint8_t ch)
{
switch(ch) {
case 0: TCCR5A &= ~(1<<COM5B1); break; // CH_1 : OC5B
case 1: TCCR5A &= ~(1<<COM5C1); break; // CH_2 : OC5C
case 2: TCCR1A &= ~(1<<COM1B1); break; // CH_3 : OC1B
case 3: TCCR1A &= ~(1<<COM1C1); break; // CH_4 : OC1C
case 4: TCCR4A &= ~(1<<COM4C1); break; // CH_5 : OC4C
case 5: TCCR4A &= ~(1<<COM4B1); break; // CH_6 : OC4B
case 6: TCCR3A &= ~(1<<COM3C1); break; // CH_7 : OC3C
case 7: TCCR3A &= ~(1<<COM3B1); break; // CH_8 : OC3B
case 8: TCCR5A &= ~(1<<COM5A1); break; // CH_9 : OC5A
case 9: TCCR1A &= ~(1<<COM1A1); break; // CH_10: OC1A
case 10: TCCR3A &= ~(1<<COM3A1); break; // CH_11: OC3A
}
}
uint16_t APM_RC_APM1::InputCh(uint8_t ch)
{
uint16_t result;
if (_HIL_override[ch] != 0) {
return _HIL_override[ch];
}
// We need to block ICP4 interrupts during the read of 16 bit PWM values
uint8_t _timsk4 = TIMSK4;
TIMSK4 &= ~(1<<ICIE4);
// value
result = _PWM_RAW[ch];
// Enable ICP4 interrupt if previously active
TIMSK4 = _timsk4;
// Because timer runs at 0.5us we need to do value/2
result >>= 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<NUM_CHANNELS; i++) {
if (v[i] != -1) {
_HIL_override[i] = v[i];
}
if (_HIL_override[i] != 0) {
sum++;
}
}
_radio_status = 1;
_last_update = millis();
if (sum == 0) {
return 0;
} else {
return 1;
}
}
void APM_RC_APM1::clearOverride(void)
{
for (uint8_t i=0; i<NUM_CHANNELS; i++) {
_HIL_override[i] = 0;
}
}
#endif // defined(ATMega1280)

41
libraries/APM_RC/APM_RC_APM1.h

@ -1,41 +0,0 @@ @@ -1,41 +0,0 @@
#ifndef __APM_RC_APM1_H__
#define __APM_RC_APM1_H__
#define MIN_PULSEWIDTH 900
#define MAX_PULSEWIDTH 2100
#include "APM_RC.h"
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
class APM_RC_APM1 : public APM_RC_Class
{
public:
APM_RC_APM1();
void Init( Arduino_Mega_ISR_Registry * isr_reg );
void OutputCh(uint8_t ch, uint16_t pwm);
uint16_t OutputCh_current(uint8_t ch);
uint16_t InputCh(uint8_t ch);
uint8_t GetState();
bool setHIL(int16_t v[NUM_CHANNELS]);
void clearOverride(void);
void Force_Out(void);
void SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz = 400);
void enable_out(uint8_t);
void disable_out(uint8_t);
void Force_Out0_Out1(void);
void Force_Out2_Out3(void);
void Force_Out6_Out7(void);
private:
static void _timer4_capt_cb(void);
static volatile uint16_t _PWM_RAW[NUM_CHANNELS];
static volatile uint8_t _radio_status;
int16_t _HIL_override[NUM_CHANNELS];
};
#endif

328
libraries/APM_RC/APM_RC_APM2.cpp

@ -1,328 +0,0 @@ @@ -1,328 +0,0 @@
/*
* APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. 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_APM2.h"
#include <avr/interrupt.h>
#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<<WGM11));
TCCR1B = (1<<WGM13)|(1<<WGM12)|(1<<CS11);
ICR1 = 40000; // 0.5us tick => 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<<WGM41));
TCCR4B = (1<<WGM43)|(1<<WGM42)|(1<<CS41);
OCR4A = 0xFFFF; // Init OCR registers to nil output signal
OCR4B = 0xFFFF;
OCR4C = 0xFFFF;
ICR4 = 40000; // 0.5us tick => 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<<WGM31));
TCCR3B = (1<<WGM33)|(1<<WGM32)|(1<<CS31);
OCR3A = 0xFFFF; // Init OCR registers to nil output signal
OCR3B = 0xFFFF;
OCR3C = 0xFFFF;
ICR3 = 40000; // 0.5us tick => 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<<WGM50)|(1<<WGM51));
// Input Capture rising edge
TCCR5B = ((1<<WGM53)|(1<<WGM52)|(1<<CS51)|(1<<ICES5));
OCR5A = 40000; // 0.5us tick => 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<<ICIE5);
}
void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm)
{
pwm=constrain(pwm,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
pwm<<=1; // pwm*2;
switch(ch)
{
case 0: OCR1B=pwm; break; // out1
case 1: OCR1A=pwm; break; // out2
case 2: OCR4C=pwm; break; // out3
case 3: OCR4B=pwm; break; // out4
case 4: OCR4A=pwm; break; // out5
case 5: OCR3C=pwm; break; // out6
case 6: OCR3B=pwm; break; // out7
case 7: OCR3A=pwm; break; // out8
case 9: OCR5B=pwm; break; // out10
case 10: OCR5C=pwm; break; // out11
}
}
uint16_t APM_RC_APM2::OutputCh_current(uint8_t ch)
{
uint16_t pwm=0;
switch(ch) {
case 0: pwm=OCR1B; break; // out1
case 1: pwm=OCR1A; break; // out2
case 2: pwm=OCR4C; break; // out3
case 3: pwm=OCR4B; break; // out4
case 4: pwm=OCR4A; break; // out5
case 5: pwm=OCR3C; break; // out6
case 6: pwm=OCR3B; break; // out7
case 7: pwm=OCR3A; break; // out8
case 9: pwm=OCR5B; break; // out10
case 10: pwm=OCR5C; break; // out11
}
return pwm>>1;
}
void APM_RC_APM2::enable_out(uint8_t ch)
{
switch(ch) {
case 0: TCCR1A |= (1<<COM1B1); break; // CH_1 : OC1B
case 1: TCCR1A |= (1<<COM1A1); break; // CH_2 : OC1A
case 2: TCCR4A |= (1<<COM4C1); break; // CH_3 : OC4C
case 3: TCCR4A |= (1<<COM4B1); break; // CH_4 : OC4B
case 4: TCCR4A |= (1<<COM4A1); break; // CH_5 : OC4A
case 5: TCCR3A |= (1<<COM3C1); break; // CH_6 : OC3C
case 6: TCCR3A |= (1<<COM3B1); break; // CH_7 : OC3B
case 7: TCCR3A |= (1<<COM3A1); break; // CH_8 : OC3A
case 9: TCCR5A |= (1<<COM5B1); break; // CH_10 : OC5B
case 10: TCCR5A |= (1<<COM5C1); break; // CH_11 : OC5C
}
}
void APM_RC_APM2::disable_out(uint8_t ch)
{
switch(ch) {
case 0: TCCR1A &= ~(1<<COM1B1); break; // CH_1 : OC1B
case 1: TCCR1A &= ~(1<<COM1A1); break; // CH_2 : OC1A
case 2: TCCR4A &= ~(1<<COM4C1); break; // CH_3 : OC4C
case 3: TCCR4A &= ~(1<<COM4B1); break; // CH_4 : OC4B
case 4: TCCR4A &= ~(1<<COM4A1); break; // CH_5 : OC4A
case 5: TCCR3A &= ~(1<<COM3C1); break; // CH_6 : OC3C
case 6: TCCR3A &= ~(1<<COM3B1); break; // CH_7 : OC3B
case 7: TCCR3A &= ~(1<<COM3A1); break; // CH_8 : OC3A
case 9: TCCR5A &= ~(1<<COM5B1); break; // CH_10 : OC5B
case 10: TCCR5A &= ~(1<<COM5C1); break; // CH_11 : OC5C
}
}
uint16_t APM_RC_APM2::InputCh(unsigned char ch)
{
uint16_t result;
if (_HIL_override[ch] != 0) {
return _HIL_override[ch];
}
// We need to block ICP5 interrupts during the read of 16 bit PWM values
uint8_t _timsk5 = TIMSK5;
TIMSK5 &= ~(1<<ICIE5);
// value
result = _PWM_RAW[ch];
// Enable ICP5 interrupt if previously active
TIMSK5 = _timsk5;
// Because timer runs at 0.5us we need to do value/2
result >>= 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<NUM_CHANNELS; i++) {
if (v[i] != -1) {
_HIL_override[i] = v[i];
}
if (_HIL_override[i] != 0) {
sum++;
}
}
_radio_status = 1;
_last_update = millis();
if (sum == 0) {
return 0;
} else {
return 1;
}
}
void APM_RC_APM2::clearOverride(void)
{
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
_HIL_override[i] = 0;
}
}
#endif

42
libraries/APM_RC/APM_RC_APM2.h

@ -1,42 +0,0 @@ @@ -1,42 +0,0 @@
#ifndef __APM_RC_APM2_H__
#define __APM_RC_APM2_H__
#define NUM_CHANNELS 8
#define MIN_PULSEWIDTH 900
#define MAX_PULSEWIDTH 2100
#include "APM_RC.h"
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
class APM_RC_APM2 : public APM_RC_Class
{
private:
public:
APM_RC_APM2();
void Init( Arduino_Mega_ISR_Registry * isr_reg );
void OutputCh(uint8_t ch, uint16_t pwm);
uint16_t OutputCh_current(uint8_t ch);
uint16_t InputCh(unsigned char ch);
unsigned char GetState();
bool setHIL(int16_t v[NUM_CHANNELS]);
void clearOverride(void);
void Force_Out(void);
void SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz = 400);
void enable_out(uint8_t);
void disable_out(uint8_t);
void Force_Out0_Out1(void);
void Force_Out2_Out3(void);
void Force_Out6_Out7(void);
private:
static void _timer5_capt_cb(void);
static volatile uint16_t _PWM_RAW[NUM_CHANNELS];
static volatile uint8_t _radio_status;
int16_t _HIL_override[NUM_CHANNELS];
};
#endif

48
libraries/APM_RC/examples/APM1_radio/APM1_radio.pde

@ -1,48 +0,0 @@ @@ -1,48 +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 <FastSerial.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // 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();
}
}

2
libraries/APM_RC/examples/APM1_radio/Makefile

@ -1,2 +0,0 @@ @@ -1,2 +0,0 @@
BOARD = mega2560
include ../../../AP_Common/Arduino.mk

46
libraries/APM_RC/examples/APM2_radio/APM2_radio.pde

@ -1,46 +0,0 @@ @@ -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 <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // 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();
}
}

2
libraries/APM_RC/examples/APM2_radio/Makefile

@ -1,2 +0,0 @@ @@ -1,2 +0,0 @@
BOARD = mega2560
include ../../../AP_Common/Arduino.mk

63
libraries/APM_RC/examples/ISR_Mask/ISR_Mask.pde

@ -1,63 +0,0 @@ @@ -1,63 +0,0 @@
/*
test interrupt masking methods on APM1
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h>
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<<ICIE4);
delayMicroseconds(100);
TIMSK4 = _timsk4;
#endif
}

2
libraries/APM_RC/examples/ISR_Mask/Makefile

@ -1,2 +0,0 @@ @@ -1,2 +0,0 @@
BOARD = mega2560
include ../../../AP_Common/Arduino.mk

8
libraries/APM_RC/keywords.txt

@ -1,8 +0,0 @@ @@ -1,8 +0,0 @@
APM_RC KEYWORD1
begin KEYWORD2
InputCh KEYWORD2
OutputCh KEYWORD2
GetState KEYWORD2
Force_Out0_Out1 KEYWORD2
Force_Out2_Out3 KEYWORD2
Force_Out6_Out7 KEYWORD2
Loading…
Cancel
Save