mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-07-04 12:37:53 +00:00
Update Multiprotocol.ino
This commit is contained in:
parent
2c176e7bdd
commit
829a6ea50d
@ -39,6 +39,7 @@
|
|||||||
|
|
||||||
#include <avr/pgmspace.h>
|
#include <avr/pgmspace.h>
|
||||||
#include "_Config.h"
|
#include "_Config.h"
|
||||||
|
#include "TX_Def.h"
|
||||||
//Multiprotocol module configuration file
|
//Multiprotocol module configuration file
|
||||||
|
|
||||||
//Global constants/variables
|
//Global constants/variables
|
||||||
@ -59,6 +60,9 @@ uint8_t packet[40];
|
|||||||
uint16_t Servo_data[NUM_CHN];
|
uint16_t Servo_data[NUM_CHN];
|
||||||
uint8_t Servo_AUX;
|
uint8_t Servo_AUX;
|
||||||
|
|
||||||
|
#ifndef STM32_board
|
||||||
|
uint16_t servo_max_100,servo_min_100,servo_max_125,servo_min_125;
|
||||||
|
#endif
|
||||||
// Protocol variables
|
// Protocol variables
|
||||||
uint8_t cyrfmfg_id[6];//for dsm2 and devo
|
uint8_t cyrfmfg_id[6];//for dsm2 and devo
|
||||||
uint8_t rx_tx_addr[5];
|
uint8_t rx_tx_addr[5];
|
||||||
@ -122,18 +126,20 @@ uint8_t option;
|
|||||||
uint8_t cur_protocol[2];
|
uint8_t cur_protocol[2];
|
||||||
uint8_t prev_protocol=0;
|
uint8_t prev_protocol=0;
|
||||||
|
|
||||||
|
#ifdef STM32_board
|
||||||
void PPM_decode();
|
void PPM_decode();
|
||||||
void ISR_COMPB();
|
void ISR_COMPB();
|
||||||
|
#endif
|
||||||
// Telemetry
|
// Telemetry
|
||||||
#define MAX_PKT 27
|
#define MAX_PKT 27
|
||||||
uint8_t pkt[MAX_PKT];//telemetry receiving packets
|
uint8_t pkt[MAX_PKT];//telemetry receiving packets
|
||||||
#if defined(TELEMETRY)
|
#if defined(TELEMETRY)
|
||||||
#ifndef BASH_SERIAL
|
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_head=0;
|
||||||
volatile uint8_t tx_tail=0;
|
volatile uint8_t tx_tail=0;
|
||||||
#endif // BASH_SERIAL
|
#endif // BASH_SERIAL
|
||||||
uint8_t pktt[MAX_PKT];//telemetry receiving packets
|
|
||||||
uint8_t v_lipo;
|
uint8_t v_lipo;
|
||||||
int16_t RSSI_dBm;
|
int16_t RSSI_dBm;
|
||||||
uint8_t telemetry_link=0;
|
uint8_t telemetry_link=0;
|
||||||
@ -237,14 +243,20 @@ void setup()
|
|||||||
// Set servos positions
|
// Set servos positions
|
||||||
for(uint8_t i=0;i<NUM_CHN;i++)
|
for(uint8_t i=0;i<NUM_CHN;i++)
|
||||||
Servo_data[i]=1500;
|
Servo_data[i]=1500;
|
||||||
Servo_data[THROTTLE]=PPM_MIN_100;
|
Servo_data[THROTTLE]=servo_min_100;
|
||||||
|
#ifdef ENABLE_PPM
|
||||||
memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data));
|
memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data));
|
||||||
|
#endif
|
||||||
|
|
||||||
//Wait for every component to start
|
//Wait for every component to start
|
||||||
delay(100);
|
delayMilliseconds(100);
|
||||||
|
|
||||||
// Read status of bind button
|
// Read status of bind button
|
||||||
#ifdef XMEGA
|
// Read status of bind button
|
||||||
|
if( IS_BIND_BUTTON_on )
|
||||||
|
BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan
|
||||||
|
|
||||||
|
/* #ifdef XMEGA
|
||||||
if( (PORTD.IN & _BV(2)) == 0x00 )
|
if( (PORTD.IN & _BV(2)) == 0x00 )
|
||||||
#else
|
#else
|
||||||
# if defined STM32_board
|
# if defined STM32_board
|
||||||
@ -253,12 +265,10 @@ void setup()
|
|||||||
if( (PINB & _BV(5)) == 0x00 )
|
if( (PINB & _BV(5)) == 0x00 )
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan
|
*/
|
||||||
|
|
||||||
// Read status of mode select binary switch
|
// Read status of mode select binary switch
|
||||||
// after this mode_select will be one of {0000, 0001, ..., 1111}
|
// after this mode_select will be one of {0000, 0001, ..., 1111}
|
||||||
#ifdef XMEGA
|
#ifdef XMEGA
|
||||||
mode_select=0x0F - ( PORTA.IN & 0x0F ) ; //encoder dip switches 1,2,4,8=>B2,B3,B4,C0
|
|
||||||
mode_select = MODE_SERIAL ;
|
mode_select = MODE_SERIAL ;
|
||||||
#else
|
#else
|
||||||
#if defined STM32_board
|
#if defined STM32_board
|
||||||
@ -277,22 +287,15 @@ void setup()
|
|||||||
LED_SET_OUTPUT;
|
LED_SET_OUTPUT;
|
||||||
// Read or create protocol id
|
// Read or create protocol id
|
||||||
MProtocol_id_master=random_id(10,false);
|
MProtocol_id_master=random_id(10,false);
|
||||||
|
|
||||||
|
#ifdef STM32_board
|
||||||
initSPI2();
|
initSPI2();
|
||||||
|
#endif
|
||||||
//Init RF modules
|
//Init RF modules
|
||||||
#ifdef CC2500_INSTALLED
|
modules_reset();
|
||||||
CC2500_Reset();
|
|
||||||
#endif
|
|
||||||
#ifdef A7105_INSTALLED
|
|
||||||
A7105_Reset();
|
|
||||||
#endif
|
|
||||||
#ifdef CYRF6936_INSTALLED
|
|
||||||
CYRF_Reset();
|
|
||||||
#endif
|
|
||||||
#ifdef NFR24L01_INSTALLED
|
|
||||||
NRF24L01_Reset();
|
|
||||||
#endif
|
|
||||||
//LED_ON;
|
//LED_ON;
|
||||||
//Protocol and interrupts initialization
|
//Protocol and interrupts initialization
|
||||||
|
#ifdef ENABLE_PPM
|
||||||
if(mode_select != MODE_SERIAL)
|
if(mode_select != MODE_SERIAL)
|
||||||
{ // PPM
|
{ // PPM
|
||||||
mode_select--;
|
mode_select--;
|
||||||
@ -304,6 +307,10 @@ void setup()
|
|||||||
if(PPM_prot[mode_select].power) POWER_FLAG_on;
|
if(PPM_prot[mode_select].power) POWER_FLAG_on;
|
||||||
if(PPM_prot[mode_select].autobind) AUTOBIND_FLAG_on;
|
if(PPM_prot[mode_select].autobind) AUTOBIND_FLAG_on;
|
||||||
mode_select++;
|
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();
|
protocol_init();
|
||||||
|
|
||||||
@ -314,7 +321,7 @@ void setup()
|
|||||||
EIMSK |= (1<<INT1); // INT1 interrupt enable
|
EIMSK |= (1<<INT1); // INT1 interrupt enable
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if defined STM32_board
|
#ifdef STM32_board
|
||||||
attachInterrupt(PPM_pin,PPM_decode,FALLING);
|
attachInterrupt(PPM_pin,PPM_decode,FALLING);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -323,12 +330,16 @@ void setup()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
#endif
|
||||||
{ // Serial
|
{ // Serial
|
||||||
|
#ifdef ENABLE_SERIAL
|
||||||
cur_protocol[0]=0;
|
cur_protocol[0]=0;
|
||||||
cur_protocol[1]=0;
|
cur_protocol[1]=0;
|
||||||
prev_protocol=0;
|
prev_protocol=0;
|
||||||
|
servo_max_100=SERIAL_MAX_100; servo_min_100=SERIAL_MIN_100;
|
||||||
|
servo_max_125=SERIAL_MAX_125; servo_min_125=SERIAL_MIN_125;
|
||||||
Mprotocol_serial_init(); // Configure serial and enable RX interrupt
|
Mprotocol_serial_init(); // Configure serial and enable RX interrupt
|
||||||
|
#endif //ENABLE_SERIAL
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -524,6 +535,15 @@ static void protocol_init()
|
|||||||
remote_callback = 0;
|
remote_callback = 0;
|
||||||
|
|
||||||
set_rx_tx_addr(MProtocol_id);
|
set_rx_tx_addr(MProtocol_id);
|
||||||
|
// reset telemetry
|
||||||
|
#ifdef TELEMETRY
|
||||||
|
tx_pause();
|
||||||
|
pass=0;
|
||||||
|
telemetry_link=0;
|
||||||
|
tx_tail=0;
|
||||||
|
tx_head=0;
|
||||||
|
#endif
|
||||||
|
|
||||||
blink=millis();
|
blink=millis();
|
||||||
if(IS_BIND_BUTTON_FLAG_on)
|
if(IS_BIND_BUTTON_FLAG_on)
|
||||||
AUTOBIND_FLAG_on;
|
AUTOBIND_FLAG_on;
|
||||||
@ -586,6 +606,21 @@ static void protocol_init()
|
|||||||
#endif
|
#endif
|
||||||
#if defined(DEVO_CYRF6936_INO)
|
#if defined(DEVO_CYRF6936_INO)
|
||||||
case MODE_DEVO:
|
case MODE_DEVO:
|
||||||
|
#ifdef ENABLE_PPM
|
||||||
|
if(mode_select) //PPM mode
|
||||||
|
{
|
||||||
|
if(IS_BIND_BUTTON_FLAG_on)
|
||||||
|
{
|
||||||
|
eeprom_write_byte((uint8_t*)(30+mode_select),0x00); // reset to autobind mode for the current model
|
||||||
|
option=0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
option=eeprom_read_byte((uint8_t*)(30+mode_select)); // load previous mode: autobind or fixed id
|
||||||
|
if(option!=1) option=0; // if not fixed id mode then it should be autobind
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif //ENABLE_PPM
|
||||||
CTRL2_on; //antenna RF4
|
CTRL2_on; //antenna RF4
|
||||||
next_callback = DevoInit();
|
next_callback = DevoInit();
|
||||||
remote_callback = devo_callback;
|
remote_callback = devo_callback;
|
||||||
@ -729,16 +764,8 @@ static void protocol_init()
|
|||||||
|
|
||||||
static void update_serial_data()
|
static void update_serial_data()
|
||||||
{
|
{
|
||||||
RX_FLAG_off; //data has been processed
|
|
||||||
|
|
||||||
do
|
|
||||||
{
|
|
||||||
cli();
|
|
||||||
if(IS_RX_MISSED_BUFF_on) // If the buffer is still valid
|
|
||||||
memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
|
|
||||||
sei();
|
|
||||||
RX_MISSED_BUFF_off;
|
|
||||||
RX_DONOTUPDTAE_on;
|
RX_DONOTUPDTAE_on;
|
||||||
|
RX_FLAG_off; //data has been processed
|
||||||
if(rx_ok_buff[0]&0x20) //check range
|
if(rx_ok_buff[0]&0x20) //check range
|
||||||
RANGE_FLAG_on;
|
RANGE_FLAG_on;
|
||||||
else
|
else
|
||||||
@ -766,6 +793,7 @@ static void update_serial_data()
|
|||||||
else
|
else
|
||||||
if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set
|
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
|
CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind
|
||||||
|
else
|
||||||
cur_protocol[0] = rx_ok_buff[0]; //store current protocol
|
cur_protocol[0] = rx_ok_buff[0]; //store current protocol
|
||||||
|
|
||||||
// decode channel values
|
// decode channel values
|
||||||
@ -783,36 +811,54 @@ static void update_serial_data()
|
|||||||
Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125%
|
Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125%
|
||||||
}
|
}
|
||||||
RX_DONOTUPDTAE_off;
|
RX_DONOTUPDTAE_off;
|
||||||
|
|
||||||
|
#ifdef XMEGA
|
||||||
|
cli();
|
||||||
|
#else
|
||||||
|
#ifdef STM32_board
|
||||||
|
//here code fro RX intrurpt disable
|
||||||
|
USART3_BASE->CR1 &= ~ USART_CR1_RXIE;//disable
|
||||||
|
#else
|
||||||
|
UCSR0B &= ~(1<<RXCIE0); // RX interrupt disable
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
if(IS_RX_MISSED_BUFF_on) // If the buffer is still valid
|
||||||
|
{ memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
|
||||||
|
RX_FLAG_on; // data to be processed next time...
|
||||||
|
RX_MISSED_BUFF_off;
|
||||||
}
|
}
|
||||||
while(IS_RX_MISSED_BUFF_on); // We've just processed an old frame...
|
#ifdef XMEGA
|
||||||
|
sei();
|
||||||
|
#else
|
||||||
|
#ifdef STM32_board
|
||||||
|
//here code fro RX intrurpt enable
|
||||||
|
USART3_BASE->CR1 |= USART_CR1_RXIE;//disable
|
||||||
|
#else
|
||||||
|
UCSR0B |= (1<<RXCIE0) ; // RX interrupt enable
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void module_reset()
|
void modules_reset()
|
||||||
{
|
{
|
||||||
if(remote_callback)
|
#ifdef CC2500_INSTALLED
|
||||||
{ // previous protocol loaded
|
|
||||||
remote_callback = 0;
|
|
||||||
switch(prev_protocol)
|
|
||||||
{
|
|
||||||
case MODE_FLYSKY:
|
|
||||||
case MODE_HUBSAN:
|
|
||||||
A7105_Reset();
|
|
||||||
break;
|
|
||||||
case MODE_FRSKY:
|
|
||||||
case MODE_FRSKYX:
|
|
||||||
case MODE_SFHSS:
|
|
||||||
CC2500_Reset();
|
CC2500_Reset();
|
||||||
break;
|
#endif
|
||||||
case MODE_DSM2:
|
#ifdef A7105_INSTALLED
|
||||||
case MODE_DEVO:
|
A7105_Reset();
|
||||||
|
#endif
|
||||||
|
#ifdef CYRF6936_INSTALLED
|
||||||
CYRF_Reset();
|
CYRF_Reset();
|
||||||
break;
|
#endif
|
||||||
default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI, MODE_FY326
|
#ifdef NFR24L01_INSTALLED
|
||||||
NRF24L01_Reset();
|
NRF24L01_Reset();
|
||||||
break;
|
#endif
|
||||||
}
|
|
||||||
}
|
//Wait for every component to reset
|
||||||
|
delayMilliseconds(100);
|
||||||
|
prev_power=0xFD; // unused power value
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef STM32_board
|
#ifndef STM32_board
|
||||||
int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max)
|
int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max)
|
||||||
{
|
{
|
||||||
@ -828,13 +874,13 @@ int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t
|
|||||||
// Channel value is converted to 8bit values full scale
|
// Channel value is converted to 8bit values full scale
|
||||||
uint8_t convert_channel_8b(uint8_t num)
|
uint8_t convert_channel_8b(uint8_t num)
|
||||||
{
|
{
|
||||||
return (uint8_t) (map(limit_channel_100(num),PPM_MIN_100,PPM_MAX_100,0,255));
|
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,0,255));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Channel value is converted to 8bit values to provided values scale
|
// Channel value is converted to 8bit values to provided values scale
|
||||||
uint8_t convert_channel_8b_scale(uint8_t num,uint8_t min,uint8_t max)
|
uint8_t convert_channel_8b_scale(uint8_t num,uint8_t min,uint8_t max)
|
||||||
{
|
{
|
||||||
return (uint8_t) (map(limit_channel_100(num),PPM_MIN_100,PPM_MAX_100,min,max));
|
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,min,max));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Channel value is converted sign + magnitude 8bit values
|
// Channel value is converted sign + magnitude 8bit values
|
||||||
@ -848,7 +894,7 @@ uint8_t convert_channel_s8b(uint8_t num)
|
|||||||
// Channel value is converted to 10bit values
|
// Channel value is converted to 10bit values
|
||||||
uint16_t convert_channel_10b(uint8_t num)
|
uint16_t convert_channel_10b(uint8_t num)
|
||||||
{
|
{
|
||||||
return (uint16_t) (map(limit_channel_100(num),PPM_MIN_100,PPM_MAX_100,1,1023));
|
return (uint16_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,1,1023));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Channel value is multiplied by 1.5
|
// Channel value is multiplied by 1.5
|
||||||
@ -868,11 +914,11 @@ void convert_channel_HK310(uint8_t num, uint8_t *low, uint8_t *high)
|
|||||||
// Channel value is limited to PPM_100
|
// Channel value is limited to PPM_100
|
||||||
uint16_t limit_channel_100(uint8_t ch)
|
uint16_t limit_channel_100(uint8_t ch)
|
||||||
{
|
{
|
||||||
if(Servo_data[ch]>PPM_MAX_100)
|
if(Servo_data[ch]>servo_max_100)
|
||||||
return PPM_MAX_100;
|
return servo_max_100;
|
||||||
else
|
else
|
||||||
if (Servo_data[ch]<PPM_MIN_100)
|
if (Servo_data[ch]<servo_min_100)
|
||||||
return PPM_MIN_100;
|
return servo_min_100;
|
||||||
return Servo_data[ch];
|
return Servo_data[ch];
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1069,6 +1115,7 @@ void init()
|
|||||||
/**************************/
|
/**************************/
|
||||||
|
|
||||||
//PPM
|
//PPM
|
||||||
|
#ifdef ENABLE_PPM
|
||||||
#ifdef XMEGA
|
#ifdef XMEGA
|
||||||
ISR(PORTD_INT0_vect)
|
ISR(PORTD_INT0_vect)
|
||||||
#else
|
#else
|
||||||
@ -1104,16 +1151,13 @@ void init()
|
|||||||
else
|
else
|
||||||
if(chan!=-1) // need to wait for start of frame
|
if(chan!=-1) // need to wait for start of frame
|
||||||
{ //servo values between 500us and 2420us will end up here
|
{ //servo values between 500us and 2420us will end up here
|
||||||
uint16_t a = Cur_TCNT1>>1;
|
PPM_data[chan]= Cur_TCNT1>>1;;
|
||||||
if(a<PPM_MIN) a=PPM_MIN;
|
|
||||||
else if(a>PPM_MAX) a=PPM_MAX;
|
|
||||||
PPM_data[chan]=a;
|
|
||||||
if(chan++>=NUM_CHN)
|
if(chan++>=NUM_CHN)
|
||||||
chan=-1; // don't accept any new channels
|
chan=-1; // don't accept any new channels
|
||||||
}
|
}
|
||||||
Prev_TCNT1+=Cur_TCNT1;
|
Prev_TCNT1+=Cur_TCNT1;
|
||||||
}
|
}
|
||||||
|
#endif //ENABLE_PPM
|
||||||
//Serial RX
|
//Serial RX
|
||||||
#ifdef XMEGA
|
#ifdef XMEGA
|
||||||
ISR(USARTC0_RXC_vect)
|
ISR(USARTC0_RXC_vect)
|
||||||
@ -1157,7 +1201,6 @@ void init()
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
idx++;
|
|
||||||
#ifdef XMEGA
|
#ifdef XMEGA
|
||||||
TCC1.CCB = TCC1.CNT+(6500L) ; // Full message should be received within timer of 3250us
|
TCC1.CCB = TCC1.CNT+(6500L) ; // Full message should be received within timer of 3250us
|
||||||
TCC1.INTFLAGS = TC1_CCBIF_bm ; // clear OCR1B match flag
|
TCC1.INTFLAGS = TC1_CCBIF_bm ; // clear OCR1B match flag
|
||||||
@ -1175,6 +1218,7 @@ void init()
|
|||||||
TIMSK1 |=(1<<OCIE1B); // enable interrupt on compare B match
|
TIMSK1 |=(1<<OCIE1B); // enable interrupt on compare B match
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
idx++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@ -1194,16 +1238,7 @@ void init()
|
|||||||
#endif
|
#endif
|
||||||
if(idx>RXBUFFER_SIZE)
|
if(idx>RXBUFFER_SIZE)
|
||||||
{ // A full frame has been received
|
{ // A full frame has been received
|
||||||
#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<<OCIE1B); // disable interrupt on compare B match
|
|
||||||
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
if(!IS_RX_DONOTUPDTAE_on)
|
if(!IS_RX_DONOTUPDTAE_on)
|
||||||
{ //Good frame received and main has finished with previous buffer
|
{ //Good frame received and main has finished with previous buffer
|
||||||
memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
|
memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
|
||||||
@ -1229,6 +1264,20 @@ void init()
|
|||||||
discard_frame=1; // Error encountered discard full frame...
|
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<<OCIE1B); // disable interrupt on compare B match
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
#if defined STM32_board //If activated telemetry it doesn't work activated
|
#if defined STM32_board //If activated telemetry it doesn't work activated
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -1246,11 +1295,22 @@ void init()
|
|||||||
#if defined STM32_board
|
#if defined STM32_board
|
||||||
void ISR_COMPB()
|
void ISR_COMPB()
|
||||||
#else
|
#else
|
||||||
ISR(TIMER1_COMPB_vect)
|
ISR(TIMER1_COMPB_vect,ISR_NOBLOCK)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ // Timer1 compare B interrupt
|
{ // Timer1 compare B interrupt
|
||||||
discard_frame=1; // Error encountered discard full frame...
|
discard_frame=1; // Error encountered discard full frame...
|
||||||
|
#ifdef XMEGA
|
||||||
|
TCC1.INTCTRLB &=0xF3; // Disable interrupt on compare B match
|
||||||
|
#else
|
||||||
|
#ifdef STM32_board
|
||||||
|
detachInterrupt(2);//disable interrupt on ch2
|
||||||
|
#else
|
||||||
|
TIMSK1 &=~(1<<OCIE1B); // Disable interrupt on compare B match
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif //ENABLE_SERIAL
|
||||||
|
Loading…
x
Reference in New Issue
Block a user