From 6c3ef981e248111ac87c6df1b48aab26b6e32309 Mon Sep 17 00:00:00 2001 From: midelic Date: Thu, 22 Sep 2016 20:11:59 +0300 Subject: [PATCH] Delete Multiprotocol.ino --- Multiprotocol.ino | 1558 --------------------------------------------- 1 file changed, 1558 deletions(-) delete mode 100644 Multiprotocol.ino diff --git a/Multiprotocol.ino b/Multiprotocol.ino deleted file mode 100644 index 918d07d..0000000 --- a/Multiprotocol.ino +++ /dev/null @@ -1,1558 +0,0 @@ -/********************************************************* - Multiprotocol Tx code - by Midelic and Pascal Langer(hpnuts) - http://www.rcgroups.com/forums/showthread.php?t=2165676 - https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/edit/master/README.md - - Thanks to PhracturedBlue, Hexfet, Goebish, Victzh and all protocol developers - Ported from deviation firmware - - This project is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Multiprotocol is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with Multiprotocol. If not, see . -*/ -#define STM32_board -//#undef __cplusplus -#if defined STM32_board -#include "Multiprotocol_STM32.h" -#include -#include -#include -#include -uint16_t OCR1A = 0; -uint16_t TCNT1=0; -HardwareTimer timer(2); -#else -#include -#include -#include "Multiprotocol.h" -#endif - -#include -#include "_Config.h" -#include "TX_Def.h" -//Multiprotocol module configuration file - -//Global constants/variables -uint32_t MProtocol_id;//tx id, -uint32_t MProtocol_id_master; -uint32_t Model_fixed_id=0; -uint32_t fixed_id; -uint32_t blink=0; -uint8_t prev_option;//change option value on the fly. -uint8_t prev_power=0xFD; // unused power value -// -uint16_t counter; -uint8_t channel; -uint8_t packet[40]; - -#define NUM_CHN 16 -// Servo data -uint16_t Servo_data[NUM_CHN]; -uint8_t Servo_AUX; -uint16_t servo_max_100,servo_min_100,servo_max_125,servo_min_125; - -#ifndef STM32_board -uint16_t servo_max_100,servo_min_100,servo_max_125,servo_min_125; -#endif -// Protocol variables -uint8_t cyrfmfg_id[6];//for dsm2 and devo -uint8_t rx_tx_addr[5]; -uint8_t phase; -uint16_t bind_counter; -uint8_t bind_phase; -uint8_t binding_idx; -uint16_t packet_period; -uint8_t packet_count; -uint8_t packet_sent; -uint8_t packet_length; -uint8_t hopping_frequency[23]; -uint8_t *hopping_frequency_ptr; -uint8_t hopping_frequency_no=0; -uint8_t rf_ch_num; -uint8_t throttle, rudder, elevator, aileron; -uint8_t flags; -uint16_t crc; -uint8_t crc8; -uint16_t seed; -// -uint16_t state; -uint8_t len; -uint8_t RX_num; - -#if defined(FRSKYX_CC2500_INO) || defined(SFHSS_CC2500_INO) -uint8_t calData[48]; -#endif - -//Channel mapping for protocols -const uint8_t CH_AETR[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; -const uint8_t CH_TAER[]={THROTTLE, AILERON, ELEVATOR, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; -const uint8_t CH_RETA[]={RUDDER, ELEVATOR, THROTTLE, AILERON, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; -const uint8_t CH_EATR[]={ELEVATOR, AILERON, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; - -// Mode_select variables -uint8_t mode_select; -uint8_t protocol_flags=0,protocol_flags2=0; - -// PPM variable -volatile uint16_t PPM_data[NUM_CHN]; - -// Serial variables -#ifdef INVERT_TELEMETRY -// enable bit bash for serial -#define BASH_SERIAL 1 -#define INVERT_SERIAL 1 -#endif -#define BAUD 100000 -#define RXBUFFER_SIZE 25 -#define TXBUFFER_SIZE 32 -volatile uint8_t rx_buff[RXBUFFER_SIZE]; -volatile uint8_t rx_ok_buff[RXBUFFER_SIZE]; -#ifndef BASH_SERIAL -volatile uint8_t tx_buff[TXBUFFER_SIZE]; -#endif -volatile uint8_t discard_frame = 0; - -//Serial protocol -uint8_t sub_protocol; -uint8_t option; -uint8_t cur_protocol[2]; -uint8_t prev_protocol=0; - -#ifdef STM32_board -void PPM_decode(); -void ISR_COMPB(); -#endif -// Telemetry -#define MAX_PKT 27 -uint8_t pkt[MAX_PKT];//telemetry receiving packets -#if defined(TELEMETRY) -uint8_t pass = 0; -uint8_t pktt[MAX_PKT];//telemetry receiving packets -#ifndef BASH_SERIAL -volatile uint8_t tx_head=0; -volatile uint8_t tx_tail=0; -#endif // BASH_SERIAL -uint8_t v_lipo; -int16_t RSSI_dBm; -uint8_t telemetry_link=0; -uint8_t telemetry_counter=0; -#endif - -// Callback -typedef uint16_t (*void_function_t) (void);//pointer to a function with no parameters which return an uint16_t integer -void_function_t remote_callback = 0; -static void CheckTimer(uint16_t (*cb)(void)); - -// Init -void setup() -{ - #ifdef XMEGA - PORTD.OUTSET = 0x17 ; - PORTD.DIRSET = 0xB2 ; - PORTD.DIRCLR = 0x4D ; - PORTD.PIN0CTRL = 0x18 ; - PORTD.PIN2CTRL = 0x18 ; - PORTE.DIRSET = 0x01 ; - PORTE.DIRCLR = 0x02 ; - PORTE.OUTSET = 0x01 ; - - for ( uint8_t count = 0 ; count < 20 ; count += 1 ) - asm("nop") ; - PORTE.OUTCLR = 0x01 ; - #else - // General pinout - #if defined STM32_board - pinMode(CS_pin,OUTPUT); - pinMode(CC25_CSN_pin,OUTPUT); - pinMode(NRF_CSN_pin,OUTPUT); - pinMode(CYRF_CSN_pin,OUTPUT); - pinMode(CYRF_RST_pin,OUTPUT); - pinMode(CTRL1,OUTPUT); - pinMode(CTRL2,OUTPUT); - #if defined TELEMETRY - pinMode(TX_INV_pin,OUTPUT); - pinMode(RX_INV_pin,OUTPUT); - #if defined TARANIS - TX_INV_on; - RX_INV_on; - #else - TX_INV_off; - RX_INV_off; - #endif - #endif - //pinMode(SDI_pin,OUTPUT); - //pinMode(SCK_pin,OUTPUT);//spi pins initialized with spi init - //pinMode(SDO_pin,INPUT); - pinMode(BIND_pin,INPUT_PULLUP); - pinMode(PPM_pin,INPUT); - pinMode(S1_pin,INPUT_PULLUP);//dial switch - pinMode(S2_pin,INPUT_PULLUP); - pinMode(S3_pin,INPUT_PULLUP); - pinMode(S4_pin,INPUT_PULLUP); - #else - DDRD = (1<regs->IDR)>>4)&0x0F); - #else - mode_select=0x0F - ( ( (PINB>>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0 - #endif - #endif - - //********************************** - //mode_select=0; // here to test PPM - //********************************** - // Update LED - - LED_OFF; - LED_SET_OUTPUT; - // Read or create protocol id - MProtocol_id_master=random_id(10,false); - - #ifdef STM32_board - initSPI2(); - #endif - //Init RF modules - modules_reset(); - //LED_ON; - //Protocol and interrupts initialization -#ifdef ENABLE_PPM - if(mode_select != MODE_SERIAL) - { // PPM - mode_select--; - cur_protocol[0] = PPM_prot[mode_select].protocol; - sub_protocol = PPM_prot[mode_select].sub_proto; - RX_num = PPM_prot[mode_select].rx_num; - MProtocol_id = RX_num + MProtocol_id_master; - option = PPM_prot[mode_select].option; - if(PPM_prot[mode_select].power) POWER_FLAG_on; - if(PPM_prot[mode_select].autobind) AUTOBIND_FLAG_on; - mode_select++; - servo_max_100=PPM_MAX_100; servo_min_100=PPM_MIN_100; - servo_max_125=PPM_MAX_125; servo_min_125=PPM_MIN_125; - - protocol_init(); - - #ifndef XMEGA - #ifndef STM32_board - //Configure PPM interrupt - EICRA |=(1<2*200) - { - do - { - Update_All(); - } - while(remote_callback==0); - } - #ifdef XMEGA - if( (TCC1.INTFLAGS & TC1_CCAIF_bm) != 0) - { - cli(); // disable global int - TCC1.CCA = TCC1.CNT ; // Callback should already have been called... Use "now" as new sync point. - sei(); // enable global int - } - else - while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait before callback - #else - #if defined STM32_board - if((TIMER2_BASE->SR & TIMER_SR_CC1IF)!=0){ - cli(); - OCR1A = TIMER2_BASE->CNT; - TIMER2_BASE->CCR1=OCR1A; - sei(); - } - else - while((TIMER2_BASE->SR & TIMER_SR_CC1IF )==0);//walit till compare match - #else - if( (TIFR1 & (1<4000) - { // start to wait here as much as we can... - next_callback-=2000; - - #ifdef XMEGA - cli(); // disable global int - TCC1.CCA +=2000*2; // set compare A for callback - TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag - sei(); // enable global int - Update_All(); - if(IS_CHANGE_PROTOCOL_FLAG_on) - break; // Protocol has been changed - while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait 2ms... - #else - - #if defined STM32_board - cli(); - OCR1A+=2000*2;// clear compare A=callback flag - TIMER2_BASE->CCR1=OCR1A; - TCNT1 = TIMER2_BASE->CNT; - TIMER2_BASE->SR &= ~TIMER_SR_CC1IF; //clear compare Flag - sei(); - Update_All(); - if(IS_CHANGE_PROTOCOL_FLAG_on) - break; // Protocol has been changed - while((TIMER2_BASE->SR &TIMER_SR_CC1IF)==0);//2ms wait - #else - cli(); - OCR1A+=2000*2; // clear compare A=callback flag - TIFR1=(1<CCR1 = OCR1A; - TCNT1 = TIMER2_BASE->CNT; - TIMER2_BASE->SR &= ~TIMER_SR_CC1IF;//clear compare Flag write zero - diff=OCR1A-TCNT1; // compare timer and comparator - sei(); - #else - cli(); - OCR1A+=next_callback; // set compare A for callback - TIFR1=(1<PPM_MAX_125) temp_ppm=PPM_MAX_125; - Servo_data[i]= temp_ppm ; - } - update_aux_flags(); - PPM_FLAG_off; // wait for next frame before update - } -#endif //ENABLE_PPM - update_led_status(); - #if defined(TELEMETRY) - uint8_t protocol=cur_protocol[0]&0x1F; - if( (protocol==MODE_FRSKY) || (protocol==MODE_HUBSAN) || (protocol==MODE_FRSKYX) || (protocol==MODE_DSM2) ) - TelemetryUpdate(); - #endif -#ifndef STM32_board - TX_ON; - NOP(); - TX_OFF; -#endif -} - - -// Update Servo_AUX flags based on servo AUX positions -static void update_aux_flags(void) -{ - Servo_AUX=0; - for(uint8_t i=0;i<8;i++) - if(Servo_data[AUX1+i]>PPM_SWITCH) - Servo_AUX|=1< led on - else - blink+=BLINK_BIND_TIME; //blink fastly during binding - LED_TOGGLE; - } -} - -inline void tx_pause() -{ -#ifdef TELEMETRY - #ifdef XMEGA - USARTC0.CTRLA &= ~0x03 ; // Pause telemetry by disabling transmitter interrupt - #else - #ifndef BASH_SERIAL - #ifdef STM32_board - USART3_BASE->CR1 &= ~ USART_CR1_TXEIE;//disable TX intrerupt - #else - UCSR0B &= ~_BV(UDRIE0); // Pause telemetry by disabling transmitter interrupt - #endif - #endif - #endif -#endif -} - - -inline void tx_resume() -{ -#ifdef TELEMETRY - if(!IS_TX_PAUSE_on) - #ifdef XMEGA - USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ; // Resume telemetry by enabling transmitter interrupt - #else - #ifdef STM32_board - USART3_BASE->CR1 |= USART_CR1_TXEIE;// TX intrrupt enabled - #else - UCSR0B |= _BV(UDRIE0); // Resume telemetry by enabling transmitter interrupt - #endif - #endif -#endif -} - - -#ifdef STM32_board -void start_timer2(){ - // Pause the timer while we're configuring it - timer.pause(); - TIMER2_BASE->PSC = 35;//36-1;for 72 MHZ /0.5sec/(35+1) - TIMER2_BASE->ARR = 0xFFFF; //count till max - timer.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE); - timer.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE); - // Refresh the timer's count, prescale, and overflow - timer.refresh(); - timer.resume(); -} -#endif - -// Protocol scheduler -static void CheckTimer(uint16_t (*cb)(void)) -{ - uint16_t next_callback,diff; - #ifdef XMEGA - if( (TCC1.INTFLAGS & TC1_CCAIF_bm) != 0) - { - cli(); // disable global int - TCC1.CCA = TCC1.CNT ; // Callback should already have been called... Use "now" as new sync point. - sei(); // enable global int - } - else - while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait before callback - #else - #if defined STM32_board - if((TIMER2_BASE->SR & TIMER_SR_CC1IF)!=0){ - cli(); - OCR1A = TIMER2_BASE->CNT; - TIMER2_BASE->CCR1=OCR1A; - sei(); - } - else - while((TIMER2_BASE->SR & TIMER_SR_CC1IF )==0);//walit till compare match - #else - if( (TIFR1 & (1<4000) - { // start to wait here as much as we can... - next_callback=next_callback-2000; - - #ifdef XMEGA - cli(); // disable global int - TCC1.CCA +=2000*2; // set compare A for callback - TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag - sei(); // enable global int - while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait 2ms... - #else - - #if defined STM32_board - cli(); - OCR1A+=2000*2;// clear compare A=callback flag - TIMER2_BASE->CCR1=OCR1A; - TCNT1 = TIMER2_BASE->CNT; - TIMER2_BASE->SR &= ~TIMER_SR_CC1IF; //clear compare Flag - sei(); - while((TIMER2_BASE->SR &TIMER_SR_CC1IF)==0);//2ms wait - #else - cli(); - OCR1A+=2000*2; // clear compare A=callback flag - TIFR1=(1<CCR1 = OCR1A; - TCNT1 = TIMER2_BASE->CNT; - TIMER2_BASE->SR &= ~TIMER_SR_CC1IF;//clear compare Flag write zero - diff=OCR1A-TCNT1; // compare timer and comparator - sei(); - #else - cli(); - OCR1A+=next_callback; // set compare A for callback - TIFR1=(1<32000) - { // next_callback should not be more than 32767 so we will wait here... - uint16_t temp=(next_callback>>10)-2; - delay(temp); - next_callback-=temp<<10; // between 2-3ms left at this stage - } - - #ifdef XMEGA - cli(); // disable global int - TCC1.CCA = TCC1.CNT + next_callback*2; // set compare A for callback - sei(); // enable global int - TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A flag - #else - #if defined STM32_board - cli(); // disable global int - TCNT1 = TIMER2_BASE->CNT; - OCR1A=TCNT1+next_callback*2; - TIMER2_BASE->CCR1 = OCR1A; - sei(); - TIMER2_BASE->SR &= ~TIMER_SR_CC1IF;//clear compare Flag write zero - #else - cli(); // disable global int - OCR1A=TCNT1+next_callback*2; // set compare A for callback - sei(); // enable global int - TIFR1=(1<>4)& 0x07; //subprotocol no (0-7) bits 4-6 - RX_num=rx_ok_buff[1]& 0x0F; - MProtocol_id=MProtocol_id_master+RX_num; //personalized RX bind + rx num // rx_num bits 0---3 - } - else - if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set - CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind - else - cur_protocol[0] = rx_ok_buff[0]; //store current protocol - - // decode channel values - volatile uint8_t *p=rx_ok_buff+2; - uint8_t dec=-3; - for(uint8_t i=0;i=8) - { - dec-=8; - p++; - } - p++; - Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125% - } - RX_DONOTUPDTAE_off; - -#ifdef XMEGA - cli(); - #else - #ifdef STM32_board - //here code fro RX intrurpt disable - USART3_BASE->CR1 &= ~ USART_CR1_RXNEIE;//disable - #else - UCSR0B &= ~(1<CR1 |= USART_CR1_RXNEIE ;//disable - #else - UCSR0B |= (1<>8); -} - -// Channel value is limited to PPM_100 -uint16_t limit_channel_100(uint8_t ch) -{ - if(Servo_data[ch]>servo_max_100) - return servo_max_100; - else - if (Servo_data[ch]CR1 |= USART_CR1_PCE_BIT; - USART3_BASE->CR1 &= ~ USART_CR1_RE;//disable - USART2_BASE->CR1 &= ~ USART_CR1_TE;//disable transmit - #else - #include - UBRR0H = UBRRH_VALUE; - UBRR0L = UBRRL_VALUE; - UCSR0A = 0 ; // Clear X2 bit - //Set frame format to 8 data bits, even parity, 2 stop bits - UCSR0C = (1<> 24) & 0xFF; - rx_tx_addr[1] = (id >> 16) & 0xFF; - rx_tx_addr[2] = (id >> 8) & 0xFF; - rx_tx_addr[3] = (id >> 0) & 0xFF; - rx_tx_addr[4] = 0xC1; // for YD717: always uses first data port -} - -#if defined STM32_board -static uint32_t random_id(uint16_t adress, uint8_t create_new) -{ - uint32_t id; - uint8_t txid[4]; - pinMode(PB0, INPUT_ANALOG); // set up pin for analog input - pinMode(PB1, INPUT_ANALOG); // set up pin for analog input - - if ((EEPROM.read(adress+100)==0xf0) && !create_new) - { // TXID exists in EEPROM - for(uint8_t i=0;i<4;i++) - txid[i]=EEPROM.read(adress+110); - id=(txid[0] | ((uint32_t)txid[1]<<8) | ((uint32_t)txid[2]<<16) | ((uint32_t)txid[3]<<24)); - } - else - { // if not generate a random ID - randomSeed((uint32_t)analogRead(PB0)<<10|analogRead(PB1));//seed - // - id = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16); - txid[0]= (id &0xFF); - txid[1] = ((id >> 8) & 0xFF); - txid[2] = ((id >> 16) & 0xFF); - txid[3] = ((id >> 24) & 0xFF); - for(uint8_t i=0;i<4;i++) - EEPROM.write((adress+110),txid[i]); - EEPROM.write(adress+100,0xF0); - } - return id; -} - -#else -static uint32_t random_id(uint16_t adress, uint8_t create_new) -{ - uint32_t id; - uint8_t txid[4]; - - if (eeprom_read_byte((uint8_t*)(adress+10))==0xf0 && !create_new) - { // TXID exists in EEPROM - eeprom_read_block((void*)txid,(const void*)adress,4); - id=(txid[0] | ((uint32_t)txid[1]<<8) | ((uint32_t)txid[2]<<16) | ((uint32_t)txid[3]<<24)); - } - else - { // if not generate a random ID - randomSeed((uint32_t)analogRead(A6)<<10|analogRead(A7));//seed - // - id = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16); - txid[0]= (id &0xFF); - txid[1] = ((id >> 8) & 0xFF); - txid[2] = ((id >> 16) & 0xFF); - txid[3] = ((id >> 24) & 0xFF); - eeprom_write_block((const void*)txid,(void*)adress,4); - eeprom_write_byte((uint8_t*)(adress+10),0xf0);//write bind flag in eeprom. - } - return id; -} - -#endif - -#ifndef XMEGA -#ifndef STM32_board -/************************************/ -/** Arduino replacement routines **/ -/************************************/ -// replacement millis() and micros() -// These work polled, no interrupts -// micros() MUST be called at least once every 32 milliseconds -uint16_t MillisPrecount ; -uint16_t lastTimerValue ; -uint32_t TotalMicros ; -uint32_t TotalMillis ; -uint8_t Correction ; - -uint32_t micros() -{ - uint16_t elapsed ; - uint8_t millisToAdd ; - uint8_t oldSREG = SREG ; - cli() ; - uint16_t time = TCNT1 ; // Read timer 1 - SREG = oldSREG ; - - elapsed = time - lastTimerValue ; - elapsed += Correction ; - Correction = elapsed & 0x01 ; - elapsed >>= 1 ; - - uint32_t ltime = TotalMicros ; - ltime += elapsed ; - cli() ; - TotalMicros = ltime ; // Done this way for RPM to work correctly - lastTimerValue = time ; - SREG = oldSREG ; // Still valid from above - - elapsed += MillisPrecount; - millisToAdd = 0 ; - - if ( elapsed > 15999 ) - { - millisToAdd = 16 ; - elapsed -= 16000 ; - } - if ( elapsed > 7999 ) - { - millisToAdd += 8 ; - elapsed -= 8000 ; - } - if ( elapsed > 3999 ) - { - millisToAdd += 4 ; - elapsed -= 4000 ; - } - if ( elapsed > 1999 ) - { - millisToAdd += 2 ; - elapsed -= 2000 ; - } - if ( elapsed > 999 ) - { - millisToAdd += 1 ; - elapsed -= 1000 ; - } - TotalMillis += millisToAdd ; - MillisPrecount = elapsed ; - return TotalMicros ; -} - -uint32_t millis() -{ - micros() ; - return TotalMillis ; -} - -void delayMilliseconds(unsigned long ms) -{ - uint16_t start = (uint16_t)micros(); - uint16_t lms = ms ; - - while (lms > 0) { - if (((uint16_t)micros() - start) >= 1000) { - lms--; - start += 1000; - } - } -} - -/* Important notes: - - Max value is 16000µs - - delay is not accurate due to interrupts happening */ -void delayMicroseconds(unsigned int us) -{ - if (--us == 0) - return; - us <<= 2; // * 4 - us -= 2; // - 2 - __asm__ __volatile__ ( - "1: sbiw %0,1" "\n\t" // 2 cycles - "brne 1b" : "=w" (us) : "0" (us) // 2 cycles - ); -} - -void init() -{ - // this needs to be called before setup() or some functions won't work there - sei(); -} - -#endif -#endif - - -/**************************/ -/**************************/ -/** Interrupt routines **/ -/**************************/ -/**************************/ - -//PPM -#ifdef ENABLE_PPM -#ifdef XMEGA -ISR(PORTD_INT0_vect) -#else -#ifdef STM32_board -void PPM_decode() -#else -ISR(INT1_vect) -#endif -#endif -{ // Interrupt on PPM pin - static int8_t chan=-1; - static uint16_t Prev_TCNT1=0; - uint16_t Cur_TCNT1; - - #ifdef XMEGA - Cur_TCNT1 = TCC1.CNT - Prev_TCNT1 ; // Capture current Timer1 value - #else - #if defined STM32_board - uint16_t time=TIMER2_BASE->CNT; - Cur_TCNT1=time-Prev_TCNT1; // Capture current Timer1 value - #else - Cur_TCNT1=TCNT1-Prev_TCNT1; // Capture current Timer1 value - #endif - #endif - if(Cur_TCNT1<1000) - chan=-1; // bad frame - else - if(Cur_TCNT1>4840) - { - chan=0; // start of frame - PPM_FLAG_on; // full frame present (even at startup since PPM_data has been initialized) - } - else - if(chan!=-1) // need to wait for start of frame - { //servo values between 500us and 2420us will end up here - PPM_data[chan]= Cur_TCNT1>>1;; - if(chan++>=NUM_CHN) - chan=-1; // don't accept any new channels - } - Prev_TCNT1+=Cur_TCNT1; -} -#endif //ENABLE_PPM - - - -#ifdef ENABLE_SERIAL -//Serial RX -#ifdef XMEGA -ISR(USARTC0_RXC_vect) -#else -#if defined STM32_board -#ifdef __cplusplus -extern "C" { - #endif - void __irq_usart2() - #else - ISR(USART_RX_vect) - #endif - #endif - - { // RX interrupt - static uint8_t idx=0; - #ifdef XMEGA - if((USARTC0.STATUS & 0x1C)==0) // Check frame error, data overrun and parity error - #else - #ifndef STM32_board - UCSR0B &= ~_BV(RXCIE0) ; // RX interrupt disable - #endif - sei(); - #if defined STM32_board - if(USART2_BASE->SR & USART_SR_RXNE) { - if((USART2_BASE->SR &0x0F)==0) - #else - if((UCSR0A&0x1C)==0) // Check frame error, data overrun and parity error - #endif - #endif - { // received byte is ok to process - if(idx==0||discard_frame==1) - { // Let's try to sync at this point - idx=0;discard_frame=0; - #ifdef XMEGA - if(USARTC0.DATA==0x55) // If 1st byte is 0x55 it looks ok - - #else - #if defined STM32_board - if(USART2_BASE->DR==0x55) - #else - if(UDR0==0x55) // If 1st byte is 0x55 it looks ok - #endif - #endif - { - #ifdef XMEGA - TCC1.CCB = TCC1.CNT+(6500L) ; // Full message should be received within timer of 3250us - TCC1.INTFLAGS = TC1_CCBIF_bm ; // clear OCR1B match flag - TCC1.INTCTRLB = (TCC1.INTCTRLB & 0xF3) | 0x04 ; // enable interrupt on compare B match - - #else - #if defined STM32_board - uint16_t OCR1B = TIMER2_BASE->CNT; - OCR1B +=6500L; - timer.setCompare(TIMER_CH2,OCR1B); - timer.attachCompare2Interrupt(ISR_COMPB); - #else - OCR1B=TCNT1+6500L; // Full message should be received within timer of 3250us - TIFR1=(1<DR&0xff; // Store received byte - #else - rx_buff[(idx++)-1]=UDR0; // Store received byte - #endif - #endif - if(idx>RXBUFFER_SIZE) - { // A full frame has been received - - if(!IS_RX_DONOTUPDTAE_on) - { //Good frame received and main has finished with previous buffer - memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer - RX_FLAG_on; // flag for main to process servo data - } - else - RX_MISSED_BUFF_on; // notify that rx_buff is good - discard_frame=1; // start again - } - } - } - else - { - #ifdef XMEGA - idx = USARTC0.DATA ; // Dummy read - #else - #if defined STM32_board - idx=USART2_BASE->DR&0xff; - #else - idx=UDR0; // Dummy read - #endif - #endif - discard_frame=1; // Error encountered discard full frame... - } - - if(discard_frame==1) - { - #ifdef XMEGA - TCC1.INTCTRLB &=0xF3; // disable interrupt on compare B match - #else - #if defined STM32_board - detachInterrupt(2);//disable interrupt on ch2 - #else - TIMSK1 &=~(1<