Compare commits

..

31 Commits

Author SHA1 Message Date
pascallanger
23478d3d21 Update Protocols_Details.md 2020-05-08 22:50:52 +02:00
Pascal Langer
ba72b6dedd eSky150v2 last minute typo... 2020-05-08 20:01:33 +02:00
Pascal Langer
103f595891 New protocol eSky 150 v2
Protocol: 69
No sub protocol
No extended limit
RX outputs is be set automatically to the eSky default TAER
16 channels
2020-05-08 19:55:16 +02:00
Pascal Langer
957d623b4b FrSky D16 LBT v1.x & 2.1: adjust thresholds to match ETSI requirements 2020-05-02 18:20:47 +02:00
Pascal Langer
2be757e609 Skyartec: small changes 2020-04-22 15:02:06 +02:00
Pascal Langer
c4be660a05 Skyartec: activate cc2500 rf tune 2020-04-21 18:27:15 +02:00
Pascal Langer
c1c5f9fe3a Hide Proto Scanner 2020-04-21 12:15:53 +02:00
Pascal Langer
53c0637a85 Fix a bug introduced with Alpha protocols ordering 2020-04-21 11:43:48 +02:00
Pascal Langer
4ae30dc3b0 New protocol: Skyartec 2020-04-18 19:04:38 +02:00
Pascal Langer
fc5fbc9899 Multi_Names update for OpenTX 2020-04-16 17:03:17 +02:00
Pascal Langer
2397bf365b Update Multi_Names.ino 2020-04-16 13:52:10 +02:00
Pascal Langer
42cd17d5f2 Multi Names: if proto invalid give first available proto 2020-04-16 12:07:19 +02:00
Pascal Langer
a35e01bbeb Update Protocols_Details.md 2020-04-15 11:23:40 +02:00
Pascal Langer
b21e8030b3 Fix independant protocols build 2020-04-15 01:30:06 +02:00
Pascal Langer
0984a42fe5 Update Protocols_Details.md 2020-04-13 22:42:41 +02:00
Pascal Langer
ed50d60108 Update Protocols_Details.md 2020-04-13 22:41:37 +02:00
Pascal Langer
a7f72a73e5 Update Protocols_Details.md 2020-04-13 22:31:26 +02:00
Pascal Langer
1c02cb46f5 FrSky Clone mode
Check documentation for full details: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md#FRSKY_RX---55
2020-04-13 22:10:58 +02:00
Pascal Langer
da8fd21177 Update FrSkyL_cc2500.ino 2020-04-11 20:17:02 +02:00
Pascal Langer
7e5cd9819a New protocol FrSkyL: LR12
Model: L9R RX
2 sub protocols: LR12 and LR12_6CH
2020-04-11 20:09:32 +02:00
Pascal Langer
00aecb3ab1 Update Protocols_Details.md 2020-04-10 19:38:49 +02:00
Pascal Langer
cde77a88fd FrSkyRX: added sub_protocol, documentation and more 2020-04-10 19:32:50 +02:00
E1yot
08a555f187 Initial Version of CloneMode (#342)
* Initial Version

* Bugfix and change of the handling of the RX Num.

If RX Num is 63, write a finetune value of 127 to the EEPROM.
A real finetune value of 127 means, the frequency of module is out of range and
the module should be replaced. This way the clone mode should not get unwanted
active by a module with a frequency drift arround 63.
2020-04-10 19:01:01 +02:00
Pascal Langer
4039cbf8af Small corrections 2020-04-07 10:55:54 +02:00
Pascal Langer
3f652fa06c FrSkyX: improve SPort to RX code 2020-04-07 01:43:05 +02:00
Pascal Langer
272d2be3ae Update FrSky_Rx_cc2500.ino 2020-04-05 16:05:51 +02:00
Pascal Langer
7e461344a8 Update Protocols_Details.md 2020-04-05 10:46:26 +02:00
Pascal Langer
8af985a2cb FrSkyRX: check additional ID and use RX num 2020-04-05 10:44:09 +02:00
Pascal Langer
08eee34446 Protocol PROPEL: enhanced telemetry 2020-04-05 09:39:33 +02:00
Pascal Langer
0a5b97a177 New Protocol: PROPEL
Compatible model: PROPEL 74-Z Speeder Bike
Protcol: PROPEL (66)
Sub protocol: none
Autobind protocol
Extended limits not supported
Telemetry supported
14 channels in use due to many features
2020-04-03 19:36:05 +02:00
Bryce Johnson
cab782b38e redpine updates to make released betaflight and deviation builds (#341)
Co-authored-by: Bryce Johnson <bryce@redpinelabs.com>
2020-04-02 12:39:26 +02:00
21 changed files with 2108 additions and 632 deletions

View File

@@ -150,6 +150,11 @@ void CC2500_SetPower()
#else
power=CC2500_HIGH_POWER;
#endif
if(IS_LBT_POWER_on)
{
power=CC2500_LBT_POWER;
LBT_POWER_off; // Only accept once
}
if(IS_RANGE_FLAG_on)
power=CC2500_RANGE_POWER;
if(prev_power != power)

View File

@@ -143,10 +143,10 @@ uint16_t convert_channel_frsky(uint8_t num)
// 0-2047, 0 = 817, 1024 = 1500, 2047 = 2182
//64=860,1024=1500,1984=2140//Taranis 125%
static uint16_t __attribute__((unused)) FrSkyX_scaleForPXX( uint8_t i )
static uint16_t __attribute__((unused)) FrSkyX_scaleForPXX( uint8_t i, uint8_t num_chan=8)
{ //mapped 860,2140(125%) range to 64,1984(PXX values);
uint16_t chan_val=convert_channel_frsky(i)-1226;
if(i>7) chan_val|=2048; // upper channels offset
if(i>=num_chan) chan_val|=2048; // upper channels offset
return chan_val;
}

View File

@@ -0,0 +1,141 @@
/*
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 <http://www.gnu.org/licenses/>.
*/
#if defined(ESKY150V2_CC2500_INO)
#include "iface_nrf250k.h"
//#define ESKY150V2_FORCE_ID
#define ESKY150V2_PAYLOADSIZE 40
#define ESKY150V2_BINDPAYLOADSIZE 150
#define ESKY150V2_NFREQCHANNELS 70
#define ESKY150V2_TXID_SIZE 4
#define ESKY150V2_BIND_CHANNEL 0x00
#define ESKY150V2_PACKET_PERIOD 10000
#define ESKY150V2_BINDING_PACKET_PERIOD 57000
#ifdef ESKY150V2_FORCE_ID
const uint8_t PROGMEM ESKY150V2_hop[ESKY150V2_NFREQCHANNELS]= {
0x07, 0x47, 0x09, 0x27, 0x0B, 0x42, 0x0D, 0x35, 0x17, 0x40, 0x26, 0x3D, 0x16, 0x43, 0x06, 0x2A, 0x24, 0x44,
0x0E, 0x38, 0x20, 0x48, 0x22, 0x2D, 0x2B, 0x39, 0x0F, 0x36, 0x23, 0x46, 0x14, 0x3B, 0x1A, 0x41, 0x10, 0x2E,
0x1E, 0x28, 0x0C, 0x49, 0x1D, 0x3E, 0x29, 0x2C, 0x25, 0x30, 0x1C, 0x2F, 0x1B, 0x33, 0x13, 0x31, 0x0A, 0x37,
0x12, 0x3C, 0x18, 0x4B, 0x11, 0x45, 0x21, 0x4A, 0x1F, 0x3F, 0x15, 0x32, 0x08, 0x3A, 0x19, 0x34 };
/*const uint8_t PROGMEM ESKY150V2_hop2[40]= {
0x19, 0x23, 0x13, 0x1B, 0x09, 0x22, 0x14, 0x27, 0x06, 0x26, 0x16, 0x24, 0x0B, 0x2A, 0x0E, 0x1C, 0x11, 0x1E,
0x08, 0x29, 0x0D, 0x28, 0x18, 0x2D, 0x12, 0x20, 0x0C, 0x1A, 0x10, 0x1D, 0x07, 0x2C, 0x0A, 0x2B, 0x0F, 0x25,
0x15, 0x1F, 0x17, 0x21 };*/
#endif
static void __attribute__((unused)) ESKY150V2_set_freq(void)
{
calc_fh_channels(ESKY150V2_NFREQCHANNELS);
#ifdef ESKY150V2_FORCE_ID
for(uint8_t i=0; i<ESKY150V2_NFREQCHANNELS; i++)
hopping_frequency[i]=pgm_read_byte_near( &ESKY150V2_hop[i] );
#endif
//Bind channel
hopping_frequency[ESKY150V2_NFREQCHANNELS]=ESKY150V2_BIND_CHANNEL;
//Calib all channels
NRF250K_SetFreqOffset(); // Set frequency offset
NRF250K_HoppingCalib(ESKY150V2_NFREQCHANNELS+1);
}
static void __attribute__((unused)) ESKY150V2_send_packet()
{
NRF250K_SetFreqOffset(); // Set frequency offset
NRF250K_Hopping(hopping_frequency_no);
if (++hopping_frequency_no >= ESKY150V2_NFREQCHANNELS)
hopping_frequency_no = 0;
NRF250K_SetPower(); //Set power level
packet[0] = 0xFA; // Unknown
packet[1] = 0x41; // Unknown
packet[2] = 0x08; // Unknown
packet[3] = 0x00; // Unknown
for(uint8_t i=0;i<16;i++)
{
uint16_t channel=convert_channel_16b_limit(CH_TAER[i],200,1000);
packet[4+2*i] = channel;
packet[5+2*i] = channel>>8;
}
NRF250K_WritePayload(packet, ESKY150V2_PAYLOADSIZE);
}
uint16_t ESKY150V2_callback()
{
if(option==0) option=1; //Trick the RF component auto select system
if(IS_BIND_DONE)
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(ESKY150V2_PACKET_PERIOD);
#endif
ESKY150V2_send_packet();
}
else
{
BIND_DONE; //Need full power for bind to work...
NRF250K_SetPower(); //Set power level
BIND_IN_PROGRESS;
NRF250K_WritePayload(packet, ESKY150V2_BINDPAYLOADSIZE);
if (--bind_counter == 0)
{
BIND_DONE;
// Change TX address from bind to normal mode
NRF250K_SetTXAddr(rx_tx_addr, ESKY150V2_TXID_SIZE);
memset(packet,0x00,ESKY150V2_PAYLOADSIZE);
}
return 30000; //ESKY150V2_BINDING_PACKET_PERIOD;
}
return ESKY150V2_PACKET_PERIOD;
}
uint16_t initESKY150V2()
{
if(option==0) option=1; // Trick the RF component auto select system
NRF250K_Init();
ESKY150V2_set_freq();
hopping_frequency_no = 0;
#ifdef ESKY150V2_FORCE_ID // ID taken from TX dump
rx_tx_addr[0]=0x87;rx_tx_addr[1]=0x5B;rx_tx_addr[2]=0x2C;rx_tx_addr[3]=0x5D;
#endif
memset(packet,0x00,ESKY150V2_BINDPAYLOADSIZE);
if(IS_BIND_IN_PROGRESS)
{
NRF250K_SetTXAddr((uint8_t *)"\x73\x73\x74\x63", ESKY150V2_TXID_SIZE); //Bind address
NRF250K_Hopping(ESKY150V2_NFREQCHANNELS); //Bind channel
memcpy(packet,"\x73\x73\x74\x63", ESKY150V2_TXID_SIZE);
memcpy(&packet[ESKY150V2_TXID_SIZE],rx_tx_addr, ESKY150V2_TXID_SIZE);
packet[8]=0x41; //Unknown
packet[9]=0x88; //Unknown
packet[10]=0x41; //Unknown
memset(&packet[11],0xAA,4); //Unknown
memcpy(&packet[15],hopping_frequency,ESKY150V2_NFREQCHANNELS); // hop table
//for(uint8_t i=0; i<40; i++) // Does not seem to be needed
// packet[i+85]=pgm_read_byte_near( &ESKY150V2_hop2[i] );
bind_counter=100;
}
else
NRF250K_SetTXAddr(rx_tx_addr, ESKY150V2_TXID_SIZE);
return 50000;
}
#endif

View File

@@ -17,7 +17,7 @@
/** FrSky D and X routines **/
/******************************/
#if defined(FRSKYX_CC2500_INO) || defined(FRSKY_RX_CC2500_INO) || defined(FRSKYR9_SX1276_INO)
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO) || defined(FRSKY_RX_CC2500_INO) || defined(FRSKYR9_SX1276_INO)
//**CRC**
const uint16_t PROGMEM FrSkyX_CRC_Short[]={
0x0000, 0x1189, 0x2312, 0x329B, 0x4624, 0x57AD, 0x6536, 0x74BF,
@@ -29,9 +29,9 @@ static uint16_t __attribute__((unused)) FrSkyX_CRCTable(uint8_t val)
val /= 16 ;
return word ^ (0x1081 * val) ;
}
uint16_t FrSkyX_crc(uint8_t *data, uint8_t len)
uint16_t FrSkyX_crc(uint8_t *data, uint8_t len, uint8_t init=0)
{
uint16_t crc = 0;
uint16_t crc = init;
for(uint8_t i=0; i < len; i++)
crc = (crc<<8) ^ FrSkyX_CRCTable((uint8_t)(crc>>8) ^ *data++);
return crc;
@@ -39,7 +39,7 @@ uint16_t FrSkyX_crc(uint8_t *data, uint8_t len)
#endif
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO) || defined(FRSKY_RX_CC2500_INO)
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
@@ -50,6 +50,8 @@ enum {
FRSKY_DATA5,
};
uint8_t FrSkyFormat=0;
void Frsky_init_hop(void)
{
uint8_t val;
@@ -86,15 +88,14 @@ void FrSkyX2_init_hop(void)
{
channel = 5 * (uint16_t(inc * i) % 47) + offset;
//Exception list from dumps
if(sub_protocol & 2 )// LBT or FCC
{
//LBT
if(FrSkyFormat & 2 )// LBT or FCC
{//LBT
if( channel <=1 || channel == 43 || channel == 44 || channel == 87 || channel == 88 || channel == 129 || channel == 130 || channel == 173 || channel == 174)
channel += 2;
else if( channel == 216 || channel == 217 || channel == 218)
channel += 3;
}
else // FCC
else //FCC
if ( channel == 3 || channel == 4 || channel == 46 || channel == 47 || channel == 90 || channel == 91 || channel == 133 || channel == 134 || channel == 176 || channel == 177 || channel == 220 || channel == 221 )
channel += 2;
//Store
@@ -105,11 +106,38 @@ void FrSkyX2_init_hop(void)
hopping_frequency[47] = 0; //Bind freq
}
void Frsky_init_clone(void)
{
debugln("Clone mode");
uint16_t temp = FRSKYD_CLONE_EEPROM_OFFSET;
if(protocol==PROTO_FRSKYX)
temp=FRSKYX_CLONE_EEPROM_OFFSET;
else if(protocol==PROTO_FRSKYX2)
temp=FRSKYX2_CLONE_EEPROM_OFFSET;
FrSkyFormat=eeprom_read_byte((EE_ADDR)temp++);
if(protocol==PROTO_FRSKYX)
FrSkyFormat >>= 1;
else
FrSkyFormat >>= 2;
FrSkyFormat <<= 1; //FCC_16/LBT_16
rx_tx_addr[3] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[2] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[1] = eeprom_read_byte((EE_ADDR)temp++);
memset(hopping_frequency,0x00,50);
if(protocol!=PROTO_FRSKYX2)
{//D8 and D16v1
for (uint8_t ch = 0; ch < 47; ch++)
hopping_frequency[ch] = eeprom_read_byte((EE_ADDR)temp++);
}
else
FrSkyX2_init_hop();
}
#endif
/******************************/
/** FrSky V, D and X routines **/
/******************************/
#if defined(FRSKYV_CC2500_INO) || defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
#if defined(FRSKYV_CC2500_INO) || defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO)
const PROGMEM uint8_t FRSKY_common_startreg_cc2500_conf[]= {
CC2500_02_IOCFG0 ,
CC2500_00_IOCFG2 ,
@@ -177,7 +205,7 @@ void FrSkyX2_init_hop(void)
/*15_DEVIATN*/ 0x42 };
#endif
#if defined(FRSKYX_CC2500_INO)
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO)
const PROGMEM uint8_t FRSKYX_cc2500_conf[]= {
//FRSKYX
/*02_IOCFG0*/ 0x06 ,
@@ -219,6 +247,26 @@ void FrSkyX2_init_hop(void)
/*13_MDMCFG1*/ 0x23 ,
/*14_MDMCFG0*/ 0x7a ,
/*15_DEVIATN*/ 0x53 };
const PROGMEM uint8_t FRSKYL_cc2500_conf[]= {
/*02_IOCFG0*/ 0x02 ,
/*00_IOCFG2*/ 0x02 ,
/*17_MCSM1*/ 0x0C ,
/*18_MCSM0*/ 0x18 ,
/*06_PKTLEN*/ 0xFF ,
/*07_PKTCTRL1*/ 0x00 ,
/*08_PKTCTRL0*/ 0x02 ,
/*3E_PATABLE*/ 0xFE ,
/*0B_FSCTRL1*/ 0x0A ,
/*0C_FSCTRL0*/ 0x00 ,
/*0D_FREQ2*/ 0x5c ,
/*0E_FREQ1*/ 0x76 ,
/*0F_FREQ0*/ 0x27 ,
/*10_MDMCFG4*/ 0x5C ,
/*11_MDMCFG3*/ 0x3B ,
/*12_MDMCFG2*/ 0x00 ,
/*13_MDMCFG1*/ 0x03 ,
/*14_MDMCFG0*/ 0x7A ,
/*15_DEVIATN*/ 0x47 };
#endif
const PROGMEM uint8_t FRSKY_common_end_cc2500_conf[][2]= {
@@ -263,7 +311,7 @@ void FrSkyX2_init_hop(void)
}
#endif
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYX2_CC2500_INO)
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO)
uint8_t FrSkyX_chanskip;
uint8_t FrSkyX_TX_Seq, FrSkyX_TX_IN_Seq;
uint8_t FrSkyX_RX_Seq ;
@@ -289,11 +337,14 @@ static void __attribute__((unused)) FrSkyX_set_start(uint8_t ch )
static void __attribute__((unused)) FrSkyX_init()
{
FRSKY_init_cc2500((sub_protocol&2)?FRSKYXEU_cc2500_conf:FRSKYX_cc2500_conf); // LBT or FCC
if(protocol==PROTO_FRSKYL)
FRSKY_init_cc2500(FRSKYL_cc2500_conf);
else
FRSKY_init_cc2500((FrSkyFormat&2)?FRSKYXEU_cc2500_conf:FRSKYX_cc2500_conf); // LBT or FCC
if(protocol==PROTO_FRSKYX2)
{
CC2500_WriteReg(CC2500_08_PKTCTRL0, 0x05); // Enable CRC
if(!(sub_protocol&2))
if(!(FrSkyFormat&2))
{ // FCC
CC2500_WriteReg(CC2500_17_MCSM1, 0x0E); // Go/Stay in RX mode
CC2500_WriteReg(CC2500_11_MDMCFG3, 0x84); // bitrate 70K->77K

View File

@@ -97,6 +97,9 @@ static void __attribute__((unused)) frsky2way_data_frame()
uint16_t initFrSky_2way()
{
//FrskyD init hop
if (sub_protocol==DCLONE)
Frsky_init_clone();
else
for(uint8_t i=0;i<50;i++)
{
uint8_t freq = (i * 0x1e) % 0xeb;

View File

@@ -0,0 +1,262 @@
/*
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 <http://www.gnu.org/licenses/>.
*/
#if defined(FRSKYL_CC2500_INO)
#include "iface_cc2500.h"
//#define FRSKYL_FORCE_ID
#define FRSKYL_PACKET_LEN 256
#define FRSKYL_PERIOD 18000
uint8_t FrSkyL_buffer[FRSKYL_PACKET_LEN];
static void __attribute__((unused)) FrSkyL_build_bind_packet()
{
//Header
packet[0] = 0x4E; // Unknown but constant
//Bind packet
memset(&packet[1],0x00,3);
//ID
packet[4 ] = rx_tx_addr[3]; // ID
packet[5 ] = rx_tx_addr[2]; // ID
int idx = ((state -FRSKY_BIND) % 10) * 5;
packet[6 ] = idx;
packet[7 ] = hopping_frequency[idx++];
packet[8 ] = hopping_frequency[idx++];
packet[9 ] = hopping_frequency[idx++];
packet[10] = hopping_frequency[idx++];
packet[11] = hopping_frequency[idx++];
packet[12] = rx_tx_addr[1]; // ID or hw ver?
packet[13] = RX_num;
packet[14] = 0x00; // Unknown but constant
//CRC
uint16_t lcrc = FrSkyX_crc(&packet[1], 14);
packet[15] = lcrc >> 8;
packet[16] = lcrc;
//Debug
/* debug("Bind:");
for(uint8_t i=0;i<17;i++)
debug(" %02X",packet[i]);
debugln("");*/
}
static void __attribute__((unused)) FrSkyL_build_packet()
{
static uint8_t chan_offset=0;
uint16_t chan_0,chan_1;
//Header
packet[0 ] = 0x4E; // Unknown but constant
//ID
packet[1 ] = rx_tx_addr[3]; // ID
packet[2 ] = rx_tx_addr[2]; // ID
packet[3 ] = rx_tx_addr[1]; // ID or hw ver?
//skip_hop
packet[4 ] = (FrSkyX_chanskip<<6)|hopping_frequency_no;
packet[5 ] = FrSkyX_chanskip>>2;
//Channels
uint8_t startChan = chan_offset;
for(uint8_t i = 0; i <9 ; i+=3)
{//9 bytes of channel data
chan_0 = FrSkyX_scaleForPXX(startChan,6);
startChan++;
//
chan_1 = FrSkyX_scaleForPXX(startChan,6);
startChan++;
//
packet[6+i] = lowByte(chan_0); //3 bytes*4
packet[6+i+1]=(((chan_0>>8) & 0x0F)|(chan_1 << 4));
packet[6+i+2]=chan_1>>4;
}
if(sub_protocol & 0x01 ) //6ch mode only??
chan_offset = 0 ;
else
chan_offset^=0x06;
//CRC
uint16_t lcrc = FrSkyX_crc(&packet[1], 14, RX_num);
packet[15] = lcrc >> 8;
packet[16] = lcrc;
//Debug
/*debug("Norm:");
for(uint8_t i=0;i<17;i++)
debug(" %02X",packet[i]);
debugln("");*/
}
static void __attribute__((unused)) FrSkyL_encode_packet(bool type)
{
#define FRSKYL_BIT0 0xED
#define FRSKYL_BIT1 0x712
uint32_t bits = 0;
uint8_t bitsavailable = 0;
uint8_t idx = 0,len=6;
if(type)
{//just replace packet content
idx=66;
len=17;
}
//debugln("Encode:");
for (uint8_t i = 0; i < len; i++)
{
uint8_t tmp=packet[i];
//debug("%02X =",tmp);
for(uint8_t j=0;j<8;j++)
{
bits <<= 11;
if(tmp&0x01)
bits |= FRSKYL_BIT1;
else
bits |= FRSKYL_BIT0;
tmp >>=1;
bitsavailable += 11;
while (bitsavailable >= 8) {
uint32_t bits_tmp=bits>>(bitsavailable-8);
bitsavailable -= 8;
FrSkyL_buffer[idx] = bits_tmp;
//debug(" %02X",FrSkyL_buffer[idx]);
idx++;
}
}
//debugln("");
}
}
uint16_t ReadFrSkyL()
{
static uint8_t written=0, send=0;
switch(send)
{
case 1:
CC2500_Strobe(CC2500_SIDLE);
CC2500_Strobe(CC2500_SFTX);
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, FrSkyL_buffer, 64);
CC2500_Strobe(CC2500_STX);
CC2500_Strobe(CC2500_SIDLE); // This cancels the current transmission???
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, FrSkyL_buffer, 64);
CC2500_Strobe(CC2500_SFTX); // This just clears what we've written???
CC2500_Strobe(CC2500_STX);
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, FrSkyL_buffer, 64);
written=64;
send++;
return 2623;
case 2:
len=FRSKYL_PACKET_LEN-written;
if(len>31)
len=31;
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, FrSkyL_buffer+written, len);
written+=len;
if(len!=31) //everything has been sent
{
send=0;
return 2936;
}
return 1984;
}
switch(state)
{
default:
//Bind
#ifdef MULTI_SYNC
telemetry_set_input_sync(9000);
#endif
FrSkyX_set_start(47);
CC2500_SetPower();
CC2500_Strobe(CC2500_SFRX);
//
FrSkyL_build_bind_packet();
FrSkyL_encode_packet(true);
CC2500_Strobe(CC2500_SIDLE);
if(IS_BIND_DONE)
state = FRSKY_BIND_DONE;
else
{
state++;
send=1;
}
return 537;
case FRSKY_BIND_DONE:
FrSkyX_initialize_data(0);
hopping_frequency_no=0;
BIND_DONE;
state++; //FRSKY_DATA1
break;
case FRSKY_DATA1:
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); //Frequency offset hack
prev_option = option ;
}
FrSkyX_set_start(hopping_frequency_no);
FrSkyL_build_packet();
FrSkyL_encode_packet(true);
CC2500_SetPower();
hopping_frequency_no = (hopping_frequency_no+FrSkyX_chanskip)%47;
send=1;
return 537;
}
return 1;
}
uint16_t initFrSkyL()
{
set_rx_tx_addr(MProtocol_id_master);
rx_tx_addr[1]=0x02; // ID related, hw version?
#ifdef FRSKYL_FORCE_ID
rx_tx_addr[3]=0x0E;
rx_tx_addr[2]=0x1C;
rx_tx_addr[1]=0x02;
#endif
FrSkyX2_init_hop();
while(!FrSkyX_chanskip)
FrSkyX_chanskip=random(0xfefefefe)%47;
FrSkyX_init();
//Prepare frame
memset(FrSkyL_buffer,0x00,FRSKYL_PACKET_LEN-3);
memset(&FrSkyL_buffer[FRSKYL_PACKET_LEN-3],0x55,3);
memset(packet,0xAA,6);
FrSkyL_encode_packet(false);
/*debugln("Frame:");
for(uint16_t i=0;i<FRSKYL_PACKET_LEN;i++)
{
debug(" %02X",FrSkyL_buffer[i]);
if(i%11==10)
debugln("");
}
debugln("");*/
if(IS_BIND_IN_PROGRESS)
{
state = FRSKY_BIND;
FrSkyX_initialize_data(1);
}
else
{
state = FRSKY_DATA1;
FrSkyX_initialize_data(0);
}
return 10000;
}
#endif

View File

@@ -1,6 +1,4 @@
/* **************************
* By Midelic on RCGroups *
**************************
/*
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
@@ -13,7 +11,7 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
*/
#if defined(FRSKYX_CC2500_INO)
@@ -22,7 +20,7 @@
static void __attribute__((unused)) FrSkyX_build_bind_packet()
{
uint8_t packet_size = 0x1D;
if(protocol==PROTO_FRSKYX && (sub_protocol & 2 ))
if(protocol==PROTO_FRSKYX && (FrSkyFormat & 2 ))
packet_size=0x20; // FrSkyX V1 LBT
//Header
packet[0] = packet_size; // Number of bytes in the packet (after this one)
@@ -42,7 +40,7 @@ static void __attribute__((unused)) FrSkyX_build_bind_packet()
packet[8] = hopping_frequency[idx++];
packet[9] = hopping_frequency[idx++];
packet[10] = hopping_frequency[idx++];
packet[11] = 0x02; // Unknown but constant ID?
packet[11] = rx_tx_addr[1]; // Unknown but constant ID?
packet[12] = RX_num;
//
memset(&packet[13], 0, packet_size - 14);
@@ -54,7 +52,7 @@ static void __attribute__((unused)) FrSkyX_build_bind_packet()
else
{
//packet 1D 03 01 0E 1C 02 00 00 32 0B 00 00 A8 26 28 01 A1 00 00 00 3E F6 87 C7 00 00 00 00 C9 C9
packet[5] = 0x02; // Unknown but constant ID?
packet[5] = rx_tx_addr[1]; // Unknown but constant ID?
packet[6] = RX_num;
//Bind flags
packet[7]=0;
@@ -99,7 +97,7 @@ static void __attribute__((unused)) FrSkyX_build_packet()
{
FS_flag = 0x10;
failsafe_chan = 0;
} else if (FS_flag & 0x10 && failsafe_chan < (sub_protocol & 0x01 ? 8-1:16-1))
} else if (FS_flag & 0x10 && failsafe_chan < (FrSkyFormat & 0x01 ? 8-1:16-1))
{
FS_flag = 0x10 | ((FS_flag + 2) & 0x0F); //10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
failsafe_chan ++;
@@ -113,13 +111,13 @@ static void __attribute__((unused)) FrSkyX_build_packet()
#endif
uint8_t packet_size = 0x1D;
if(protocol==PROTO_FRSKYX && (sub_protocol & 2 ))
if(protocol==PROTO_FRSKYX && (FrSkyFormat & 2 ))
packet_size=0x20; // FrSkyX V1 LBT
//Header
packet[0] = packet_size; // Number of bytes in the packet (after this one)
packet[1] = rx_tx_addr[3]; // ID
packet[2] = rx_tx_addr[2]; // ID
packet[3] = 0x02; // Unknown but constant ID?
packet[3] = rx_tx_addr[1]; // Unknown but constant ID?
//
packet[4] = (FrSkyX_chanskip<<6)|hopping_frequency_no;
packet[5] = FrSkyX_chanskip>>2;
@@ -157,7 +155,7 @@ static void __attribute__((unused)) FrSkyX_build_packet()
packet[9+i+1]=(((chan_0>>8) & 0x0F)|(chan_1 << 4));
packet[9+i+2]=chan_1>>4;
}
if(sub_protocol & 0x01 ) //In X8 mode send only 8ch every 9ms
if(FrSkyFormat & 0x01 ) //In X8 mode send only 8ch every 9ms
chan_offset = 0 ;
else
chan_offset^=0x08;
@@ -256,10 +254,6 @@ static void __attribute__((unused)) FrSkyX_build_packet()
uint16_t ReadFrSkyX()
{
#ifdef DEBUG_SERIAL
static uint16_t fr_time=0;
#endif
switch(state)
{
default:
@@ -291,14 +285,14 @@ uint16_t ReadFrSkyX()
}
FrSkyX_set_start(hopping_frequency_no);
FrSkyX_build_packet();
if(sub_protocol & 2)
if(FrSkyFormat & 2)
{// LBT
CC2500_Strobe(CC2500_SRX); //Acquire RSSI
state++;
return 400; // LBT v2.1
}
case FRSKY_DATA2:
if(sub_protocol & 2)
if(FrSkyFormat & 2)
{
uint16_t rssi=0;
for(uint8_t i=0;i<4;i++)
@@ -308,10 +302,10 @@ uint16_t ReadFrSkyX()
uint8_t rssi_level=convert_channel_8b(CH16)>>1; //CH16 0..127
if ( rssi > rssi_level && rssi < 128) //test rssi level dynamically
#else
if ( rssi > 72 && rssi < 128) //LBT and RSSI between -36 and -8.5 dBm
if ( rssi > 14 && rssi < 128) // if RSSI above -65dBm (12=-70) => ETSI requirement
#endif
{
POWER_FLAG_off; // Reduce to low power before transmitting
LBT_POWER_on; // Reduce to low power before transmitting
debugln("Busy %d %d",hopping_frequency_no,rssi);
}
}
@@ -322,7 +316,7 @@ uint16_t ReadFrSkyX()
hopping_frequency_no = (hopping_frequency_no+FrSkyX_chanskip)%47;
CC2500_WriteData(packet, packet[0]+1);
state=FRSKY_DATA3;
if(sub_protocol & 2)
if(FrSkyFormat & 2)
return 4000; // LBT v2.1
else
return 5200; // FCC v2.1
@@ -331,7 +325,7 @@ uint16_t ReadFrSkyX()
CC2500_SetTxRxMode(RX_EN);
CC2500_Strobe(CC2500_SRX);
state++;
if(sub_protocol & 2)
if(FrSkyFormat & 2)
return 4100; // LBT v2.1
else
return 3300; // FCC v2.1
@@ -389,9 +383,15 @@ uint16_t ReadFrSkyX()
uint16_t initFrSkyX()
{
set_rx_tx_addr(MProtocol_id_master);
FrSkyFormat = sub_protocol;
if(protocol==PROTO_FRSKYX)
if (sub_protocol==XCLONE)
Frsky_init_clone();
else if(protocol==PROTO_FRSKYX)
{
Frsky_init_hop();
rx_tx_addr[1]=0x02; // ID related, hw version?
}
else
{
#ifdef FRSKYX2_FORCE_ID
@@ -399,6 +399,7 @@ uint16_t initFrSkyX()
rx_tx_addr[2]=0x1C;
FrSkyX_chanskip=18;
#endif
rx_tx_addr[1]=0x02; // ID related, hw version?
FrSkyX2_init_hop();
}

View File

@@ -17,16 +17,19 @@
#include "iface_cc2500.h"
#define FRSKY_RX_D16FCC_LENGTH 32
#define FRSKY_RX_D16LBT_LENGTH 35
#define FRSKY_RX_D8_LENGTH 20
#define FRSKY_RX_FORMATS 3
#define FRSKY_RX_D16FCC_LENGTH 0x1D+1
#define FRSKY_RX_D16LBT_LENGTH 0x20+1
#define FRSKY_RX_D16v2_LENGTH 0x1D+1
#define FRSKY_RX_D8_LENGTH 0x11+1
#define FRSKY_RX_FORMATS 5
enum
{
FRSKY_RX_D16FCC = 0,
FRSKY_RX_D16LBT,
FRSKY_RX_D8
FRSKY_RX_D8 =0,
FRSKY_RX_D16FCC =1,
FRSKY_RX_D16LBT =2,
FRSKY_RX_D16v2FCC =3,
FRSKY_RX_D16v2LBT =4,
};
enum {
@@ -40,7 +43,7 @@ enum {
const PROGMEM uint8_t frsky_rx_common_reg[][2] = {
{CC2500_02_IOCFG0, 0x01},
{CC2500_18_MCSM0, 0x18},
{CC2500_07_PKTCTRL1, 0x04},
{CC2500_07_PKTCTRL1, 0x05},
{CC2500_3E_PATABLE, 0xFF},
{CC2500_0C_FSCTRL0, 0},
{CC2500_0D_FREQ2, 0x5C},
@@ -62,7 +65,7 @@ const PROGMEM uint8_t frsky_rx_common_reg[][2] = {
{CC2500_2D_TEST1, 0x31},
{CC2500_2E_TEST0, 0x0B},
{CC2500_03_FIFOTHR, 0x07},
{CC2500_09_ADDR, 0x00},
{CC2500_09_ADDR, 0x03},
};
const PROGMEM uint8_t frsky_rx_d16fcc_reg[][2] = {
@@ -116,27 +119,36 @@ static void __attribute__((unused)) frsky_rx_strobe_rx()
}
static void __attribute__((unused)) frsky_rx_initialise_cc2500() {
const uint8_t frsky_rx_length[] = { FRSKY_RX_D16FCC_LENGTH, FRSKY_RX_D16LBT_LENGTH, FRSKY_RX_D8_LENGTH };
const uint8_t frsky_rx_length[] = { FRSKY_RX_D8_LENGTH, FRSKY_RX_D16FCC_LENGTH, FRSKY_RX_D16LBT_LENGTH, FRSKY_RX_D16v2_LENGTH, FRSKY_RX_D16v2_LENGTH };
packet_length = frsky_rx_length[frsky_rx_format];
CC2500_Reset();
CC2500_Strobe(CC2500_SIDLE);
for (uint8_t i = 0; i < sizeof(frsky_rx_common_reg) / 2; i++)
CC2500_WriteReg(pgm_read_byte_near(&frsky_rx_common_reg[i][0]), pgm_read_byte_near(&frsky_rx_common_reg[i][1]));
switch (frsky_rx_format) {
switch (frsky_rx_format)
{
case FRSKY_RX_D16v2FCC:
case FRSKY_RX_D16FCC:
for (uint8_t i = 0; i < sizeof(frsky_rx_d16fcc_reg) / 2; i++)
CC2500_WriteReg(pgm_read_byte_near(&frsky_rx_d16fcc_reg[i][0]), pgm_read_byte_near(&frsky_rx_d16fcc_reg[i][1]));
if(frsky_rx_format==FRSKY_RX_D16v2FCC)
{
CC2500_WriteReg(CC2500_08_PKTCTRL0, 0x05); // Enable CRC
CC2500_WriteReg(CC2500_17_MCSM1, 0x0E); // Go/Stay in RX mode
CC2500_WriteReg(CC2500_11_MDMCFG3, 0x84); // bitrate 70K->77K
}
break;
case FRSKY_RX_D16v2LBT:
case FRSKY_RX_D16LBT:
for (uint8_t i = 0; i < sizeof(frsky_rx_d16lbt_reg) / 2; i++)
CC2500_WriteReg(pgm_read_byte_near(&frsky_rx_d16lbt_reg[i][0]), pgm_read_byte_near(&frsky_rx_d16lbt_reg[i][1]));
if(frsky_rx_format==FRSKY_RX_D16v2LBT)
CC2500_WriteReg(CC2500_08_PKTCTRL0, 0x05); // Enable CRC
break;
case FRSKY_RX_D8:
for (uint8_t i = 0; i < sizeof(frsky_rx_d8_reg) / 2; i++)
CC2500_WriteReg(pgm_read_byte_near(&frsky_rx_d8_reg[i][0]), pgm_read_byte_near(&frsky_rx_d8_reg[i][1]));
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05); // always check address
CC2500_WriteReg(CC2500_09_ADDR, 0x03); // bind address
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
break;
}
@@ -169,16 +181,70 @@ static void __attribute__((unused)) frsky_rx_calibrate()
}
}
static uint8_t __attribute__((unused)) frskyx_rx_check_crc()
static uint8_t __attribute__((unused)) frskyx_rx_check_crc_id(bool bind,bool init)
{
// check D8 checksum
/*debugln("RX");
for(uint8_t i=0; i<packet_length;i++)
debug(" %02X",packet[i]);
debugln("");*/
if(bind && packet[0]!=packet_length-1 && packet[1] !=0x03 && packet[2] != 0x01)
return false;
uint8_t offset=bind?3:1;
// Check D8 checksum
if (frsky_rx_format == FRSKY_RX_D8)
return (packet[packet_length-1] & 0x80) == 0x80; // check CRC_OK flag in status byte 2
// check D16 checksum
uint8_t limit = packet_length - 4;
uint16_t lcrc = FrSkyX_crc(&packet[3], limit - 3); // computed crc
uint16_t rcrc = (packet[limit] << 8) | (packet[limit + 1] & 0xff); // received crc
return lcrc == rcrc;
{
if((packet[packet_length+1] & 0x80) != 0x80) // Check CRC_OK flag in status byte 2
return false; // Bad CRC
if(init)
{//Save TXID
rx_tx_addr[3] = packet[3];
rx_tx_addr[2] = packet[4];
}
else
if(rx_tx_addr[3] != packet[offset] || rx_tx_addr[2] != packet[offset+1])
return false; // Bad address
return true; // Full match
}
// Check D16v2 checksum
if (frsky_rx_format == FRSKY_RX_D16v2LBT || frsky_rx_format == FRSKY_RX_D16v2FCC)
if((packet[packet_length+1] & 0x80) != 0x80) // Check CRC_OK flag in status byte 2
return false;
//debugln("HW Checksum ok");
// Check D16 checksum
uint16_t lcrc = FrSkyX_crc(&packet[3], packet_length - 5); // Compute crc
uint16_t rcrc = (packet[packet_length-2] << 8) | (packet[packet_length-1] & 0xff); // Received crc
if(lcrc != rcrc)
return false; // Bad CRC
//debugln("Checksum ok");
if (bind && (frsky_rx_format == FRSKY_RX_D16v2LBT || frsky_rx_format == FRSKY_RX_D16v2FCC))
for(uint8_t i=3; i<packet_length-2; i++) //unXOR bind packet
packet[i] ^= 0xA7;
uint8_t offset2=0;
if (bind && (frsky_rx_format == FRSKY_RX_D16LBT || frsky_rx_format == FRSKY_RX_D16FCC))
offset2=6;
if(init)
{//Save TXID
rx_tx_addr[3] = packet[3];
rx_tx_addr[2] = packet[4];
rx_tx_addr[1] = packet[5+offset2];
rx_tx_addr[0] = packet[6+offset2]; // RXnum
}
else
if(rx_tx_addr[3] != packet[offset] || rx_tx_addr[2] != packet[offset+1] || rx_tx_addr[1] != packet[offset+2+offset2])
return false; // Bad address
//debugln("Address ok");
if(!bind && rx_tx_addr[0] != packet[6])
return false; // Bad RX num
//debugln("Match");
return true; // Full match
}
static void __attribute__((unused)) frsky_rx_build_telemetry_packet()
@@ -189,8 +255,24 @@ static void __attribute__((unused)) frsky_rx_build_telemetry_packet()
uint8_t idx = 0;
uint8_t i;
if (frsky_rx_format == FRSKY_RX_D16FCC || frsky_rx_format == FRSKY_RX_D16LBT) {
// decode D16 channels
if (frsky_rx_format == FRSKY_RX_D8)
{// decode D8 channels
raw_channel[0] = ((packet[10] & 0x0F) << 8 | packet[6]);
raw_channel[1] = ((packet[10] & 0xF0) << 4 | packet[7]);
raw_channel[2] = ((packet[11] & 0x0F) << 8 | packet[8]);
raw_channel[3] = ((packet[11] & 0xF0) << 4 | packet[9]);
raw_channel[4] = ((packet[16] & 0x0F) << 8 | packet[12]);
raw_channel[5] = ((packet[16] & 0xF0) << 4 | packet[13]);
raw_channel[6] = ((packet[17] & 0x0F) << 8 | packet[14]);
raw_channel[7] = ((packet[17] & 0xF0) << 4 | packet[15]);
for (i = 0; i < 8; i++) {
if (raw_channel[i] < 1290)
raw_channel[i] = 1290;
rx_rc_chan[i] = min(((raw_channel[i] - 1290) << 4) / 15, 2047);
}
}
else
{// decode D16 channels
raw_channel[0] = ((packet[10] << 8) & 0xF00) | packet[9];
raw_channel[1] = ((packet[11] << 4) & 0xFF0) | (packet[10] >> 4);
raw_channel[2] = ((packet[13] << 8) & 0xF00) | packet[12];
@@ -211,22 +293,6 @@ static void __attribute__((unused)) frsky_rx_build_telemetry_packet()
}
}
}
else {
// decode D8 channels
raw_channel[0] = ((packet[10] & 0x0F) << 8 | packet[6]);
raw_channel[1] = ((packet[10] & 0xF0) << 4 | packet[7]);
raw_channel[2] = ((packet[11] & 0x0F) << 8 | packet[8]);
raw_channel[3] = ((packet[11] & 0xF0) << 4 | packet[9]);
raw_channel[4] = ((packet[16] & 0x0F) << 8 | packet[12]);
raw_channel[5] = ((packet[16] & 0xF0) << 4 | packet[13]);
raw_channel[6] = ((packet[17] & 0x0F) << 8 | packet[14]);
raw_channel[7] = ((packet[17] & 0xF0) << 4 | packet[15]);
for (i = 0; i < 8; i++) {
if (raw_channel[i] < 1290)
raw_channel[i] = 1290;
rx_rc_chan[i] = min(((raw_channel[i] - 1290) << 4) / 15, 2047);
}
}
// buid telemetry packet
packet_in[idx++] = RX_LQI;
@@ -246,6 +312,49 @@ static void __attribute__((unused)) frsky_rx_build_telemetry_packet()
}
}
static void __attribute__((unused)) frsky_rx_data()
{
uint16_t temp = FRSKY_RX_EEPROM_OFFSET;
frsky_rx_format = eeprom_read_byte((EE_ADDR)temp++) % FRSKY_RX_FORMATS;
rx_tx_addr[3] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[2] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[1] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[0] = RX_num;
frsky_rx_finetune = eeprom_read_byte((EE_ADDR)temp++);
debug("format=%d, ", frsky_rx_format);
debug("addr[3]=%02X, ", rx_tx_addr[3]);
debug("addr[2]=%02X, ", rx_tx_addr[2]);
debug("addr[1]=%02X, ", rx_tx_addr[1]);
debug("rx_num=%02X, ", rx_tx_addr[0]);
debugln("tune=%d", (int8_t)frsky_rx_finetune);
if(frsky_rx_format != FRSKY_RX_D16v2LBT && frsky_rx_format != FRSKY_RX_D16v2FCC)
{//D8 & D16v1
for (uint8_t ch = 0; ch < 47; ch++)
hopping_frequency[ch] = eeprom_read_byte((EE_ADDR)temp++);
}
else
{
FrSkyFormat=frsky_rx_format == FRSKY_RX_D16v2FCC?0:2;
FrSkyX2_init_hop();
}
debug("ch:");
for (uint8_t ch = 0; ch < 47; ch++)
debug(" %02X", hopping_frequency[ch]);
debugln("");
frsky_rx_initialise_cc2500();
frsky_rx_calibrate();
CC2500_WriteReg(CC2500_18_MCSM0, 0x08); // FS_AUTOCAL = manual
CC2500_WriteReg(CC2500_09_ADDR, rx_tx_addr[3]); // set address
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05); // check address
if (option == 0)
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
else
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
frsky_rx_set_channel(hopping_frequency_no);
phase = FRSKY_RX_DATA;
}
uint16_t initFrSky_Rx()
{
state = 0;
@@ -254,32 +363,16 @@ uint16_t initFrSky_Rx()
rx_data_started = false;
frsky_rx_finetune = 0;
telemetry_link = 0;
if (IS_BIND_IN_PROGRESS) {
packet_count = 0;
if (IS_BIND_IN_PROGRESS)
{
frsky_rx_format = FRSKY_RX_D8;
frsky_rx_initialise_cc2500();
phase = FRSKY_RX_TUNE_START;
debugln("FRSKY_RX_TUNE_START");
}
else {
uint16_t temp = FRSKY_RX_EEPROM_OFFSET;
frsky_rx_format = eeprom_read_byte((EE_ADDR)temp++) % FRSKY_RX_FORMATS;
rx_tx_addr[0] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[1] = eeprom_read_byte((EE_ADDR)temp++);
rx_tx_addr[2] = eeprom_read_byte((EE_ADDR)temp++);
frsky_rx_finetune = eeprom_read_byte((EE_ADDR)temp++);
for (uint8_t ch = 0; ch < 47; ch++)
hopping_frequency[ch] = eeprom_read_byte((EE_ADDR)temp++);
frsky_rx_initialise_cc2500();
frsky_rx_calibrate();
CC2500_WriteReg(CC2500_18_MCSM0, 0x08); // FS_AUTOCAL = manual
CC2500_WriteReg(CC2500_09_ADDR, rx_tx_addr[0]); // set address
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05); // check address
if (option == 0)
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
else
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
frsky_rx_set_channel(hopping_frequency_no);
phase = FRSKY_RX_DATA;
}
frsky_rx_data();
return 1000;
}
@@ -291,7 +384,8 @@ uint16_t FrSky_Rx_callback()
static int8_t tune_low, tune_high;
uint8_t len, ch;
if ((prev_option != option) && (phase >= FRSKY_RX_DATA)) {
if ((prev_option != option) && (phase >= FRSKY_RX_DATA))
{
if (option == 0)
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
else
@@ -299,28 +393,30 @@ uint16_t FrSky_Rx_callback()
prev_option = option;
}
if (rx_disable_lna != IS_POWER_FLAG_on) {
if (rx_disable_lna != IS_POWER_FLAG_on)
{
rx_disable_lna = IS_POWER_FLAG_on;
CC2500_SetTxRxMode(rx_disable_lna ? TXRX_OFF : RX_EN);
}
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
switch(phase) {
switch(phase)
{
case FRSKY_RX_TUNE_START:
if (len >= packet_length) {
CC2500_ReadData(packet, packet_length);
if(packet[1] == 0x03 && packet[2] == 0x01 && frskyx_rx_check_crc()) {
rx_tx_addr[0] = packet[3]; // TXID
rx_tx_addr[1] = packet[4]; // TXID
if (len == packet_length + 2) //+2=RSSI+LQI+CRC
{
CC2500_ReadData(packet, len);
if(frskyx_rx_check_crc_id(true,true))
{
frsky_rx_finetune = -127;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
phase = FRSKY_RX_TUNE_LOW;
debugln("FRSKY_RX_TUNE_LOW");
frsky_rx_strobe_rx();
return 1000;
}
}
frsky_rx_format = (frsky_rx_format + 1) % FRSKY_RX_FORMATS; // switch to next format (D16FCC, D16LBT, D8)
frsky_rx_format = (frsky_rx_format + 1) % FRSKY_RX_FORMATS; // switch to next format (D8, D16FCC, D16LBT, D16v2FCC, D16v2LBT)
frsky_rx_initialise_cc2500();
frsky_rx_finetune += 10;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
@@ -328,13 +424,15 @@ uint16_t FrSky_Rx_callback()
return 18000;
case FRSKY_RX_TUNE_LOW:
if (len >= packet_length) {
CC2500_ReadData(packet, packet_length);
if(packet[1] == 0x03 && packet[2] == 0x01 && frskyx_rx_check_crc() && packet[3] == rx_tx_addr[0] && packet[4] == rx_tx_addr[1]) {
if (len == packet_length + 2) //+2=RSSI+LQI+CRC
{
CC2500_ReadData(packet, len);
if(frskyx_rx_check_crc_id(true,false)) {
tune_low = frsky_rx_finetune;
frsky_rx_finetune = 127;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
phase = FRSKY_RX_TUNE_HIGH;
debugln("FRSKY_RX_TUNE_HIGH");
frsky_rx_strobe_rx();
return 1000;
}
@@ -345,16 +443,23 @@ uint16_t FrSky_Rx_callback()
return 18000;
case FRSKY_RX_TUNE_HIGH:
if (len >= packet_length) {
CC2500_ReadData(packet, packet_length);
if(packet[1] == 0x03 && packet[2] == 0x01 && frskyx_rx_check_crc() && packet[3] == rx_tx_addr[0] && packet[4] == rx_tx_addr[1]) {
if (len == packet_length + 2) //+2=RSSI+LQI+CRC
{
CC2500_ReadData(packet, len);
if(frskyx_rx_check_crc_id(true,false)) {
tune_high = frsky_rx_finetune;
frsky_rx_finetune = (tune_low + tune_high) / 2;
CC2500_WriteReg(CC2500_0C_FSCTRL0, (int8_t)frsky_rx_finetune);
if(tune_low < tune_high)
{
phase = FRSKY_RX_BIND;
debugln("FRSKY_RX_TUNE_HIGH");
}
else
{
phase = FRSKY_RX_TUNE_START;
debugln("FRSKY_RX_TUNE_START");
}
frsky_rx_strobe_rx();
return 1000;
}
@@ -365,40 +470,47 @@ uint16_t FrSky_Rx_callback()
return 18000;
case FRSKY_RX_BIND:
if(len >= packet_length) {
CC2500_ReadData(packet, packet_length);
if(packet[1] == 0x03 && packet[2] == 0x01 && frskyx_rx_check_crc() && packet[3] == rx_tx_addr[0] && packet[4] == rx_tx_addr[1] && packet[5] <= 0x2D) {
if (len == packet_length + 2) //+2=RSSI+LQI+CRC
{
CC2500_ReadData(packet, len);
if(frskyx_rx_check_crc_id(true,false)) {
if(frsky_rx_format != FRSKY_RX_D16v2LBT && frsky_rx_format != FRSKY_RX_D16v2FCC)
{// D8 & D16v1
if(packet[5] <= 0x2D)
{
for (ch = 0; ch < 5; ch++)
hopping_frequency[packet[5]+ch] = packet[6+ch];
state |= 1 << (packet[5] / 5);
if (state == 0x3ff) {
debug("Bind complete: ");
frsky_rx_calibrate();
rx_tx_addr[2] = packet[12]; // RX # (D16)
CC2500_WriteReg(CC2500_18_MCSM0, 0x08); // FS_AUTOCAL = manual
CC2500_WriteReg(CC2500_09_ADDR, rx_tx_addr[0]); // set address
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05); // check address
phase = FRSKY_RX_DATA;
frsky_rx_set_channel(hopping_frequency_no);
}
}
else
state=0x3FF; //No hop table for D16v2
if (state == 0x3FF)
{
debugln("Bind complete");
BIND_DONE;
// store format, finetune setting, txid, channel list
uint16_t temp = FRSKY_RX_EEPROM_OFFSET;
eeprom_write_byte((EE_ADDR)temp++, frsky_rx_format);
debug("format=%d, ", frsky_rx_format);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[0]);
debug("addr[0]=%02X, ", rx_tx_addr[0]);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[1]);
debug("addr[1]=%02X, ", rx_tx_addr[1]);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[2]);
debug("rx_num=%02X, ", rx_tx_addr[2]);
eeprom_write_byte((EE_ADDR)temp++, frsky_rx_finetune);
debugln("tune=%d", (int8_t)frsky_rx_finetune);
for (ch = 0; ch < 47; ch++)
if(sub_protocol==FRSKY_CLONE)
{
eeprom_write_byte((EE_ADDR)temp++, hopping_frequency[ch]);
debug("%02X ", hopping_frequency[ch]);
if(frsky_rx_format==FRSKY_RX_D8)
temp=FRSKYD_CLONE_EEPROM_OFFSET;
else if(frsky_rx_format == FRSKY_RX_D16FCC || frsky_rx_format == FRSKY_RX_D16LBT)
temp=FRSKYX_CLONE_EEPROM_OFFSET;
else
temp=FRSKYX2_CLONE_EEPROM_OFFSET;
}
debugln("");
BIND_DONE;
eeprom_write_byte((EE_ADDR)temp++, frsky_rx_format);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[3]);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[2]);
eeprom_write_byte((EE_ADDR)temp++, rx_tx_addr[1]);
if(sub_protocol==FRSKY_RX)
eeprom_write_byte((EE_ADDR)temp++, frsky_rx_finetune);
if(frsky_rx_format != FRSKY_RX_D16v2FCC && frsky_rx_format != FRSKY_RX_D16v2LBT)
for (ch = 0; ch < 47; ch++)
eeprom_write_byte((EE_ADDR)temp++, hopping_frequency[ch]);
frsky_rx_data();
debugln("FRSKY_RX_DATA");
}
}
frsky_rx_strobe_rx();
@@ -406,35 +518,48 @@ uint16_t FrSky_Rx_callback()
return 1000;
case FRSKY_RX_DATA:
if (len >= packet_length) {
CC2500_ReadData(packet, packet_length);
if (packet[1] == rx_tx_addr[0] && packet[2] == rx_tx_addr[1] && frskyx_rx_check_crc() && (frsky_rx_format == FRSKY_RX_D8 || packet[6] == rx_tx_addr[2])) {
RX_RSSI = packet[packet_length-2];
if (len == packet_length + 2) //+2=RSSI+LQI+CRC
{
CC2500_ReadData(packet, len);
if(frskyx_rx_check_crc_id(false,false))
{
RX_RSSI = packet[len-2];
if(RX_RSSI >= 128)
RX_RSSI -= 128;
else
RX_RSSI += 128;
bool chanskip_valid=true;
// hop to next channel
if (frsky_rx_format == FRSKY_RX_D16FCC || frsky_rx_format == FRSKY_RX_D16LBT)
{
if (frsky_rx_format != FRSKY_RX_D8)
{//D16v1 & D16v2
if(rx_data_started)
{
if(frsky_rx_chanskip != (((packet[4] & 0xC0) >> 6) | ((packet[5] & 0x3F) << 2)))
{
chanskip_valid=false; // chanskip value has changed which surely indicates a bad frame
packet_count++;
if(packet_count>5) // the TX must have changed chanskip...
frsky_rx_chanskip = ((packet[4] & 0xC0) >> 6) | ((packet[5] & 0x3F) << 2); // chanskip init
}
else
packet_count=0;
}
else
frsky_rx_chanskip = ((packet[4] & 0xC0) >> 6) | ((packet[5] & 0x3F) << 2); // chanskip init
}
hopping_frequency_no = (hopping_frequency_no + frsky_rx_chanskip) % 47;
frsky_rx_set_channel(hopping_frequency_no);
if (telemetry_link == 0 && chanskip_valid) { // send channels to TX
if(chanskip_valid)
{
if (telemetry_link == 0)
{ // send channels to TX
frsky_rx_build_telemetry_packet();
telemetry_link = 1;
}
pps_counter++;
}
rx_data_started = true;
read_retry = 0;
pps_counter++;
}
}
@@ -443,6 +568,11 @@ uint16_t FrSky_Rx_callback()
pps_timer = millis();
debugln("%d pps", pps_counter);
RX_LQI = pps_counter;
if(pps_counter==0) // no packets for 1 sec or more...
{// restart the search
rx_data_started=false;
packet_count=0;
}
pps_counter = 0;
}

View File

@@ -1,6 +1,6 @@
1,Flysky,Flysky,V9x9,V6x6,V912,CX20
2,Hubsan,H107,H301,H501
3,FrskyD
3,FrskyD,D8,Cloned
4,Hisky,Hisky,HK310
5,V2x2,V2x2,JXD506
6,DSM,DSM2-22,DSM2-11,DSMX-22,DSMX-11,AUTO
@@ -12,7 +12,7 @@
12,CX10,GREEN,BLUE,DM007,---,J3015_1,J3015_2,MK33041
13,CG023,CG023,YD829
14,Bayang,Bayang,H8S3D,X16_AH,IRDRONE,DHD_D4
15,FrskyX,CH_16,CH_8,EU_16,EU_8
15,FrskyX,CH_16,CH_8,EU_16,EU_8,Cloned
16,ESky,Std,ET4
17,MT99xx,MT,H7,YZ,LS,FY805
18,MJXq,WLH08,X600,X800,H26D,E010,H26WH,PHOENIX
@@ -44,7 +44,7 @@
44,NCC1701
45,E01X,E012,E015,E016H
46,V911S,V911S,E119
47,GD00X,GD_V1,GD_V2
47,GD00x,GD_V1,GD_V2
48,V761
49,KF606
50,Redpine,Fast,Slow
@@ -52,7 +52,7 @@
52,ZSX,280
53,Flyzone,FZ-410
54,Scanner
55,Frsky_RX
55,Frsky_RX,RX,CloneTX
56,AFHDS2A_RX
57,HoTT
58,FX816,P38
@@ -61,5 +61,9 @@
61,Tiger
62,XK,X450,X420
63,XN_DUMP,250K,1M,2M,AUTO
64,FrskyX2,CH_16,CH_8,EU_16,EU_8
64,FrskyX2,CH_16,CH_8,EU_16,EU_8,Cloned
65,FrSkyR9,915MHz,868MHz,915_8ch,868_8ch
66,PROPEL,74-Z
67,LR12,LR12,LR12_6ch
68,Skyartec
69,ESKYv2,150V2

View File

@@ -29,6 +29,7 @@ const char STR_SLT[] ="SLT";
const char STR_CX10[] ="CX10";
const char STR_CG023[] ="CG023";
const char STR_BAYANG[] ="Bayang";
const char STR_FRSKYL[] ="FrSky L";
const char STR_FRSKYX[] ="FrSky X";
const char STR_FRSKYX2[] ="FrSkyX2";
const char STR_ESKY[] ="ESky";
@@ -50,6 +51,7 @@ const char STR_GW008[] ="GW008";
const char STR_DM002[] ="DM002";
const char STR_CABELL[] ="Cabell";
const char STR_ESKY150[] ="Esky150";
const char STR_ESKY150V2[] ="EskyV2";
const char STR_H8_3D[] ="H8 3D";
const char STR_CORONA[] ="Corona";
const char STR_CFLIE[] ="CFlie";
@@ -61,7 +63,7 @@ const char STR_TRAXXAS[] ="Traxxas";
const char STR_NCC1701[] ="NCC1701";
const char STR_E01X[] ="E01X";
const char STR_V911S[] ="V911S";
const char STR_GD00X[] ="GD00X";
const char STR_GD00X[] ="GD00x";
const char STR_V761[] ="V761";
const char STR_KF606[] ="KF606";
const char STR_REDPINE[] ="Redpine";
@@ -79,10 +81,13 @@ const char STR_TIGER[] ="Tiger";
const char STR_XK[] ="XK";
const char STR_XN297DUMP[] ="XN297DP";
const char STR_FRSKYR9[] ="FrSkyR9";
const char STR_PROPEL[] ="PROPEL";
const char STR_SKYARTEC[] ="Skyartc";
const char STR_SUBTYPE_FLYSKY[] = "\x04""Std\0""V9x9""V6x6""V912""CX20";
const char STR_SUBTYPE_HUBSAN[] = "\x04""H107""H301""H501";
const char STR_SUBTYPE_FRSKYX[] = "\x07""D16\0 ""D16 8ch""LBT(EU)""LBT 8ch";
const char STR_SUBTYPE_FRSKYD[] = "\x06""D8\0 ""Cloned";
const char STR_SUBTYPE_FRSKYX[] = "\x07""D16\0 ""D16 8ch""LBT(EU)""LBT 8ch""Cloned\0";
const char STR_SUBTYPE_HISKY[] = "\x05""Std\0 ""HK310";
const char STR_SUBTYPE_V2X2[] = "\x06""Std\0 ""JXD506";
const char STR_SUBTYPE_DSM[] = "\x06""2 22ms""2 11ms""X 22ms""X 11ms";
@@ -117,10 +122,15 @@ const char STR_SUBTYPE_FLYZONE[] = "\x05""FZ410";
const char STR_SUBTYPE_FX816[] = "\x03""P38";
const char STR_SUBTYPE_XN297DUMP[] = "\x07""250Kbps""1Mbps\0 ""2Mbps\0 ""Auto\0 ";
const char STR_SUBTYPE_ESKY150[] = "\x03""4CH""7CH";
const char STR_SUBTYPE_ESKY150V2[] = "\x05""150V2";
const char STR_SUBTYPE_V911S[] = "\x05""V911S""E119\0";
const char STR_SUBTYPE_XK[] = "\x04""X450""X420";
const char STR_SUBTYPE_FRSKYR9[] = "\x07""915MHz\0""868MHz\0""915 8ch""868 8ch";
const char STR_SUBTYPE_ESKY[] = "\x03""Std""ET4";
const char STR_SUBTYPE_PROPEL[] = "\x04""74-Z";
const char STR_SUBTYPE_FRSKY_RX[] = "\x07""RX\0 ""CloneTX";
const char STR_SUBTYPE_FRSKYL[] = "\x08""LR12\0 ""LR12 6ch";
const char STR_SUBTYPE_WFLY[] = "\x06""WFR0xS";
enum
{
@@ -139,196 +149,210 @@ enum
const mm_protocol_definition multi_protocols[] = {
// Protocol number, Protocol String, Number of sub_protocols, Sub_protocol strings, Option type
#if defined(FLYSKY_A7105_INO)
{PROTO_FLYSKY, STR_FLYSKY, 5, STR_SUBTYPE_FLYSKY, OPTION_NONE },
#endif
#if defined(HUBSAN_A7105_INO)
{PROTO_HUBSAN, STR_HUBSAN, 3, STR_SUBTYPE_HUBSAN, OPTION_VIDFREQ },
#endif
#if defined(FRSKYD_CC2500_INO)
{PROTO_FRSKYD, STR_FRSKYD, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(HISKY_NRF24L01_INO)
{PROTO_HISKY, STR_HISKY, 2, STR_SUBTYPE_HISKY, OPTION_NONE },
#endif
#if defined(V2X2_NRF24L01_INO)
{PROTO_V2X2, STR_V2X2, 2, STR_SUBTYPE_V2X2, OPTION_NONE },
#endif
#if defined(DSM_CYRF6936_INO)
{PROTO_DSM, STR_DSM, 4, STR_SUBTYPE_DSM, OPTION_MAXTHR },
#endif
#if defined(DEVO_CYRF6936_INO)
{PROTO_DEVO, STR_DEVO, 5, STR_SUBTYPE_DEVO, OPTION_FIXEDID },
#endif
#if defined(YD717_NRF24L01_INO)
{PROTO_YD717, STR_YD717, 5, STR_SUBTYPE_YD717, OPTION_NONE },
#endif
#if defined(KN_NRF24L01_INO)
{PROTO_KN, STR_KN, 2, STR_SUBTYPE_KN, OPTION_NONE },
#endif
#if defined(SYMAX_NRF24L01_INO)
{PROTO_SYMAX, STR_SYMAX, 2, STR_SUBTYPE_SYMAX, OPTION_NONE },
#endif
#if defined(SLT_NRF24L01_INO)
{PROTO_SLT, STR_SLT, 5, STR_SUBTYPE_SLT, OPTION_RFTUNE },
#endif
#if defined(CX10_NRF24L01_INO)
{PROTO_CX10, STR_CX10, 7, STR_SUBTYPE_CX10, OPTION_NONE },
#endif
#if defined(CG023_NRF24L01_INO)
{PROTO_CG023, STR_CG023, 2, STR_SUBTYPE_CG023, OPTION_NONE },
#endif
#if defined(BAYANG_NRF24L01_INO)
{PROTO_BAYANG, STR_BAYANG, 5, STR_SUBTYPE_BAYANG, OPTION_TELEM },
#endif
#if defined(FRSKYX_CC2500_INO)
{PROTO_FRSKYX, STR_FRSKYX, 4, STR_SUBTYPE_FRSKYX, OPTION_RFTUNE },
{PROTO_FRSKYX2, STR_FRSKYX2, 4, STR_SUBTYPE_FRSKYX, OPTION_RFTUNE },
#endif
#if defined(ESKY_NRF24L01_INO)
{PROTO_ESKY, STR_ESKY, 2, STR_SUBTYPE_ESKY, OPTION_NONE },
#endif
#if defined(MT99XX_NRF24L01_INO)
{PROTO_MT99XX, STR_MT99XX, 5, STR_SUBTYPE_MT99, OPTION_NONE },
#endif
#if defined(MJXQ_NRF24L01_INO)
{PROTO_MJXQ, STR_MJXQ, 7, STR_SUBTYPE_MJXQ, OPTION_RFTUNE },
#endif
#if defined(SHENQI_NRF24L01_INO)
{PROTO_SHENQI, STR_SHENQI, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(FY326_NRF24L01_INO)
{PROTO_FY326, STR_FY326, 2, STR_SUBTYPE_FY326, OPTION_NONE },
#endif
#if defined(SFHSS_CC2500_INO)
{PROTO_SFHSS, STR_SFHSS, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(J6PRO_CYRF6936_INO)
{PROTO_J6PRO, STR_J6PRO, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(FQ777_NRF24L01_INO)
{PROTO_FQ777, STR_FQ777, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(ASSAN_NRF24L01_INO)
#if defined(ASSAN_NRF24L01_INO)
{PROTO_ASSAN, STR_ASSAN, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(FRSKYV_CC2500_INO)
{PROTO_FRSKYV, STR_FRSKYV, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(HONTAI_NRF24L01_INO)
{PROTO_HONTAI, STR_HONTAI, 4, STR_SUBTYPE_HONTAI, OPTION_NONE },
#endif
#if defined(AFHDS2A_A7105_INO)
{PROTO_AFHDS2A, STR_AFHDS2A, 4, STR_SUBTYPE_AFHDS2A, OPTION_SRVFREQ },
#endif
#if defined(CX10_NRF24L01_INO)
{PROTO_Q2X2, STR_Q2X2, 3, STR_SUBTYPE_Q2X2, OPTION_NONE },
#endif
#if defined(WK2x01_CYRF6936_INO)
{PROTO_WK2x01, STR_WK2x01, 6, STR_SUBTYPE_WK2x01, OPTION_NONE },
#endif
#if defined(Q303_NRF24L01_INO)
{PROTO_Q303, STR_Q303, 4, STR_SUBTYPE_Q303, OPTION_NONE },
#endif
#if defined(GW008_NRF24L01_INO)
{PROTO_GW008, STR_GW008, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(DM002_NRF24L01_INO)
{PROTO_DM002, STR_DM002, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(CABELL_NRF24L01_INO)
{PROTO_CABELL, STR_CABELL, 8, STR_SUBTYPE_CABELL, OPTION_OPTION },
#endif
#if defined(ESKY150_NRF24L01_INO)
{PROTO_ESKY150, STR_ESKY150, 2, STR_SUBTYPE_ESKY150, OPTION_NONE },
#endif
#if defined(H8_3D_NRF24L01_INO)
{PROTO_H8_3D, STR_H8_3D, 4, STR_SUBTYPE_H83D, OPTION_NONE },
#endif
#if defined(CORONA_CC2500_INO)
{PROTO_CORONA, STR_CORONA, 3, STR_SUBTYPE_CORONA, OPTION_RFTUNE },
#endif
#if defined(CFLIE_NRF24L01_INO)
{PROTO_CFLIE, STR_CFLIE, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(HITEC_CC2500_INO)
{PROTO_HITEC, STR_HITEC, 3, STR_SUBTYPE_HITEC, OPTION_RFTUNE },
#endif
#if defined(WFLY_CYRF6936_INO)
{PROTO_WFLY, STR_WFLY, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(BUGS_A7105_INO)
{PROTO_BUGS, STR_BUGS, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(BUGSMINI_NRF24L01_INO)
{PROTO_BUGSMINI, STR_BUGSMINI, 2, STR_SUBTYPE_BUGS_MINI, OPTION_NONE },
#endif
#if defined(TRAXXAS_CYRF6936_INO)
{PROTO_TRAXXAS, STR_TRAXXAS, 1, STR_SUBTYPE_TRAXXAS, OPTION_NONE },
#endif
#if defined(NCC1701_NRF24L01_INO)
{PROTO_NCC1701, STR_NCC1701, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(E01X_NRF24L01_INO)
{PROTO_E01X, STR_E01X, 3, STR_SUBTYPE_E01X, OPTION_OPTION },
#endif
#if defined(V911S_NRF24L01_INO)
{PROTO_V911S, STR_V911S, 2, STR_SUBTYPE_V911S, OPTION_RFTUNE },
#endif
#if defined(GD00X_NRF24L01_INO)
{PROTO_GD00X, STR_GD00X, 2, STR_SUBTYPE_GD00X, OPTION_RFTUNE },
#endif
#if defined(V761_NRF24L01_INO)
{PROTO_V761, STR_V761, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(KF606_NRF24L01_INO)
{PROTO_KF606, STR_KF606, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(REDPINE_CC2500_INO)
{PROTO_REDPINE, STR_REDPINE, 2, STR_SUBTYPE_REDPINE, OPTION_RFTUNE },
#endif
#if defined(POTENSIC_NRF24L01_INO)
{PROTO_POTENSIC, STR_POTENSIC, 1, STR_SUBTYPE_POTENSIC, OPTION_NONE },
#endif
#if defined(ZSX_NRF24L01_INO)
{PROTO_ZSX, STR_ZSX, 1, STR_SUBTYPE_ZSX, OPTION_NONE },
#endif
#if defined(FLYZONE_A7105_INO)
{PROTO_FLYZONE, STR_FLYZONE, 1, STR_SUBTYPE_FLYZONE, OPTION_NONE },
#endif
#if defined(SCANNER_CC2500_INO)
{PROTO_SCANNER, STR_SCANNER, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(FRSKY_RX_CC2500_INO)
{PROTO_FRSKY_RX, STR_FRSKY_RX, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(AFHDS2A_RX_A7105_INO)
{PROTO_AFHDS2A_RX, STR_AFHDS2A_RX,0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(HOTT_CC2500_INO)
{PROTO_HOTT, STR_HOTT, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(FX816_NRF24L01_INO)
{PROTO_FX816, STR_FX816, 1, STR_SUBTYPE_FX816, OPTION_NONE },
#endif
#if defined(BAYANG_RX_NRF24L01_INO)
#endif
#if defined(BAYANG_NRF24L01_INO)
{PROTO_BAYANG, STR_BAYANG, 5, STR_SUBTYPE_BAYANG, OPTION_TELEM },
#endif
#if defined(BAYANG_RX_NRF24L01_INO)
{PROTO_BAYANG_RX, STR_BAYANG_RX, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(PELIKAN_A7105_INO)
{PROTO_PELIKAN, STR_PELIKAN , 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(TIGER_NRF24L01_INO)
{PROTO_TIGER, STR_TIGER , 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(XK_NRF24L01_INO)
{PROTO_XK, STR_XK , 2, STR_SUBTYPE_XK, OPTION_RFTUNE },
#endif
#if defined(XN297DUMP_NRF24L01_INO)
{PROTO_XN297DUMP, STR_XN297DUMP, 4, STR_SUBTYPE_XN297DUMP, OPTION_RFCHAN },
#endif
#if defined(FRSKYR9_SX1276_INO)
#endif
#if defined(BUGS_A7105_INO)
{PROTO_BUGS, STR_BUGS, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(BUGSMINI_NRF24L01_INO)
{PROTO_BUGSMINI, STR_BUGSMINI, 2, STR_SUBTYPE_BUGS_MINI, OPTION_NONE },
#endif
#if defined(CABELL_NRF24L01_INO)
{PROTO_CABELL, STR_CABELL, 8, STR_SUBTYPE_CABELL, OPTION_OPTION },
#endif
#if defined(CFLIE_NRF24L01_INO)
{PROTO_CFLIE, STR_CFLIE, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(E01X_NRF24L01_INO)
{PROTO_E01X, STR_E01X, 3, STR_SUBTYPE_E01X, OPTION_OPTION },
#endif
#if defined(CG023_NRF24L01_INO)
{PROTO_CG023, STR_CG023, 2, STR_SUBTYPE_CG023, OPTION_NONE },
#endif
#if defined(CORONA_CC2500_INO)
{PROTO_CORONA, STR_CORONA, 3, STR_SUBTYPE_CORONA, OPTION_RFTUNE },
#endif
#if defined(CX10_NRF24L01_INO)
{PROTO_CX10, STR_CX10, 7, STR_SUBTYPE_CX10, OPTION_NONE },
#endif
#if defined(DEVO_CYRF6936_INO)
{PROTO_DEVO, STR_DEVO, 5, STR_SUBTYPE_DEVO, OPTION_FIXEDID },
#endif
#if defined(DM002_NRF24L01_INO)
{PROTO_DM002, STR_DM002, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(DSM_CYRF6936_INO)
{PROTO_DSM, STR_DSM, 4, STR_SUBTYPE_DSM, OPTION_MAXTHR },
#endif
#if defined(ESKY_NRF24L01_INO)
{PROTO_ESKY, STR_ESKY, 2, STR_SUBTYPE_ESKY, OPTION_NONE },
#endif
#if defined(ESKY150_NRF24L01_INO)
{PROTO_ESKY150, STR_ESKY150, 2, STR_SUBTYPE_ESKY150, OPTION_NONE },
#endif
#if defined(ESKY150V2_CC2500_INO)
{PROTO_ESKY150V2, STR_ESKY150V2, 1, STR_SUBTYPE_ESKY150V2, OPTION_RFTUNE },
#endif
#if defined(FLYSKY_A7105_INO)
{PROTO_FLYSKY, STR_FLYSKY, 5, STR_SUBTYPE_FLYSKY, OPTION_NONE },
#endif
#if defined(AFHDS2A_A7105_INO)
{PROTO_AFHDS2A, STR_AFHDS2A, 4, STR_SUBTYPE_AFHDS2A, OPTION_SRVFREQ },
#endif
#if defined(AFHDS2A_RX_A7105_INO)
{PROTO_AFHDS2A_RX, STR_AFHDS2A_RX,0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(FLYZONE_A7105_INO)
{PROTO_FLYZONE, STR_FLYZONE, 1, STR_SUBTYPE_FLYZONE, OPTION_NONE },
#endif
#if defined(FQ777_NRF24L01_INO)
{PROTO_FQ777, STR_FQ777, 0, NO_SUBTYPE, OPTION_NONE },
#endif
//OpenTX 2.3.x issue: DO NOT CHANGE ORDER below
#if defined(FRSKY_RX_CC2500_INO)
{PROTO_FRSKY_RX, STR_FRSKY_RX, 2, STR_SUBTYPE_FRSKY_RX, OPTION_RFTUNE },
#endif
#if defined(FRSKYD_CC2500_INO)
{PROTO_FRSKYD, STR_FRSKYD, 2, STR_SUBTYPE_FRSKYD, OPTION_RFTUNE },
#endif
#if defined(FRSKYV_CC2500_INO)
{PROTO_FRSKYV, STR_FRSKYV, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(FRSKYX_CC2500_INO)
{PROTO_FRSKYX, STR_FRSKYX, 5, STR_SUBTYPE_FRSKYX, OPTION_RFTUNE },
{PROTO_FRSKYX2, STR_FRSKYX2, 5, STR_SUBTYPE_FRSKYX, OPTION_RFTUNE },
#endif
//OpenTX 2.3.x issue: DO NOT CHANGE ORDER above
#if defined(FRSKYL_CC2500_INO)
{PROTO_FRSKYL, STR_FRSKYL, 2, STR_SUBTYPE_FRSKYL, OPTION_RFTUNE },
#endif
#if defined(FRSKYR9_SX1276_INO)
{PROTO_FRSKY_R9, STR_FRSKYR9, 4, STR_SUBTYPE_FRSKYR9, OPTION_NONE },
#endif
#endif
#if defined(FX816_NRF24L01_INO)
{PROTO_FX816, STR_FX816, 1, STR_SUBTYPE_FX816, OPTION_NONE },
#endif
#if defined(FY326_NRF24L01_INO)
{PROTO_FY326, STR_FY326, 2, STR_SUBTYPE_FY326, OPTION_NONE },
#endif
#if defined(GD00X_NRF24L01_INO)
{PROTO_GD00X, STR_GD00X, 2, STR_SUBTYPE_GD00X, OPTION_RFTUNE },
#endif
#if defined(GW008_NRF24L01_INO)
{PROTO_GW008, STR_GW008, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(H8_3D_NRF24L01_INO)
{PROTO_H8_3D, STR_H8_3D, 4, STR_SUBTYPE_H83D, OPTION_NONE },
#endif
#if defined(HISKY_NRF24L01_INO)
{PROTO_HISKY, STR_HISKY, 2, STR_SUBTYPE_HISKY, OPTION_NONE },
#endif
#if defined(HITEC_CC2500_INO)
{PROTO_HITEC, STR_HITEC, 3, STR_SUBTYPE_HITEC, OPTION_RFTUNE },
#endif
#if defined(HONTAI_NRF24L01_INO)
{PROTO_HONTAI, STR_HONTAI, 4, STR_SUBTYPE_HONTAI, OPTION_NONE },
#endif
#if defined(HOTT_CC2500_INO)
{PROTO_HOTT, STR_HOTT, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(HUBSAN_A7105_INO)
{PROTO_HUBSAN, STR_HUBSAN, 3, STR_SUBTYPE_HUBSAN, OPTION_VIDFREQ },
#endif
#if defined(J6PRO_CYRF6936_INO)
{PROTO_J6PRO, STR_J6PRO, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(KF606_NRF24L01_INO)
{PROTO_KF606, STR_KF606, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(KN_NRF24L01_INO)
{PROTO_KN, STR_KN, 2, STR_SUBTYPE_KN, OPTION_NONE },
#endif
#if defined(MJXQ_NRF24L01_INO)
{PROTO_MJXQ, STR_MJXQ, 7, STR_SUBTYPE_MJXQ, OPTION_RFTUNE },
#endif
#if defined(MT99XX_NRF24L01_INO)
{PROTO_MT99XX, STR_MT99XX, 5, STR_SUBTYPE_MT99, OPTION_NONE },
#endif
#if defined(NCC1701_NRF24L01_INO)
{PROTO_NCC1701, STR_NCC1701, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(PELIKAN_A7105_INO)
{PROTO_PELIKAN, STR_PELIKAN , 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(POTENSIC_NRF24L01_INO)
{PROTO_POTENSIC, STR_POTENSIC, 1, STR_SUBTYPE_POTENSIC, OPTION_NONE },
#endif
#if defined(PROPEL_NRF24L01_INO)
{PROTO_PROPEL, STR_PROPEL, 4, STR_SUBTYPE_PROPEL, OPTION_NONE },
#endif
#if defined(CX10_NRF24L01_INO)
{PROTO_Q2X2, STR_Q2X2, 3, STR_SUBTYPE_Q2X2, OPTION_NONE },
#endif
#if defined(Q303_NRF24L01_INO)
{PROTO_Q303, STR_Q303, 4, STR_SUBTYPE_Q303, OPTION_NONE },
#endif
#if defined(REDPINE_CC2500_INO)
{PROTO_REDPINE, STR_REDPINE, 2, STR_SUBTYPE_REDPINE, OPTION_RFTUNE },
#endif
#if defined(SCANNER_CC2500_INO)
// {PROTO_SCANNER, STR_SCANNER, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(SFHSS_CC2500_INO)
{PROTO_SFHSS, STR_SFHSS, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(SHENQI_NRF24L01_INO)
{PROTO_SHENQI, STR_SHENQI, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(SKYARTEC_CC2500_INO)
{PROTO_SKYARTEC, STR_SKYARTEC, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
#if defined(SLT_NRF24L01_INO)
{PROTO_SLT, STR_SLT, 5, STR_SUBTYPE_SLT, OPTION_RFTUNE },
#endif
#if defined(SYMAX_NRF24L01_INO)
{PROTO_SYMAX, STR_SYMAX, 2, STR_SUBTYPE_SYMAX, OPTION_NONE },
#endif
#if defined(TIGER_NRF24L01_INO)
{PROTO_TIGER, STR_TIGER , 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(TRAXXAS_CYRF6936_INO)
{PROTO_TRAXXAS, STR_TRAXXAS, 1, STR_SUBTYPE_TRAXXAS, OPTION_NONE },
#endif
#if defined(V2X2_NRF24L01_INO)
{PROTO_V2X2, STR_V2X2, 2, STR_SUBTYPE_V2X2, OPTION_NONE },
#endif
#if defined(V761_NRF24L01_INO)
{PROTO_V761, STR_V761, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(V911S_NRF24L01_INO)
{PROTO_V911S, STR_V911S, 2, STR_SUBTYPE_V911S, OPTION_RFTUNE },
#endif
#if defined(WFLY_CYRF6936_INO)
{PROTO_WFLY, STR_WFLY, 1, STR_SUBTYPE_WFLY, OPTION_NONE },
#endif
#if defined(WK2x01_CYRF6936_INO)
{PROTO_WK2x01, STR_WK2x01, 6, STR_SUBTYPE_WK2x01, OPTION_NONE },
#endif
#if defined(XK_NRF24L01_INO)
{PROTO_XK, STR_XK , 2, STR_SUBTYPE_XK, OPTION_RFTUNE },
#endif
#if defined(XN297DUMP_NRF24L01_INO)
{PROTO_XN297DUMP, STR_XN297DUMP, 4, STR_SUBTYPE_XN297DUMP, OPTION_RFCHAN },
#endif
#if defined(YD717_NRF24L01_INO)
{PROTO_YD717, STR_YD717, 5, STR_SUBTYPE_YD717, OPTION_NONE },
#endif
#if defined(ZSX_NRF24L01_INO)
{PROTO_ZSX, STR_ZSX, 1, STR_SUBTYPE_ZSX, OPTION_NONE },
#endif
{0x00, nullptr, 0, nullptr, 0 }
};

View File

@@ -19,7 +19,7 @@
#define VERSION_MAJOR 1
#define VERSION_MINOR 3
#define VERSION_REVISION 0
#define VERSION_PATCH_LEVEL 79
#define VERSION_PATCH_LEVEL 95
//******************
// Protocols
@@ -92,6 +92,10 @@ enum PROTOCOLS
PROTO_XN297DUMP = 63, // =>NRF24L01
PROTO_FRSKYX2 = 64, // =>CC2500
PROTO_FRSKY_R9 = 65, // =>SX1276
PROTO_PROPEL = 66, // =>NRF24L01
PROTO_FRSKYL = 67, // =>CC2500
PROTO_SKYARTEC = 68, // =>CC2500
PROTO_ESKY150V2 = 69, // =>CC2500+NRF24L01
};
enum Flysky
@@ -207,12 +211,18 @@ enum MJXQ
H26WH = 5,
PHOENIX = 6,
};
enum FRSKYD
{
FRSKYD = 0,
DCLONE = 1,
};
enum FRSKYX
{
CH_16 = 0,
CH_8 = 1,
EU_16 = 2,
EU_8 = 3,
XCLONE = 4,
};
enum HONTAI
{
@@ -333,6 +343,18 @@ enum ESKY
ESKY_ET4 = 1,
};
enum FRSKY_RX
{
FRSKY_RX = 0,
FRSKY_CLONE = 1,
};
enum FRSKYL
{
LR12 = 0,
LR12_6CH = 1,
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
@@ -376,7 +398,7 @@ enum MultiPacketTypes
//*** Tests ***
//***************
#define IS_FAILSAFE_PROTOCOL ( (protocol==PROTO_HISKY && sub_protocol==HK310) || protocol==PROTO_AFHDS2A || protocol==PROTO_DEVO || protocol==PROTO_SFHSS || protocol==PROTO_WK2x01 || protocol== PROTO_HOTT || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2 )
#define IS_CHMAP_PROTOCOL ( (protocol==PROTO_HISKY && sub_protocol==HK310) || protocol==PROTO_AFHDS2A || protocol==PROTO_DEVO || protocol==PROTO_SFHSS || protocol==PROTO_WK2x01 || protocol== PROTO_DSM || protocol==PROTO_SLT || protocol==PROTO_FLYSKY || protocol==PROTO_ESKY || protocol==PROTO_J6PRO || protocol==PROTO_PELIKAN )
#define IS_CHMAP_PROTOCOL ( (protocol==PROTO_HISKY && sub_protocol==HK310) || protocol==PROTO_AFHDS2A || protocol==PROTO_DEVO || protocol==PROTO_SFHSS || protocol==PROTO_WK2x01 || protocol== PROTO_DSM || protocol==PROTO_SLT || protocol==PROTO_FLYSKY || protocol==PROTO_ESKY || protocol==PROTO_J6PRO || protocol==PROTO_PELIKAN || protocol==PROTO_SKYARTEC || protocol==PROTO_ESKY150V2 )
//***************
//*** Flags ***
@@ -466,6 +488,11 @@ enum MultiPacketTypes
#define DISABLE_TELEM_on protocol_flags3 |= _BV(3)
#define IS_DISABLE_TELEM_on ( ( protocol_flags3 & _BV(3) ) !=0 )
#define IS_DISABLE_TELEM_off ( ( protocol_flags3 & _BV(3) ) ==0 )
//LBT power
#define LBT_POWER_off protocol_flags3 &= ~_BV(7)
#define LBT_POWER_on protocol_flags3 |= _BV(7)
#define IS_LBT_POWER_on ( ( protocol_flags3 & _BV(7) ) !=0 )
#define IS_LBT_POWER_off ( ( protocol_flags3 & _BV(7) ) ==0 )
// Failsafe
@@ -590,6 +617,7 @@ enum CC2500_POWER
CC2500_POWER_17 = 0xFF // +1dbm
};
#define CC2500_HIGH_POWER CC2500_POWER_17
#define CC2500_LBT_POWER CC2500_POWER_14
#define CC2500_LOW_POWER CC2500_POWER_13
#define CC2500_RANGE_POWER CC2500_POWER_1
#define CC2500_BIND_POWER CC2500_POWER_1
@@ -643,7 +671,10 @@ enum {
#define AFHDS2A_EEPROM_OFFSET2 250 // RX ID, 4 bytes per model id, end is 250+192=442
#define HOTT_EEPROM_OFFSET 442 // RX ID, 5 bytes per model id, end is 320+442=762
#define BAYANG_RX_EEPROM_OFFSET 762 // (5) TX ID + (4) channels, 9 bytes, end is 771
//#define CONFIG_EEPROM_OFFSET 771 // Current configuration of the multimodule
#define FRSKYD_CLONE_EEPROM_OFFSET 771 // (1) format + (3) TX ID + (47) channels, 51 bytes, end is 822
#define FRSKYX_CLONE_EEPROM_OFFSET 822 // (1) format + (3) TX ID + (47) channels, 51 bytes, end is 873
#define FRSKYX2_CLONE_EEPROM_OFFSET 873 // (1) format + (3) TX ID, 4 bytes, end is 877
//#define CONFIG_EEPROM_OFFSET 877 // Current configuration of the multimodule
//****************************************
//*** MULTI protocol serial definition ***
@@ -727,6 +758,10 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
XN297DUMP 63
FRSKYX2 64
FRSKY_R9 65
PROPEL 66
FRSKYL 67
SKYARTEC 68
ESKY150V2 69
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
@@ -799,11 +834,21 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
E010 4
H26WH 5
PHOENIX 6
sub_protocol==FRSKYD
FRSKYD 0
DCLONE 1
sub_protocol==FRSKYX
CH_16 0
CH_8 1
EU_16 2
EU_8 3
XCLONE 4
sub_protocol==FRSKYX2
CH_16 0
CH_8 1
EU_16 2
EU_8 3
XCLONE 4
sub_protocol==HONTAI
HONTAI 0
JJRCX1 1
@@ -885,6 +930,12 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
sub_protocol==ESKY
ESKY_STD 0
ESKY_ET4 1
sub_protocol==FRSKY_RX
FRSKY_RX 0
FRSKY_CLONE 1
sub_protocol==FRSKYL
LR12 0
LR12_6CH 1
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
@@ -993,6 +1044,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
OPTION_RFCHAN 8
[19&0x0F] Number of sub protocols
[20..27] Sub protocol name [8], not null terminated if sub prototcol len == 8
If the current protocol is invalid [12..27] are all 0x00.
more information can be added by specifing a longer length of the type, the TX will just ignore these bytes

View File

@@ -75,7 +75,11 @@ uint32_t blink=0,last_signal=0;
//
uint16_t counter;
uint8_t channel;
uint8_t packet[50];
#ifdef ESKY150V2_CC2500_INO
uint8_t packet[150];
#else
uint8_t packet[50];
#endif
#define NUM_CHN 16
// Servo data
@@ -97,7 +101,7 @@ uint16_t packet_period;
uint8_t packet_count;
uint8_t packet_sent;
uint8_t packet_length;
#ifdef HOTT_CC2500_INO
#if defined(HOTT_CC2500_INO) || defined(ESKY150V2_CC2500_INO)
uint8_t hopping_frequency[75];
#else
uint8_t hopping_frequency[50];
@@ -504,6 +508,11 @@ void setup()
option = FORCE_FRSKYD_TUNING; // Use config-defined tuning value for FrSkyD
else
#endif
#if defined(FORCE_FRSKYL_TUNING) && defined(FRSKYL_CC2500_INO)
if(protocol==PROTO_FRSKYL)
option = FORCE_FRSKYL_TUNING; // Use config-defined tuning value for FrSkyL
else
#endif
#if defined(FORCE_FRSKYV_TUNING) && defined(FRSKYV_CC2500_INO)
if(protocol==PROTO_FRSKYV)
option = FORCE_FRSKYV_TUNING; // Use config-defined tuning value for FrSkyV
@@ -524,6 +533,11 @@ void setup()
option = FORCE_CORONA_TUNING; // Use config-defined tuning value for CORONA
else
#endif
#if defined(FORCE_SKYARTEC_TUNING) && defined(SKYARTEC_CC2500_INO)
if (protocol==PROTO_SKYARTEC)
option = FORCE_SKYARTEC_TUNING; // Use config-defined tuning value for SKYARTEC
else
#endif
#if defined(FORCE_REDPINE_TUNING) && defined(REDPINE_CC2500_INO)
if (protocol==PROTO_REDPINE)
option = FORCE_REDPINE_TUNING; // Use config-defined tuning value for REDPINE
@@ -737,7 +751,7 @@ bool Update_All()
update_led_status();
#if defined(TELEMETRY)
#if ( !( defined(MULTI_TELEMETRY) || defined(MULTI_STATUS) ) )
if((protocol == PROTO_BAYANG_RX) || (protocol == PROTO_AFHDS2A_RX) || (protocol == PROTO_FRSKY_RX) || (protocol == PROTO_SCANNER) || (protocol==PROTO_FRSKYD) || (protocol==PROTO_BAYANG) || (protocol==PROTO_NCC1701) || (protocol==PROTO_BUGS) || (protocol==PROTO_BUGSMINI) || (protocol==PROTO_HUBSAN) || (protocol==PROTO_AFHDS2A) || (protocol==PROTO_FRSKYX) || (protocol==PROTO_DSM) || (protocol==PROTO_CABELL) || (protocol==PROTO_HITEC) || (protocol==PROTO_HOTT) || (protocol==PROTO_FRSKYX2))
if((protocol == PROTO_BAYANG_RX) || (protocol == PROTO_AFHDS2A_RX) || (protocol == PROTO_FRSKY_RX) || (protocol == PROTO_SCANNER) || (protocol==PROTO_FRSKYD) || (protocol==PROTO_BAYANG) || (protocol==PROTO_NCC1701) || (protocol==PROTO_BUGS) || (protocol==PROTO_BUGSMINI) || (protocol==PROTO_HUBSAN) || (protocol==PROTO_AFHDS2A) || (protocol==PROTO_FRSKYX) || (protocol==PROTO_DSM) || (protocol==PROTO_CABELL) || (protocol==PROTO_HITEC) || (protocol==PROTO_HOTT) || (protocol==PROTO_FRSKYX2) || (protocol==PROTO_PROPEL))
#endif
if(IS_DISABLE_TELEM_off)
TelemetryUpdate();
@@ -753,8 +767,8 @@ bool Update_All()
{ // Autobind is on and BIND_CH went down
BIND_CH_PREV_off;
//Request protocol to terminate bind
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO) || defined(AFHDS2A_A7105_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2 || protocol==PROTO_FRSKYV || protocol==PROTO_AFHDS2A )
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYL_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO) || defined(AFHDS2A_A7105_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYL || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2 || protocol==PROTO_FRSKYV || protocol==PROTO_AFHDS2A )
BIND_DONE;
else
#endif
@@ -1112,6 +1126,14 @@ static void protocol_init()
remote_callback = ReadFrSky_2way;
break;
#endif
#if defined(FRSKYL_CC2500_INO)
case PROTO_FRSKYL:
PE1_off; //antenna RF2
PE2_on;
next_callback = initFrSkyL();
remote_callback = ReadFrSkyL;
break;
#endif
#if defined(FRSKYV_CC2500_INO)
case PROTO_FRSKYV:
PE1_off; //antenna RF2
@@ -1145,6 +1167,14 @@ static void protocol_init()
remote_callback = ReadCORONA;
break;
#endif
#if defined(SKYARTEC_CC2500_INO)
case PROTO_SKYARTEC:
PE1_off; //antenna RF2
PE2_on;
next_callback = initSKYARTEC();
remote_callback = ReadSKYARTEC;
break;
#endif
#if defined(REDPINE_CC2500_INO)
case PROTO_REDPINE:
PE1_off; //antenna RF2
@@ -1185,6 +1215,14 @@ static void protocol_init()
remote_callback = FrSky_Rx_callback;
break;
#endif
#if defined(ESKY150V2_CC2500_INO)
case PROTO_ESKY150V2:
PE1_off;
PE2_on; //antenna RF2
next_callback = initESKY150V2();
remote_callback = ESKY150V2_callback;
break;
#endif
#endif
#ifdef CYRF6936_INSTALLED
#if defined(DSM_CYRF6936_INO)
@@ -1485,6 +1523,12 @@ static void protocol_init()
remote_callback = XK_callback;
break;
#endif
#if defined(PROPEL_NRF24L01_INO)
case PROTO_PROPEL:
next_callback=initPROPEL();
remote_callback = PROPEL_callback;
break;
#endif
#if defined(XN297DUMP_NRF24L01_INO)
case PROTO_XN297DUMP:
next_callback=initXN297Dump();
@@ -1602,6 +1646,11 @@ void update_serial_data()
option=FORCE_FRSKYD_TUNING; // Use config-defined tuning value for FrSkyD
else
#endif
#if defined(FORCE_FRSKYL_TUNING) && defined(FRSKYL_CC2500_INO)
if(protocol==PROTO_FRSKYL)
option=FORCE_FRSKYL_TUNING; // Use config-defined tuning value for FrSkyL
else
#endif
#if defined(FORCE_FRSKYV_TUNING) && defined(FRSKYV_CC2500_INO)
if(protocol==PROTO_FRSKYV)
option=FORCE_FRSKYV_TUNING; // Use config-defined tuning value for FrSkyV
@@ -1622,6 +1671,11 @@ void update_serial_data()
option=FORCE_CORONA_TUNING; // Use config-defined tuning value for CORONA
else
#endif
#if defined(FORCE_SKYARTEC_TUNING) && defined(SKYARTEC_CC2500_INO)
if (protocol==PROTO_SKYARTEC)
option=FORCE_SKYARTEC_TUNING; // Use config-defined tuning value for SKYARTEC
else
#endif
#if defined(FORCE_REDPINE_TUNING) && defined(REDPINE_CC2500_INO)
if (protocol==PROTO_REDPINE)
option=FORCE_REDPINE_TUNING; // Use config-defined tuning value for REDPINE
@@ -1714,8 +1768,8 @@ void update_serial_data()
else
if( ((rx_ok_buff[1]&0x80)==0) && ((cur_protocol[1]&0x80)!=0) ) // Bind flag has been reset
{ // Request protocol to end bind
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO) || defined(AFHDS2A_A7105_INO) || defined(FRSKYR9_SX1276_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2 || protocol==PROTO_FRSKYV || protocol==PROTO_AFHDS2A || protocol==PROTO_FRSKY_R9 )
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYL_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO) || defined(AFHDS2A_A7105_INO) || defined(FRSKYR9_SX1276_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYL || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2 || protocol==PROTO_FRSKYV || protocol==PROTO_AFHDS2A || protocol==PROTO_FRSKY_R9 )
BIND_DONE;
else
#endif
@@ -1786,13 +1840,20 @@ void update_serial_data()
#define BYTE_STUFF 0x7D
#define STUFF_MASK 0x20
//debug("SPort_in: ");
boolean sport_valid=false;
for(uint8_t i=28;i<28+7;i++)
if(rx_ok_buff[i]!=0) sport_valid=true; //Check that the payload is not full of 0
if((rx_ok_buff[27]&0x1F) > 0x1B) //Check 1st byte validity
sport_valid=false;
if(sport_valid)
{
SportData[SportTail]=0x7E;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
SportData[SportTail]=rx_ok_buff[27]&0x1F;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
for(uint8_t i=28;i<28+7;i++)
{
if(rx_ok_buff[i]==BYTE_STUFF)
if( (rx_ok_buff[i]==BYTE_STUFF) || (rx_ok_buff[i]==0x7E) )
{//stuff
SportData[SportTail]=BYTE_STUFF;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
@@ -1815,6 +1876,7 @@ void update_serial_data()
debugln("Low buf=%d,h=%d,t=%d",used,SportHead,SportTail);
}
}
}
#endif //SPORT_SEND
#ifdef HOTT_FW_TELEMETRY
if(protocol==PROTO_HOTT && rx_len==28)
@@ -2067,7 +2129,7 @@ void pollBoot()
#if defined(TELEMETRY)
void PPM_Telemetry_serial_init()
{
if( (protocol==PROTO_FRSKYD) || (protocol==PROTO_HUBSAN) || (protocol==PROTO_AFHDS2A) || (protocol==PROTO_BAYANG)|| (protocol==PROTO_NCC1701) || (protocol==PROTO_CABELL) || (protocol==PROTO_HITEC) || (protocol==PROTO_BUGS) || (protocol==PROTO_BUGSMINI)
if( (protocol==PROTO_FRSKYD) || (protocol==PROTO_HUBSAN) || (protocol==PROTO_AFHDS2A) || (protocol==PROTO_BAYANG)|| (protocol==PROTO_NCC1701) || (protocol==PROTO_CABELL) || (protocol==PROTO_HITEC) || (protocol==PROTO_BUGS) || (protocol==PROTO_BUGSMINI) || (protocol==PROTO_PROPEL)
#ifdef TELEMETRY_FRSKYX_TO_FRSKYD
|| (protocol==PROTO_FRSKYX) || (protocol==PROTO_FRSKYX2)
#endif
@@ -2133,6 +2195,51 @@ static uint32_t random_id(uint16_t address, uint8_t create_new)
#endif
}
// Generate frequency hopping sequence in the range [02..77]
static void __attribute__((unused)) calc_fh_channels(uint8_t num_ch)
{
uint8_t idx = 0;
uint32_t rnd = MProtocol_id;
uint8_t max=(num_ch/3)+2;
while (idx < num_ch)
{
uint8_t i;
uint8_t count_2_26 = 0, count_27_50 = 0, count_51_74 = 0;
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
// Use least-significant byte. 73 is prime, so channels 76..77 are unused
uint8_t next_ch = ((rnd >> 8) % 73) + 2;
// Keep a distance of 5 between consecutive channels
if (idx !=0)
{
if(hopping_frequency[idx-1]>next_ch)
{
if(hopping_frequency[idx-1]-next_ch<5)
continue;
}
else
if(next_ch-hopping_frequency[idx-1]<5)
continue;
}
// Check that it's not duplicated and spread uniformly
for (i = 0; i < idx; i++) {
if(hopping_frequency[i] == next_ch)
break;
if(hopping_frequency[i] <= 26)
count_2_26++;
else if (hopping_frequency[i] <= 50)
count_27_50++;
else
count_51_74++;
}
if (i != idx)
continue;
if ( (next_ch <= 26 && count_2_26 < max) || (next_ch >= 27 && next_ch <= 50 && count_27_50 < max) || (next_ch >= 51 && count_51_74 < max) )
hopping_frequency[idx++] = next_ch;//find hopping frequency
}
}
/**************************/
/**************************/
/** Interrupt routines **/

View File

@@ -172,6 +172,10 @@ void NRF24L01_SetPower()
if(prev_power != power)
{
rf_setup = (rf_setup & 0xF9) | (power << 1);
if(power==3)
rf_setup |=0x01; // Si24r01 full power, unused bit for NRF
else
rf_setup &=0xFE;
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
prev_power=power;
}

View File

@@ -383,7 +383,11 @@ static void __attribute__((unused)) NRF250K_WritePayload(uint8_t* msg, uint8_t l
}
//CC2500
#ifdef CC2500_INSTALLED
#if defined(ESKY150V2_CC2500_INO)
uint8_t buf[158];
#else
uint8_t buf[35];
#endif
uint8_t last = 0;
uint8_t i;
@@ -417,10 +421,40 @@ static void __attribute__((unused)) NRF250K_WritePayload(uint8_t* msg, uint8_t l
CC2500_Strobe(CC2500_SFTX);
// packet length
CC2500_WriteReg(CC2500_3F_TXFIFO, last);
// nrf packet
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, buf, last);
// transmit
// transmit nrf packet
uint8_t *buff=buf;
uint8_t status;
if(last>63)
{
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, buff, 63);
CC2500_Strobe(CC2500_STX);
last-=63;
buff+=63;
while(last)
{//Loop until all the data is sent
do
{// Wait for the FIFO to become available
status=CC2500_ReadReg(CC2500_3A_TXBYTES | CC2500_READ_BURST);
}
while((status&0x7F)>31 && (status&0x80)==0);
if(last>31)
{//Send 31 bytes
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, buff, 31);
last-=31;
buff+=31;
}
else
{//Send last bytes
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, buff, last);
last=0;
}
}
}
else
{//Send packet
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, buff, last);
CC2500_Strobe(CC2500_STX);
}
#endif
}

View File

@@ -0,0 +1,329 @@
/*
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 <http://www.gnu.org/licenses/>.
*/
// Compatible with PROPEL 74-Z Speeder Bike.
#if defined(PROPEL_NRF24L01_INO)
#include "iface_nrf24l01.h"
//#define PROPEL_FORCE_ID
#define PROPEL_INITIAL_WAIT 500
#define PROPEL_PACKET_PERIOD 10000
#define PROPEL_BIND_RF_CHANNEL 0x23
#define PROPEL_PAYLOAD_SIZE 16
#define PROPEL_SEARCH_PERIOD 50 //*10ms
#define PROPEL_BIND_PERIOD 1500
#define PROPEL_PACKET_SIZE 14
#define PROPEL_RF_NUM_CHANNELS 4
#define PROPEL_ADDRESS_LENGTH 5
#define PROPEL_DEFAULT_PERIOD 20
enum {
PROPEL_BIND1 = 0,
PROPEL_BIND2,
PROPEL_BIND3,
PROPEL_DATA1,
};
static uint16_t __attribute__((unused)) PROPEL_checksum()
{
typedef union {
struct {
uint8_t h:1;
uint8_t g:1;
uint8_t f:1;
uint8_t e:1;
uint8_t d:1;
uint8_t c:1;
uint8_t b:1;
uint8_t a:1;
} bits;
uint8_t byte:8;
} byte_bits_t;
uint8_t sum = packet[0];
for (uint8_t i = 1; i < PROPEL_PACKET_SIZE - 2; i++)
sum += packet[i];
byte_bits_t in = { .byte = sum };
byte_bits_t out = { .byte = sum };
out.byte ^= 0x0a;
out.bits.d = !(in.bits.d ^ in.bits.h);
out.bits.c = (!in.bits.c && !in.bits.d && in.bits.g)
|| (in.bits.c && !in.bits.d && !in.bits.g)
|| (!in.bits.c && in.bits.g && !in.bits.h)
|| (in.bits.c && !in.bits.g && !in.bits.h)
|| (in.bits.c && in.bits.d && in.bits.g && in.bits.h)
|| (!in.bits.c && in.bits.d && !in.bits.g && in.bits.h);
out.bits.b = (!in.bits.b && !in.bits.c && !in.bits.d)
|| (in.bits.b && in.bits.c && in.bits.g)
|| (!in.bits.b && !in.bits.c && !in.bits.g)
|| (!in.bits.b && !in.bits.d && !in.bits.g)
|| (!in.bits.b && !in.bits.c && !in.bits.h)
|| (!in.bits.b && !in.bits.g && !in.bits.h)
|| (in.bits.b && in.bits.c && in.bits.d && in.bits.h)
|| (in.bits.b && in.bits.d && in.bits.g && in.bits.h);
out.bits.a = (in.bits.a && !in.bits.b)
|| (in.bits.a && !in.bits.c && !in.bits.d)
|| (in.bits.a && !in.bits.c && !in.bits.g)
|| (in.bits.a && !in.bits.d && !in.bits.g)
|| (in.bits.a && !in.bits.c && !in.bits.h)
|| (in.bits.a && !in.bits.g && !in.bits.h)
|| (!in.bits.a && in.bits.b && in.bits.c && in.bits.g)
|| (!in.bits.a && in.bits.b && in.bits.c && in.bits.d && in.bits.h)
|| (!in.bits.a && in.bits.b && in.bits.d && in.bits.g && in.bits.h);
return (sum << 8) | (out.byte & 0xff);
}
static void __attribute__((unused)) PROPEL_bind_packet(bool valid_rx_id)
{
memset(packet, 0, PROPEL_PACKET_SIZE);
packet[0] = 0xD0;
memcpy(&packet[1], rx_tx_addr, 4); // only 4 bytes sent of 5-byte address
if (valid_rx_id) memcpy(&packet[5], rx_id, 4);
packet[9] = rf_ch_num; // hopping table to be used when switching to normal mode
packet[11] = 0x05; // unknown, 0x01 on TX2??
uint16_t check = PROPEL_checksum();
packet[12] = check >> 8;
packet[13] = check & 0xff;
NRF24L01_WriteReg(NRF24L01_07_STATUS, (_BV(NRF24L01_07_RX_DR) | _BV(NRF24L01_07_TX_DS) | _BV(NRF24L01_07_MAX_RT)));
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WritePayload(packet, PROPEL_PACKET_SIZE);
}
static void __attribute__((unused)) PROPEL_data_packet()
{
memset(packet, 0, PROPEL_PACKET_SIZE);
packet[0] = 0xC0;
packet[1] = convert_channel_16b_limit(THROTTLE, 0x2f, 0xcf);
packet[2] = convert_channel_16b_limit(RUDDER , 0xcf, 0x2f);
packet[3] = convert_channel_16b_limit(ELEVATOR, 0x2f, 0xcf);
packet[4] = convert_channel_16b_limit(AILERON , 0xcf, 0x2f);
packet[5] = 0x40; //might be trims but unsused
packet[6] = 0x40; //might be trims but unsused
packet[7] = 0x40; //might be trims but unsused
packet[8] = 0x40; //might be trims but unsused
if (bind_phase)
{//need to send a couple of default packets after bind
bind_phase--;
packet[10] = 0x80; // LEDs
}
else
{
packet[9] = 0x02 // Always fast speed, slow=0x00, medium=0x01, fast=0x02, 0x03=flight training mode
| GET_FLAG( CH14_SW, 0x03) // Flight training mode
| GET_FLAG( CH10_SW, 0x04) // Calibrate
| GET_FLAG( CH12_SW, 0x08) // Take off
| GET_FLAG( CH8_SW, 0x10) // Fire
| GET_FLAG( CH11_SW, 0x20) // Altitude hold=0x20
| GET_FLAG( CH6_SW, 0x40) // Roll CW
| GET_FLAG( CH7_SW, 0x80); // Roll CCW
packet[10] = GET_FLAG( CH13_SW, 0x20) // Land
| GET_FLAG( CH9_SW, 0x40) // Weapon system activted=0x40
| GET_FLAG(!CH5_SW, 0x80); // LEDs
}
packet[11] = 5; // unknown, 0x01 on TX2??
uint16_t check = PROPEL_checksum();
packet[12] = check >> 8;
packet[13] = check & 0xff;
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no &= 0x03;
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, (_BV(NRF24L01_07_RX_DR) | _BV(NRF24L01_07_TX_DS) | _BV(NRF24L01_07_MAX_RT)));
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, PROPEL_PACKET_SIZE);
}
static void __attribute__((unused)) PROPEL_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x7f);
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x3f); // AA on all pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3f); // Enable all pipes
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x36); // retransmit 1ms, 6 times
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x07); // ?? match protocol capture
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x99\x77\x55\x33\x11", PROPEL_ADDRESS_LENGTH); //Bind address
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x99\x77\x55\x33\x11", PROPEL_ADDRESS_LENGTH); //Bind address
NRF24L01_WriteReg(NRF24L01_05_RF_CH, PROPEL_BIND_RF_CHANNEL);
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); // Enable dynamic payload length
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); // Enable all features
// Beken 2425 register bank 1 initialized here in stock tx capture
// Hopefully won't matter for nRF compatibility
NRF24L01_FlushTx();
NRF24L01_SetTxRxMode(TX_EN);
}
const uint8_t PROGMEM PROPEL_hopping []= { 0x47,0x36,0x27,0x44,0x33,0x0D,0x3C,0x2E,0x1B,0x39,0x2A,0x18 };
static void __attribute__((unused)) PROPEL_initialize_txid()
{
//address last byte
rx_tx_addr[4]=0x11;
//random hopping channel table
rf_ch_num=random(0xfefefefe)&0x03;
for(uint8_t i=0; i<3; i++)
hopping_frequency[i]=pgm_read_byte_near( &PROPEL_hopping[i + 3*rf_ch_num] );
hopping_frequency[3]=0x23;
#ifdef PROPEL_FORCE_ID
if(RX_num&1)
memcpy(rx_tx_addr, (uint8_t *)"\x73\xd3\x31\x30\x11", PROPEL_ADDRESS_LENGTH); //TX1: 73 d3 31 30 11
else
memcpy(rx_tx_addr, (uint8_t *)"\x94\xc5\x31\x30\x11", PROPEL_ADDRESS_LENGTH); //TX2: 94 c5 31 30 11
rf_ch_num = 0x03; //TX1
memcpy(hopping_frequency,(uint8_t *)"\x39\x2A\x18\x23",PROPEL_RF_NUM_CHANNELS); //TX1: 57,42,24,35
rf_ch_num = 0x00; //TX2
memcpy(hopping_frequency,(uint8_t *)"\x47\x36\x27\x23",PROPEL_RF_NUM_CHANNELS); //TX2: 71,54,39,35
rf_ch_num = 0x01; // Manual search
memcpy(hopping_frequency,(uint8_t *)"\x44\x33\x0D\x23",PROPEL_RF_NUM_CHANNELS); //Manual: 68,51,13,35
rf_ch_num = 0x02; // Manual search
memcpy(hopping_frequency,(uint8_t *)"\x3C\x2E\x1B\x23",PROPEL_RF_NUM_CHANNELS); //Manual: 60,46,27,35
#endif
}
uint16_t PROPEL_callback()
{
uint8_t status;
switch (phase)
{
case PROPEL_BIND1:
PROPEL_bind_packet(false); //rx_id unknown
phase++; //BIND2
return PROPEL_BIND_PERIOD;
case PROPEL_BIND2:
status=NRF24L01_ReadReg(NRF24L01_07_STATUS);
if (status & _BV(NRF24L01_07_MAX_RT))
{// Max retry (6) reached
phase = PROPEL_BIND1;
return PROPEL_BIND_PERIOD;
}
if (!(_BV(NRF24L01_07_RX_DR) & status))
return PROPEL_BIND_PERIOD; // nothing received
// received frame, got rx_id, save it
NRF24L01_ReadPayload(packet_in, PROPEL_PACKET_SIZE);
memcpy(rx_id, &packet_in[1], 4);
PROPEL_bind_packet(true); //send bind packet with rx_id
phase++; //BIND3
break;
case PROPEL_BIND3:
if (_BV(NRF24L01_07_RX_DR) & NRF24L01_ReadReg(NRF24L01_07_STATUS))
{
NRF24L01_ReadPayload(packet_in, PROPEL_PACKET_SIZE);
if (packet_in[0] == 0xa3 && memcmp(&packet_in[1],rx_id,4)==0)
{//confirmation from the model
phase++; //PROPEL_DATA1
bind_phase=PROPEL_DEFAULT_PERIOD;
packet_count=0;
BIND_DONE;
break;
}
}
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, PROPEL_ADDRESS_LENGTH);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, PROPEL_ADDRESS_LENGTH);
PROPEL_bind_packet(true); //send bind packet with rx_id
break;
case PROPEL_DATA1:
if (_BV(NRF24L01_07_RX_DR) & NRF24L01_ReadReg(NRF24L01_07_STATUS))
{// data received from the model
NRF24L01_ReadPayload(packet_in, PROPEL_PACKET_SIZE);
if (packet_in[0] == 0xa3 && memcmp(&packet_in[1],rx_id,3)==0)
{
telemetry_counter++; //LQI
v_lipo1=packet[5]; //number of life left?
v_lipo2=packet[4]; //bit mask: 0x80=flying, 0x08=taking off, 0x04=landing, 0x00=landed/crashed
if(telemetry_lost==0)
telemetry_link=1;
}
}
PROPEL_data_packet();
packet_count++;
if(packet_count>=100)
{//LQI calculation
packet_count=0;
TX_LQI=telemetry_counter;
RX_RSSI=telemetry_counter;
telemetry_counter = 0;
telemetry_lost=0;
}
break;
}
return PROPEL_PACKET_PERIOD;
}
uint16_t initPROPEL()
{
BIND_IN_PROGRESS; // autobind protocol
PROPEL_initialize_txid();
PROPEL_init();
hopping_frequency_no = 0;
phase=PROPEL_BIND1;
return PROPEL_INITIAL_WAIT;
}
#endif
// equations for checksum check byte from truth table
// (1) z = a && !b
// || a && !c && !d
// || a && !c && !g
// || a && !d && !g
// || a && !c && !h
// || a && !g && !h
// || !a && b && c && g
// || !a && b && c && d && h
// || !a && b && d && g && h;
//
// (2) y = !b && !c && !d
// || b && c && g
// || !b && !c && !g
// || !b && !d && !g
// || !b && !c && !h
// || !b && !g && !h
// || b && c && d && h
// || b && d && g && h;
//
// (3) x = !c && !d && g
// || c && !d && !g
// || !c && g && !h
// || c && !g && !h
// || c && d && g && h
// || !c && d && !g && h;
//
// (4) w = d && h
// || !d && !h;
//
// (5) v = !e;
//
// (6) u = f;
//
// (7) t = !g;
//
// (8) s = h;

View File

@@ -17,10 +17,10 @@
#include "iface_cc2500.h"
#define REDPINE_LOOPTIME_FAST 25 //2.5ms
#define REDPINE_LOOPTIME_SLOW 6 //6ms
#define REDPINE_LOOPTIME_FAST 20 //2.0ms
#define REDPINE_LOOPTIME_SLOW 20 //20ms
#define REDPINE_BIND 1000
#define REDPINE_BIND 2000
#define REDPINE_PACKET_SIZE 11
#define REDPINE_FEC false // from cc2500 datasheet: The convolutional coder is a rate 1/2 code with a constraint length of m=4
#define REDPINE_NUM_HOPS 50
@@ -105,10 +105,9 @@ static uint16_t ReadREDPINE()
}
if(IS_BIND_IN_PROGRESS)
{
if(bind_counter == REDPINE_BIND)
if (state == REDPINE_BIND) {
REDPINE_init(0);
if(bind_counter == REDPINE_BIND/2)
REDPINE_init(1);
}
REDPINE_set_channel(49);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
@@ -121,7 +120,7 @@ static uint16_t ReadREDPINE()
BIND_DONE;
REDPINE_init(sub_protocol);
}
return 9000;
return 4000;
}
else
{
@@ -149,23 +148,19 @@ static const uint8_t REDPINE_init_data[][3] = {
{CC2500_07_PKTCTRL1, 0x04, 0x04},
{CC2500_08_PKTCTRL0, 0x05, 0x05},
{CC2500_09_ADDR, 0x00, 0x00},
{CC2500_0B_FSCTRL1, 0x0A, 0x0A},
{CC2500_0B_FSCTRL1, 0x0A, 0x06},
{CC2500_0C_FSCTRL0, 0x00, 0x00},
{CC2500_0D_FREQ2, 0x5D, 0x5c},
{CC2500_0E_FREQ1, 0x93, 0x76},
{CC2500_0F_FREQ0, 0xB1, 0x27},
{CC2500_10_MDMCFG4, 0x2D, 0x7B},
{CC2500_11_MDMCFG3, 0x3B, 0x61},
{CC2500_12_MDMCFG2, 0x73, 0x13},
#ifdef REDPINE_FEC
{CC2500_13_MDMCFG1, 0xA3, 0xA3},
#else
{CC2500_13_MDMCFG1, 0x23, 0x23},
#endif
{CC2500_14_MDMCFG0, 0x56, 0x7a}, // Chan space
{CC2500_15_DEVIATN, 0x00, 0x51},
{CC2500_0D_FREQ2, 0x5D, 0x5D},
{CC2500_0E_FREQ1, 0x93, 0x93},
{CC2500_0F_FREQ0, 0xB1, 0xB1},
{CC2500_10_MDMCFG4, 0x2D, 0x78},
{CC2500_11_MDMCFG3, 0x3B, 0x93},
{CC2500_12_MDMCFG2, 0x73, 0x03},
{CC2500_13_MDMCFG1, 0x23, 0x22},
{CC2500_14_MDMCFG0, 0x56, 0xF8}, // Chan space
{CC2500_15_DEVIATN, 0x00, 0x44},
{CC2500_17_MCSM1, 0x0c, 0x0c},
{CC2500_18_MCSM0, 0x08, 0x08}, //??? 0x18, 0x18},
{CC2500_18_MCSM0, 0x18, 0x18},
{CC2500_19_FOCCFG, 0x1D, 0x16},
{CC2500_1A_BSCFG, 0x1C, 0x6c},
{CC2500_1B_AGCCTRL2, 0xC7, 0x43},
@@ -190,8 +185,9 @@ static void REDPINE_init(uint8_t format)
CC2500_WriteReg(CC2500_06_PKTLEN, REDPINE_PACKET_SIZE);
for (uint8_t i=0; i < ((sizeof REDPINE_init_data) / (sizeof REDPINE_init_data[0])); i++)
for (uint8_t i=0; i < ((sizeof(REDPINE_init_data)) / (sizeof(REDPINE_init_data[0]))); i++) {
CC2500_WriteReg(REDPINE_init_data[i][0], REDPINE_init_data[i][format+1]);
}
prev_option = option;
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
@@ -215,7 +211,6 @@ static uint16_t initREDPINE()
uint32_t idx = 0;
uint32_t rnd = MProtocol_id;
#define REDPINE_MAX_RF_CHANNEL 255
hopping_frequency[idx++] = 1;
while (idx < REDPINE_NUM_HOPS-1)
{
uint32_t i;
@@ -226,8 +221,9 @@ static uint16_t initREDPINE()
for (i = 0; i < idx; i++)
{
uint8_t ch = hopping_frequency[i];
if ((ch <= next_ch + 1) && (ch >= next_ch - 1) && (ch > 1))
if ((ch <= next_ch + 1) && (ch >= next_ch - 1) && (ch >= 1)) {
break;
}
}
if (i != idx)
continue;

View File

@@ -0,0 +1,179 @@
/*
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 <http://www.gnu.org/licenses/>.
*/
#if defined(SKYARTEC_CC2500_INO)
#include "iface_cc2500.h"
//#define SKYARTEC_FORCE_ID
#define SKYARTEC_COARSE 0x00
#define SKYARTEC_TX_ADDR rx_tx_addr[1]
#define SKYARTEC_TX_CHANNEL rx_tx_addr[0]
enum {
SKYARTEC_PKT1 = 0,
SKYARTEC_SLEEP1,
SKYARTEC_PKT2,
SKYARTEC_SLEEP2,
SKYARTEC_PKT3,
SKYARTEC_SLEEP3,
SKYARTEC_PKT4,
SKYARTEC_SLEEP4,
SKYARTEC_PKT5,
SKYARTEC_SLEEP5,
SKYARTEC_PKT6,
SKYARTEC_LAST,
};
const PROGMEM uint8_t SKYARTEC_init_values[] = {
/* 04 */ 0x13, 0x18, 0xFF, 0x05,
/* 08 */ 0x05, 0x43, 0xCD, 0x09, 0x00, 0x5D, 0x93, 0xB1 + SKYARTEC_COARSE,
/* 10 */ 0x2D, 0x20, 0x73, 0x22, 0xF8, 0x50, 0x07, 0x30,
/* 18 */ 0x18, 0x1D, 0x1C, 0xC7, 0x00, 0xB2, 0x87, 0x6B,
/* 20 */ 0xF8, 0xB6, 0x10, 0xEA, 0x0A, 0x00, 0x11, 0x41,
/* 28 */ 0x00, 0x59, 0x7F, 0x3F, 0x88, 0x31, 0x0B
};
static void __attribute__((unused)) SKYARTEC_rf_init()
{
CC2500_Strobe(CC2500_SIDLE);
for (uint8_t i = 4; i <= 0x2E; ++i)
CC2500_WriteReg(i, pgm_read_byte_near(&SKYARTEC_init_values[i-4]));
prev_option = option;
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SFTX);
CC2500_Strobe(CC2500_SFRX);
CC2500_Strobe(CC2500_SXOFF);
CC2500_Strobe(CC2500_SIDLE);
}
static void __attribute__((unused)) SKYARTEC_send_data_packet()
{
//13 c5 01 0259 0168 0000 0259 030c 021a 0489 f3 7e 0a
//header
packet[0] = 0x13; //Length
packet[1] = SKYARTEC_TX_ADDR; //Tx Addr?
packet[2] = 0x01; //???
//channels
for(uint8_t i = 0; i < 7; i++)
{
uint16_t value = convert_channel_16b_limit(CH_AETR[i],0x000,0x500);
packet[3+2*i] = value >> 8;
packet[4+2*i] = value & 0xff;
}
//checks
uint8_t xor1 = 0;
for(uint8_t i = 3; i <= 14; i++)
xor1 ^= packet[i];
packet[18] = xor1;
xor1 ^= packet[15];
xor1 ^= packet[16];
packet[17] = xor1;
packet[19] = packet[3] + packet[5] + packet[7] + packet[9] + packet[11] + packet[13];
CC2500_WriteReg(CC2500_04_SYNC1, rx_tx_addr[3]);
CC2500_WriteReg(CC2500_05_SYNC0, rx_tx_addr[2]);
CC2500_WriteReg(CC2500_09_ADDR, SKYARTEC_TX_ADDR);
CC2500_WriteReg(CC2500_0A_CHANNR, SKYARTEC_TX_CHANNEL);
CC2500_WriteData(packet, 20);
}
static void __attribute__((unused)) SKYARTEC_send_bind_packet()
{
//0b 7d 01 01 b2 c5 4a 2f 00 00 c5 d6
packet[0] = 0x0b; //Length
packet[1] = 0x7d;
packet[2] = 0x01;
packet[3] = 0x01;
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
packet[7] = rx_tx_addr[3];
packet[8] = 0x00;
packet[9] = 0x00;
packet[10] = SKYARTEC_TX_ADDR;
uint8_t xor1 = 0;
for(uint8_t i = 3; i < 11; i++)
xor1 ^= packet[i];
packet[11] = xor1;
CC2500_WriteReg(CC2500_04_SYNC1, 0x7d);
CC2500_WriteReg(CC2500_05_SYNC0, 0x7d);
CC2500_WriteReg(CC2500_09_ADDR, 0x7d);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x7d);
CC2500_WriteData(packet, 12);
}
uint16_t ReadSKYARTEC()
{
if (phase & 0x01)
{
CC2500_Strobe(CC2500_SIDLE);
if (phase == SKYARTEC_LAST)
{
CC2500_SetPower();
// Tune frequency if it has been changed
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
prev_option = option ;
}
phase = SKYARTEC_PKT1;
}
else
phase++;
return 3000;
}
if (phase == SKYARTEC_PKT1 && bind_counter)
{
SKYARTEC_send_bind_packet();
bind_counter--;
if(bind_counter == 0)
BIND_DONE;
}
else
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(6000);
#endif
SKYARTEC_send_data_packet();
}
phase++;
return 3000;
}
uint16_t initSKYARTEC()
{
SKYARTEC_rf_init();
#ifdef SKYARTEC_FORCE_ID
memset(rx_tx_addr,0x00,4);
#endif
if(rx_tx_addr[0]==0) rx_tx_addr[0]=0xB2;
if(rx_tx_addr[1]==0) rx_tx_addr[1]=0xC5;
if(rx_tx_addr[2]==0) rx_tx_addr[2]=0x4A;
if(rx_tx_addr[3]==0) rx_tx_addr[3]=0x2F;
bind_counter = 250;
phase = SKYARTEC_PKT1;
return 10000;
}
#endif

View File

@@ -120,15 +120,14 @@ static void telemetry_set_input_sync(uint16_t refreshRate)
static void multi_send_status()
{
#ifdef MULTI_NAMES
if(multi_protocols_index != 0xFF)
multi_send_header(MULTI_TELEMETRY_STATUS, 24);
else
#endif
#ifdef MULTI_TELEMETRY
multi_send_header(MULTI_TELEMETRY_STATUS, 6);
#ifdef MULTI_NAMES
multi_send_header(MULTI_TELEMETRY_STATUS, 24);
#else
multi_send_header(MULTI_TELEMETRY_STATUS, 6);
multi_send_header(MULTI_TELEMETRY_STATUS, 5);
#endif
#else
multi_send_header(MULTI_TELEMETRY_STATUS, 5);
#endif
// Build flags
@@ -141,13 +140,21 @@ static void multi_send_status()
{
flags |= 0x04;
#ifdef MULTI_NAMES
if((sub_protocol&0x07) && multi_protocols_index != 0xFF)
if(multi_protocols_index == 0xFF)
{
if(protocol!=PROTO_SCANNER)
flags &= ~0x04; //Invalid protocol
}
else if(sub_protocol&0x07)
{
uint8_t nbr=multi_protocols[multi_protocols_index].nbrSubProto;
if(protocol==PROTO_DSM) nbr++; //Auto sub_protocol
if((sub_protocol&0x07)>=nbr)
flags &= ~0x04; //Invalid sub protocol
}
#else
if(remote_callback==0)
flags &= ~0x04; //Invalid protocol
#endif
if (IS_WAIT_BIND_on)
flags |= 0x10;
@@ -177,17 +184,24 @@ static void multi_send_status()
#endif
#ifdef MULTI_NAMES
if(multi_protocols_index != 0xFF)
if(multi_protocols_index == 0xFF) // selection out of list... send first available protocol
{
Serial_write(multi_protocols[0].protocol); // begining of list
Serial_write(multi_protocols[0].protocol); // begining of list
for(uint8_t i=0;i<16;i++)
Serial_write(0x00); // everything else is invalid
}
else
{
// Protocol next/prev
if(multi_protocols[multi_protocols_index+1].protocol != 0)
Serial_write(multi_protocols[multi_protocols_index+1].protocol); // next protocol number
else
Serial_write(protocol); // end of list
Serial_write(multi_protocols[multi_protocols_index].protocol); // end of list
if(multi_protocols_index>0)
Serial_write(multi_protocols[multi_protocols_index-1].protocol); // prev protocol number
else
Serial_write(protocol); // begining of list
Serial_write(multi_protocols[multi_protocols_index].protocol); // begining of list
// Protocol
for(uint8_t i=0;i<7;i++)
Serial_write(multi_protocols[multi_protocols_index].ProtoString[i]); // protocol name
@@ -204,9 +218,9 @@ static void multi_send_status()
}
for(;j<8;j++)
Serial_write(0x00);
}
// Channels function
//TODO
}
#endif
}
#endif
@@ -514,7 +528,7 @@ void frsky_link_frame()
telemetry_link |= 2 ; // Send hub if available
}
else
{//PROTO_HUBSAN, PROTO_AFHDS2A, PROTO_BAYANG, PROTO_NCC1701, PROTO_CABELL, PROTO_HITEC, PROTO_BUGS, PROTO_BUGSMINI, PROTO_FRSKYX, PROTO_FRSKYX2
{//PROTO_HUBSAN, PROTO_AFHDS2A, PROTO_BAYANG, PROTO_NCC1701, PROTO_CABELL, PROTO_HITEC, PROTO_BUGS, PROTO_BUGSMINI, PROTO_FRSKYX, PROTO_FRSKYX2, PROTO_PROPEL
frame[1] = v_lipo1;
frame[2] = v_lipo2;
frame[3] = RX_RSSI;
@@ -935,7 +949,7 @@ void TelemetryUpdate()
#endif
if( telemetry_link & 1 )
{ // FrSkyD + Hubsan + AFHDS2A + Bayang + Cabell + Hitec + Bugs + BugsMini + NCC1701
{ // FrSkyD + Hubsan + AFHDS2A + Bayang + Cabell + Hitec + Bugs + BugsMini + NCC1701 + PROPEL
// FrSkyX telemetry if in PPM
frsky_link_frame();
return;

View File

@@ -79,6 +79,11 @@
#error "The FrSkyD forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_FRSKYL_TUNING
#if ( FORCE_FRSKYL_TUNING < -127 ) || ( FORCE_FRSKYL_TUNING > 127 )
#error "The FrSkyL forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_FRSKYV_TUNING
#if ( FORCE_FRSKYV_TUNING < -127 ) || ( FORCE_FRSKYV_TUNING > 127 )
#error "The FrSkyV forced frequency tuning value is outside of the range -127..127."
@@ -94,6 +99,11 @@
#error "The HITEC forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_HOTT_TUNING
#if ( FORCE_HOTT_TUNING < -127 ) || ( FORCE_HOTT_TUNING > 127 )
#error "The HOTT forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_REDPINE_TUNING
#if ( FORCE_REDPINE_TUNING < -127 ) || ( FORCE_REDPINE_TUNING > 127 )
#error "The REDPINE forced frequency tuning value is outside of the range -127..127."
@@ -104,9 +114,9 @@
#error "The SFHSS forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_HOTT_TUNING
#if ( FORCE_HOTT_TUNING < -127 ) || ( FORCE_HOTT_TUNING > 127 )
#error "The HOTT forced frequency tuning value is outside of the range -127..127."
#ifdef FORCE_SKYARTEC_TUNING
#if ( FORCE_SKYARTEC_TUNING < -127 ) || ( FORCE_SKYARTEC_TUNING > 127 )
#error "The SKYARTEC forced frequency tuning value is outside of the range -127..127."
#endif
#endif
//A7105
@@ -183,12 +193,12 @@
//Make sure protocols are selected correctly
#ifndef A7105_INSTALLED
#undef FLYSKY_A7105_INO
#undef HUBSAN_A7105_INO
#undef AFHDS2A_A7105_INO
#undef BUGS_A7105_INO
#undef FLYZONE_A7105_INO
#undef AFHDS2A_RX_A7105_INO
#undef BUGS_A7105_INO
#undef FLYSKY_A7105_INO
#undef FLYZONE_A7105_INO
#undef HUBSAN_A7105_INO
#undef PELIKAN_A7105_INO
#endif
#ifndef CYRF6936_INSTALLED
@@ -196,60 +206,65 @@
#undef DSM_CYRF6936_INO
#undef HOTT_CC2500_INO
#undef J6PRO_CYRF6936_INO
#undef TRAXXAS_CYRF6936_INO
#undef WFLY_CYRF6936_INO
#undef WK2x01_CYRF6936_INO
#undef TRAXXAS_CYRF6936_INO
#endif
#ifndef CC2500_INSTALLED
#undef CORONA_CC2500_INO
#undef ESKY150V2_CC2500_INO
#undef FRSKYD_CC2500_INO
#undef FRSKYL_CC2500_INO
#undef FRSKYV_CC2500_INO
#undef FRSKYX_CC2500_INO
#undef SFHSS_CC2500_INO
#undef CORONA_CC2500_INO
#undef REDPINE_CC2500_INO
#undef HITEC_CC2500_INO
#undef SCANNER_CC2500_INO
#undef FRSKY_RX_CC2500_INO
#undef HITEC_CC2500_INO
#undef HOTT_CC2500_INO
#undef REDPINE_CC2500_INO
#undef SCANNER_CC2500_INO
#undef SFHSS_CC2500_INO
#undef SKYARTEC_CC2500_INO
#endif
#ifndef NRF24L01_INSTALLED
#undef ASSAN_NRF24L01_INO
#undef BAYANG_NRF24L01_INO
#undef BAYANG_RX_NRF24L01_INO
#undef BUGSMINI_NRF24L01_INO
#undef CABELL_NRF24L01_INO
#undef CFLIE_NRF24L01_INO
#undef CG023_NRF24L01_INO
#undef CX10_NRF24L01_INO
#undef DM002_NRF24L01_INO
#undef E01X_NRF24L01_INO
#undef ESKY_NRF24L01_INO
#undef HISKY_NRF24L01_INO
#undef KF606_NRF24L01_INO
#undef KN_NRF24L01_INO
#undef SLT_NRF24L01_INO
#undef SYMAX_NRF24L01_INO
#undef V2X2_NRF24L01_INO
#undef YD717_NRF24L01_INO
#undef MT99XX_NRF24L01_INO
#undef MJXQ_NRF24L01_INO
#undef SHENQI_NRF24L01_INO
#undef ESKY150_NRF24L01_INO
#undef ESKY150V2_CC2500_INO // Use both CC2500 and NRF code
#undef FQ777_NRF24L01_INO
#undef FX816_NRF24L01_INO
#undef FY326_NRF24L01_INO
#undef FQ777_NRF24L01_INO
#undef ASSAN_NRF24L01_INO
#undef HONTAI_NRF24L01_INO
#undef Q303_NRF24L01_INO
#undef GW008_NRF24L01_INO
#undef GD00X_NRF24L01_INO
#undef DM002_NRF24L01_INO
#undef CABELL_NRF24L01_INO
#undef ESKY150_NRF24L01_INO
#undef GW008_NRF24L01_INO
#undef H8_3D_NRF24L01_INO
#undef CFLIE_NRF24L01_INO
#undef BUGSMINI_NRF24L01_INO
#undef HISKY_NRF24L01_INO
#undef HONTAI_NRF24L01_INO
#undef KF606_NRF24L01_INO
#undef KN_NRF24L01_INO
#undef MJXQ_NRF24L01_INO
#undef MT99XX_NRF24L01_INO
#undef NCC1701_NRF24L01_INO
#undef E01X_NRF24L01_INO
#undef POTENSIC_NRF24L01_INO
#undef PROPEL_NRF24L01_INO
#undef Q303_NRF24L01_INO
#undef SHENQI_NRF24L01_INO
#undef SLT_NRF24L01_INO
#undef SYMAX_NRF24L01_INO
#undef TIGER_NRF24L01_INO
#undef V2X2_NRF24L01_INO
#undef V761_NRF24L01_INO
#undef V911S_NRF24L01_INO
#undef POTENSIC_NRF24L01_INO
#undef ZSX_NRF24L01_INO
#undef BAYANG_RX_NRF24L01_INO
#undef TIGER_NRF24L01_INO
#undef XK_NRF24L01_INO
#undef YD717_NRF24L01_INO
#undef ZSX_NRF24L01_INO
#endif
#if not defined(STM32_BOARD)
#undef SX1276_INSTALLED
@@ -258,6 +273,12 @@
#undef FRSKYR9_SX1276_INO
#endif
//OpenTX 2.3.x issue
#if defined (FRSKYD_CC2500_INO) || defined(FRSKYV_CC2500_INO) || defined(FRSKYX_CC2500_INO)
#define FRSKYX_CC2500_INO
#define FRSKY_RX_CC2500_INO
#endif
//Make sure telemetry is selected correctly
#ifndef TELEMETRY
#undef INVERT_TELEMETRY

View File

@@ -92,9 +92,11 @@
//Uncomment the lines below (remove the "//") and set an appropriate value (replace the "0") to enable. Valid range is -127 to +127.
//#define FORCE_CORONA_TUNING 0
//#define FORCE_FRSKYD_TUNING 0
//#define FORCE_FRSKYL_TUNING 0
//#define FORCE_FRSKYV_TUNING 0
//#define FORCE_FRSKYX_TUNING 0
//#define FORCE_SFHSS_TUNING 0
//#define FORCE_SKYARTEC_TUNING 0
//#define FORCE_HITEC_TUNING 0
//#define FORCE_HOTT_TUNING 0
//#define FORCE_REDPINE_TUNING 0
@@ -175,6 +177,8 @@
//The protocols below need a CC2500 to be installed
#define CORONA_CC2500_INO
#define ESKY150V2_CC2500_INO //Need both CC2500 and NRF
#define FRSKYL_CC2500_INO
#define FRSKYD_CC2500_INO
#define FRSKYV_CC2500_INO
#define FRSKYX_CC2500_INO
@@ -183,6 +187,7 @@
#define HOTT_CC2500_INO
#define SCANNER_CC2500_INO
#define SFHSS_CC2500_INO
#define SKYARTEC_CC2500_INO
#define REDPINE_CC2500_INO
//The protocols below need a NRF24L01 to be installed
@@ -212,6 +217,7 @@
#define MT99XX_NRF24L01_INO
#define NCC1701_NRF24L01_INO
#define POTENSIC_NRF24L01_INO
#define PROPEL_NRF24L01_INO
#define Q303_NRF24L01_INO
#define SHENQI_NRF24L01_INO
#define SLT_NRF24L01_INO
@@ -547,6 +553,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
PROTO_ESKY150
ESKY150_4CH
ESKY150_7CH
PROTO_ESKY150V2
NONE
PROTO_FLYSKY
Flysky
V9X9
@@ -557,8 +565,15 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
FZ410
PROTO_FQ777
NONE
PROTO_FRSKY_RX
FRSKY_RX
FRSKY_CLONE
PROTO_FRSKYD
NONE
FRSKYD
DCLONE
PROTO_FRSKYL
LR12
LR12_6CH
PROTO_FRSKYR9
R9_915
R9_868
@@ -571,13 +586,16 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
CH_8
EU_16
EU_8
XCLONE
PROTO_FRSKYX2
CH_16
CH_8
EU_16
EU_8
XCLONE
PROTO_FRSKY_RX
NONE
FRSKY_RX
FRSKY_CLONE
PROTO_FX816
NONE
PROTO_FY326
@@ -638,6 +656,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
NONE
PROTO_POTENSIC
NONE
PROTO_PROPEL
NONE
PROTO_Q2X2
Q222
Q242
@@ -656,6 +676,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
NONE
PROTO_SHENQI
NONE
PROTO_SKYARTEC
NONE
PROTO_SLT
SLT_V1
SLT_V2

View File

@@ -82,17 +82,19 @@ CFlie|38|CFlie||||||||NRF24L01|
[E01X](Protocols_Details.md#E01X---45)|45|E012|E015|E016H||||||NRF24L01|XN297/HS6200
[ESky](Protocols_Details.md#ESKY---16)|16|ESky|Std|ET4||||||NRF24L01|
[ESky150](Protocols_Details.md#ESKY150---35)|35|ESKY150||||||||NRF24L01|
[ESky150V2](Protocols_Details.md#ESKY150V2---69)|69|||||||||CC2500|NRF24L01
[Flysky](Protocols_Details.md#FLYSKY---1)|1|Flysky|V9x9|V6x6|V912|CX20||||A7105|
[Flysky AFHDS2A](Protocols_Details.md#FLYSKY-AFHDS2A---28)|28|PWM_IBUS|PPM_IBUS|PWM_SBUS|PPM_SBUS|||||A7105|
[Flysky AFHDS2A RX](Protocols_Details.md#FLYSKY-AFHDS2A-RX---56)|56|||||||||A7105|
[Flyzone](Protocols_Details.md#FLYZONE---53)|53|FZ410||||||||A7105|
[FQ777](Protocols_Details.md#FQ777---23)|23|FQ777||||||||NRF24L01|SSV7241
[FrskyD](Protocols_Details.md#FRSKYD---3)|3|FrskyD||||||||CC2500|
[FQ777](Protocols_Details.md#FQ777---23)|23|||||||||NRF24L01|SSV7241
[FrskyD](Protocols_Details.md#FRSKYD---3)|3|D8|Cloned|||||||CC2500|
[FrskyL](Protocols_Details.md#FRSKYL---67)|67|LR12|LR12 6CH|||||||CC2500|
[FrskyR9](Protocols_Details.md#FRSKYR9---65)|65|FrskyR9|R9_915|R9_868||||||SX1276|
[FrskyV](Protocols_Details.md#FRSKYV---25)|25|FrskyV||||||||CC2500|
[FrskyX](Protocols_Details.md#FRSKYX---15)|15|CH_16|CH_8|EU_16|EU_8|||||CC2500|
[FrskyX2](Protocols_Details.md#FRSKYX2---64)|64|CH_16|CH_8|EU_16|EU_8|||||CC2500|
[FrskyX_RX](Protocols_Details.md#FRSKYX_RX---55)|55|||||||||CC2500|
[FrskyX](Protocols_Details.md#FRSKYX---15)|15|CH_16|CH_8|EU_16|EU_8|Cloned||||CC2500|
[FrskyX2](Protocols_Details.md#FRSKYX2---64)|64|CH_16|CH_8|EU_16|EU_8|Cloned||||CC2500|
[Frsky_RX](Protocols_Details.md#FRSKY_RX---55)|55|RX|CloneTX|||||||CC2500|
[FX816](Protocols_Details.md#FX816---58)|28|FX816|P38|||||||NRF24L01|
[FY326](Protocols_Details.md#FY326---20)|20|FY326|FY319|||||||NRF24L01|
[GD00X](Protocols_Details.md#GD00X---47)|47|GD_V1*|GD_V2*|||||||NRF24L01|
@@ -112,12 +114,14 @@ CFlie|38|CFlie||||||||NRF24L01|
[OpenLRS](Protocols_Details.md#OpenLRS---27)|27|||||||||None|
[Pelikan](Protocols_Details.md#Pelikan---60)|60|||||||||A7105|
[Potensic](Protocols_Details.md#Potensic---51)|51|A20||||||||NRF24L01|XN297
[PROPEL](Protocols_Details.md#PROPEL---66)|66|74-Z||||||||NRF24L01|
[Q2X2](Protocols_Details.md#Q2X2---29)|29|Q222|Q242|Q282||||||NRF24L01|
[Q303](Protocols_Details.md#Q303---31)|31|Q303|CX35|CX10D|CX10WD|||||NRF24L01|XN297
[Redpine](Protocols_Details.md#Redpine---50)|50|FAST|SLOW|||||||NRF24L01|
[Scanner](Protocols_Details.md#Scanner---54)|54|||||||||CC2500|
[SFHSS](Protocols_Details.md#SFHSS---21)|21|SFHSS||||||||CC2500|
[Shenqi](Protocols_Details.md#Shenqi---19)|19|Shenqi||||||||NRF24L01|LT8900
[SFHSS](Protocols_Details.md#SFHSS---21)|21|||||||||CC2500|
[Shenqi](Protocols_Details.md#Shenqi---19)|19|||||||||NRF24L01|LT8900
[Skyartec](Protocols_Details.md#Skyartec---68)|68|||||||||CC2500|CC2500
[SLT](Protocols_Details.md#SLT---11)|11|SLT_V1|SLT_V2|Q100|Q200|MR100||||NRF24L01|
[SymaX](Protocols_Details.md#Symax---10)|10|SYMAX|SYMAX5C|||||||NRF24L01|
[Tiger](Protocols_Details.md#Tiger---61)|61|Tiger||||||||NRF24L01|XN297
@@ -127,6 +131,7 @@ CFlie|38|CFlie||||||||NRF24L01|
[V911S](Protocols_Details.md#V911S---46)|46|V911S*|E119*|||||||NRF24L01|XN297
[WFly](Protocols_Details.md#WFLY---40)|40|WFLY||||||||CYRF6936|
[WK2x01](Protocols_Details.md#WK2X01---30)|30|WK2801|WK2401|W6_5_1|W6_6_1|W6_HEL|W6_HEL_I|||CYRF6936|
[XK](Protocols_Details.md#XK---62)|62|XK|X450|X420||||||NRF24L01|XN297
[YD717](Protocols_Details.md#YD717---8)|8|YD717|SKYWLKR|SYMAX4|XINXUN|NIHUI||||NRF24L01|
[ZSX](Protocols_Details.md#ZSX---52)|52|280||||||||NRF24L01|XN297
* "*" Sub Protocols designated by * suffix are using a XN297L@250kbps which will be emulated by default with the NRF24L01. If option (freq tune) is diffrent from 0, the CC2500 module (if installed) will be used instead. Each specific sub protocol has a more detailed explanation.
@@ -333,8 +338,38 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
### Sub_protocol D8 - *0*
Use the internal multi module Identifier.
### Sub_protocol Cloned - *1*
Use the identifier learnt from another FrSky radio when binding with the FrSkyRX/CloneTX mode.
RX number can't be used anymore and is ignored.
## FRSKYL - *67*
Models: FrSky receivers L9R. Also known as LR12.
Extended limits supported
Option for this protocol corresponds to fine frequency tuning. This value is different for each Module and **must** be accurate otherwise the link will not be stable.
Check the [Frequency Tuning page](/docs/Frequency_Tuning.md) to determine it.
### Sub_protocol LR12 - *0*
Refresh rate: 36ms
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
### Sub_protocol LR12 6ch - *1*
Refresh rate: 18ms
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6
## FRSKYX - *15*
Models: FrSky v1.xxx receivers X4R, X6R and X8R. Protocol also known as D16.
Models: FrSky v1.xxx receivers X4R, X6R and X8R. Protocol also known as D16 v1 FCC/LBT.
Extended limits and failsafe supported
@@ -358,31 +393,38 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
### Sub_protocol EU_16 - *2*
EU-LBT protocol 16 channels @18ms. Note that the LBT part is not implemented, the TX transmits right away.
EU-LBT protocol 16 channels @18ms.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
### Sub_protocol EU_8 - *3*
EU-LBT protocol 8 channels @9ms. Note that the LBT part is not implemented, the TX transmits right away.
EU-LBT protocol 8 channels @9ms.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
### Sub_protocol Cloned - *4*
Use the identifier learnt from another FrSky radio when binding with the FrSkyRX/CloneTX mode.
## FRSKYX2 - *64*
Same as FrSkyX but for v2.1.0.
Same as [FrskyX](Protocols_Details.md#FRSKYX---15) but for D16 v2.1.0 FCC/LBT.
## FRSKYX_RX - *55*
The FrSkyX receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
## FRSKY_RX - *55*
Auto selection of FrSkyD and FrSkyX v1.xxx at bind time.
### Sub_protocol RX - *0*
The FrSky receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
Auto detection of the protocol used by a TX transmitting FrSkyD/D8, FrSkyX/D16 v1.xxx FCC/LBT or FrSkyX/D16 v2.1.0 FCC/LBT at bind time.
Available in OpenTX 2.3.3, Trainer Mode Master/Multi
Extended limits supported
For **FrSkyX, RX num must match on the master and slave**. This enables a multi student configuration for example.
Option for this protocol corresponds to fine frequency tuning.
If the value is equal to 0, the RX will auto tune otherwise it will use the indicated value.
This value is different for each Module and **must** be accurate otherwise the link will not be stable.
@@ -390,19 +432,25 @@ Check the [Frequency Tuning page](/docs/Frequency_Tuning.md) to determine it.
Low power: enable/disable the LNA stage on the RF component to use depending on the distance with the TX.
### Sub_protocol FCC - *0*
FCC protocol 8 or 16 channels.
### Sub_protocol CloneTX - *1*
This subprotocol makes a clone of a TX identifier transmitting FrSkyD/D8, FrSkyX/D16 v1.xxx FCC/LBT and FrSkyX/D16 v2.1.0 FCC/LBT.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
There are 3 slots available, 1 slot for D8 cloning, 1 slot for FrSkyX (D16v1) cloning and 1 slot for FrSkyX2 (D16v2.1.0) cloning.
The same TX or different TXs can be used for each slot but a maximum of 1 per slot.
If you launch the FrSky_RX/CloneTX protocol and do a bind with a TX transmitting with the D8 protocol, it will be saved in the slot D8. Same for D16v1 and D16v2.1 .
Then the system will alow you to enable cloning as you wish for each model using the FrSkyD/X/X2 "Cloned" subprotocol. This way you can have models working with the original MPM indentifier and models which are shared by both the cloned TX and MPM.
### Sub_protocol EU_LBT - *1*
EU_LBT protocol 8 or 16 channels.
Clone mode operation:
- Select the FrSky_RX protocol, subprotocol CloneTX
- Select on the TX to be cloned the protocol you want to clone the identifier from: FrSkyD/D8 or FrSkyX/D16 v1.xxx FCC/LBT or FrSkyX/D16 v2.1.0 FCC/LBT
- Place both the TX and MPM in bind mode
- Wait for the bind to complete
- To use the cloned TX identifier, open a new model select the protocol you just cloned/binded and select the subprotocol "Cloned"
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
Notes:
- OpenTX 2.3.8 N184 (nightly) or later is needed to have access to the "D8Cloned" and "D16Cloned" subprotocols, D16v2.1 "Cloned" is available under FrSkyX2/Cloned.
- For FrSkyD, only the RX number used during bind is cloned -> you can't use RX num anymore
- For FrSkyX and FrSkyX2, RX number has to be adjusted on each model to match the original TX model
## HITEC - *39*
Models: OPTIMA, MINIMA and MICRO receivers.
@@ -453,6 +501,9 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
Basic telemetry is available on OpenTX 2.3.3+ with RX voltage, Rx temperature, RX RSSI, RX LQI, TX RSSI and TX LQI. Lowest the TX_LQI value is best the quality link is, it's a good indicator of how well the module is tuned.
## Scanner - *54*
2.4GHz scanner accessible using the OpenTX 2.3 Spectrum Analyser tool.
## SFHSS - *21*
Models: Futaba RXs and XK models.
@@ -465,8 +516,14 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
## Scanner - *54*
2.4GHz scanner accessible using the OpenTX 2.3 Spectrum Analyser tool.
## Skyartec - *68*
Option for this protocol corresponds to fine frequency tuning. This value is different for each Module and **must** be accurate otherwise the link will not be stable.
Check the [Frequency Tuning page](/docs/Frequency_Tuning.md) to determine it.
CH1|CH2|CH3|CH4|CH5|CH6|CH7
---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7
***
# CYRF6936 RF Module
@@ -880,6 +937,17 @@ A|E|T|R|FMODE|AUX6|AUX7
FMODE and AUX7 have 4 positions: -100%..-50%=>0, -50%..5%=>1, 5%..50%=>2, 50%..100%=>3
## ESKY150V2 - *69*
ESky protocol for small models: 150 V2, F150 V2, Blade 70s(?)
Notes:
- RX output will match the eSky standard TAER independently of the input configuration AETR, RETA... unless on OpenTX 2.3.3+ you use the "Disable channel mapping" feature on the GUI.
- To run this protocol you need both CC2500 and NRF24L01 to be enabled for code reasons, only the CC2500 is really used.
CH1|CH2|CH3|CH4|CH5 |CH6 |CH7 |CH8 |CH9 |CH10|CH11|CH12|CH13|CH14|CH15|CH16
---|---|---|---|----|----|----|----|----|----|----|----|----|----|----|----
A|E|T|R|CH5 |CH6 |CH7 |CH8 |CH9 |CH10|CH11|CH12|CH13|CH14|CH15|CH16
## FX816 - *58*
Model: FEI XIONG FX816 P38
@@ -1107,7 +1175,7 @@ CH1|CH2|CH3|CH4|CH5
A|E|T|R|Warp
## Potensic - *51*
Models: Potensic A20
Model: Potensic A20
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
@@ -1121,6 +1189,17 @@ MODE: Beginner -100%, Medium 0%, Advanced +100%
HEADLESS: Off -100%, On +100%
## PROPEL - *66*
Model: PROPEL 74-Z Speeder Bike
Autobind protocol
Telemetry: RSSI is equal to TX_LQI which indicates how well the TX receives the RX (0-100%). A1 voltage should indicate the numbers of life remaining (not tested). A2 is giving the model status using a bit mask: 0x80=flying, 0x08=taking off, 0x04=landing, 0x00=landed/crashed
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14
---|---|---|---|---|---|---|---|---|----|----|----|----|----
A|E|T|R|LEDs|RollCW|RollCCW|Fire|Weapons|Calib|Alt_Hold|Take_off|Land|Training
## Q2X2 - *29*
### Sub_protocol Q222 - *0*
Models: Q222 v1 and V686 v2
@@ -1187,7 +1266,7 @@ Model: Shenqiwei 1/20 Mini Motorcycle
CH1|CH2|CH3|CH4
---|---|---|---
| |T|R
-|-|T|R
Throttle +100%=full forward,0%=stop,-100%=full backward.
@@ -1332,6 +1411,24 @@ Models: WLtoys V911S, XK A110
### Sub_protocol E119 - *1*
Models: Eachine E119
## XK - *62*
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|----
A|E|T|R|Flight_modes|Take_off|Emerg stop|3D/6G|Picture|Video
Flight_modes: -100%=M-Mode, 0%=6G-Mode, +100%=V-Mode. CH6-CH10 are mementary switches.
### Sub_protocol X450 - *0*
Models: XK X450 (TX=X8)
This protocol is known to be problematic because it's using the xn297L emulation with a transmission speed of 250kbps therefore it doesn't work very well with every modules, this is an hardware issue with the accuracy of the components.
If the model does not respond well to inputs or hard to bind, you can try to switch the emulation from the default NRF24L01 RF component to the CC2500 by using an option value (freq tuning) different from 0. Option in this case is used for fine frequency tuning like any CC2500 protocols so check the [Frequency Tuning page](/docs/Frequency_Tuning.md).
### Sub_protocol X420 - *1*
Models: XK X420/X520 (TX=X4)
## YD717 - *8*
Autobind protocol
@@ -1353,7 +1450,7 @@ Autobind protocol
CH1|CH2|CH3|CH4|CH5
---|---|---|---|---
||T|R|LIGHT
-|-|T|R|LIGHT
# SX1276 RF Module