Compare commits

...

28 Commits

Author SHA1 Message Date
pascallanger
bf38415420 Update SGF22_nrf24l01.ino
Fix tx and freq for none CX10
2025-09-26 17:41:06 +02:00
pascallanger
5ce6c6f544 Update Protocols_Details.md 2025-07-28 11:27:57 +02:00
pascallanger
35f284763a SGF22/CX10 new subprotocol
Only 2 IDs
2025-07-28 11:20:57 +02:00
pascallanger
e35c4d3ce8 WPL 1 ID 2025-07-28 01:06:12 +02:00
pascallanger
ba59605b16 Update WPL_nrf24l01.ino 2025-07-27 19:15:55 +02:00
pascallanger
b88f4d40f4 WPL 5 2025-07-27 18:24:24 +02:00
pascallanger
5ade6bc312 WPL 4th 2025-07-27 16:51:13 +02:00
pascallanger
9e099bc486 WPL 3rd try 2025-07-27 16:42:00 +02:00
pascallanger
48b7430e75 WPL try 2 2025-07-27 16:01:52 +02:00
pascallanger
6385e822c2 MT99xx/SU35: removed autobind 2025-07-27 12:25:14 +02:00
pascallanger
66f8906273 WPL new protocol
Only 1 ID
2025-07-27 12:24:03 +02:00
Jon Sturm
dcbc557bf7 Enable Telemetry on DumbRC receivers (#1111)
Tested with X6FGv1.1, X6FP, X6DC(G)v1.1

I also tested with multiple X6F receivers and some gave RSSI Telem and some gave nothing.
2 of them had the same PCB as the X6FP and neither gave telemetry.
I had a third with the same PCB with the X6FP which did give RSSI
and of my two with an older PCB one gives RSSI telem and the other does not.

Of the receivers I tried only one set packet_in[6] to match the TX packet[1] and it was the
oldest receiver of the ones I own.
2025-05-10 11:51:48 +02:00
pascallanger
e556f5cc40 SGF22 telem improvement? 2025-04-16 07:53:47 +02:00
pascallanger
9ef2415178 Update Protocols_Details.md (#1101) 2025-04-03 18:39:02 +02:00
pascallanger
bc1a809325 Update Protocols_Details.md 2025-04-03 18:36:31 +02:00
pascallanger
082e96e381 DSMR timing 2025-04-02 18:02:44 +02:00
pascallanger
abd26ee113 Update SGF22_nrf24l01.ino 2025-04-02 14:24:18 +02:00
pascallanger
98518b3c92 Update Protocols_Details.md 2025-04-02 14:11:58 +02:00
pascallanger
d19de99172 SGF22 telemetry 2025-04-02 14:10:54 +02:00
pascallanger
13024e3816 Update SGF22_nrf24l01.ino 2025-04-01 23:01:18 +02:00
pascallanger
90fb2d745f Update AFHDS2A_a7105.ino 2025-03-31 22:21:33 +02:00
pascallanger
fa13b67f3a Update Validate.h 2025-03-31 14:56:46 +02:00
pascallanger
10be906bec Update Validate.h 2025-03-31 14:43:42 +02:00
pascallanger
f538884d48 XK2 low batt telemetry 2025-03-28 19:13:13 +01:00
pascallanger
d3e5acf704 Update Protocols_Details.md 2025-03-28 10:33:39 +01:00
pascallanger
2ac4745c62 FX/QF012 telemetry 2025-03-21 21:48:29 +01:00
pascallanger
889e01c7c6 MouldKg update 2025-03-20 17:28:33 +01:00
pascallanger
db5f1f8899 Added AFHDS2A BS4/BS6 support 2025-03-20 14:49:34 +01:00
18 changed files with 766 additions and 324 deletions

View File

@@ -54,10 +54,9 @@
28,1,Flysky_AFHDS2A,PPM_IBUS,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14
28,2,Flysky_AFHDS2A,PWM_SBUS,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14
28,3,Flysky_AFHDS2A,PPM_SBUS,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14
28,4,Flysky_AFHDS2A,PWM_IB16,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14,CH15,CH16
28,5,Flysky_AFHDS2A,PPM_IB16,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14,CH15,CH16
28,6,Flysky_AFHDS2A,PWM_SB16,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14,CH15,CH16
28,7,Flysky_AFHDS2A,PPM_SB16,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14,CH15,CH16
28,4,Flysky_AFHDS2A,Gyro_Off,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,ST_Ga,TH_Ga,Prio,Calib
28,5,Flysky_AFHDS2A,Gyro_On,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,ST_Ga,TH_Ga,Prio,Calib
28,6,Flysky_AFHDS2A,G_On_Rev,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,ST_Ga,TH_Ga,Prio,Calib
56,0,Flysky2A_RX,RX,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14
56,1,Flysky2A_RX,CPPM,0,CH5,CH6,CH7,CH8,CH9,CH10,CH11,CH12,CH13,CH14
53,0,Height,5ch,0,Gear

View File

@@ -183,8 +183,18 @@ uint16_t AFHDS2A_RX_callback()
case AFHDS2A_RX_DATA:
if (AFHDS2A_RX_data_ready()) {
A7105_ReadData(AFHDS2A_RX_TXPACKET_SIZE);
if (memcmp(&packet[1], rx_id, 4) == 0 && memcmp(&packet[5], rx_tx_addr, 4) == 0) {
if (packet[0] == 0x58 && packet[37] == 0x00 && (telemetry_link&0x7F) == 0) { // standard packet, send channels to TX
if (memcmp(&packet[1], rx_id, 4) == 0 && memcmp(&packet[5], rx_tx_addr, 4) == 0)
{
#if 0
//if(packet[0] == 0xAA)
{
for(uint8_t i=0;i<AFHDS2A_RX_TXPACKET_SIZE;i++)
debug(" %02X",packet[i]);
debugln("");
}
#endif
if (packet[0] == 0x58 && packet[37] == 0x00 && (telemetry_link&0x7F) == 0)
{ // standard packet, send channels to TX
int rssi = min(A7105_ReadReg(A7105_1D_RSSI_THOLD),160);
RX_RSSI = map16b(rssi, 160, 8, 0, 128);
AFHDS2A_RX_build_telemetry_packet();

View File

@@ -93,15 +93,16 @@ static void AFHDS2A_update_telemetry()
if (option & 0x80)
{// forward 0xAA and 0xAC telemetry to TX, skip rx and tx id to save space
packet_in[0]= TX_RSSI;
debug("T(%02X)=",packet[0]);
#if 0
debug("T(%02X)=",packet[0]);
for(uint8_t i=9;i < AFHDS2A_RXPACKET_SIZE; i++)
debug(" %02X",packet[i]);
debugln("");
#endif
for(uint8_t i=9;i < AFHDS2A_RXPACKET_SIZE; i++)
{
packet_in[i-8]=packet[i];
debug(" %02X",packet[i]);
}
packet_in[29]=packet[0]; // 0xAA Normal telemetry, 0xAC Extended telemetry
telemetry_link=2;
debugln("");
return;
}
#endif
@@ -186,16 +187,40 @@ static void AFHDS2A_build_packet(uint8_t type)
case AFHDS2A_PACKET_STICKS:
packet[0] = 0x58;
//16 channels + RX_LQI on channel 17
for(uint8_t ch=0; ch<num_ch; ch++)
for(uint8_t ch=0; ch<17; ch++)
{
if(ch == 16 // CH17=RX_LQI
#ifdef AFHDS2A_LQI_CH
|| ch == (AFHDS2A_LQI_CH-1) // override channel with LQI
#endif
)
val = 2000 - 10*RX_LQI;
val = convert_channel_ppm(sub_protocol<AFHDS2A_GYRO_OFF?CH_AETR[ch]:ch); // No remapping for BS receivers
if(ch<14)
{
packet[9 + ch*2] = val;
packet[10 + ch*2] = (val>>8)&0x0F;
}
else
val = convert_channel_ppm(CH_AETR[ch]);
{
if(ch == 16) //CH17=RX_LQI
val = 2000 - 10*RX_LQI;
packet[10 + (ch-14)*6] |= (val)<<4;
packet[12 + (ch-14)*6] |= (val)&0xF0;
packet[14 + (ch-14)*6] |= (val>>4)&0xF0;
}
}
{
uint8_t next_hop = (hopping_frequency_no+1)&0x0F;
packet[34] |= next_hop<<4;
packet[36] |= next_hop?0x80:0x90;
}
break;
case AFHDS2A_PACKET_FAILSAFE:
packet[0] = 0x56;
for(uint8_t ch=0; ch<16; ch++)
{ // Failsafe values
#ifdef FAILSAFE_ENABLE
val = Failsafe_data[protocol==PROTO_AFHDS2A?CH_AETR[ch]:ch]; // No remapping for BS receivers
if(val!=FAILSAFE_CHANNEL_HOLD && val!=FAILSAFE_CHANNEL_NOPULSES)
val = (((val<<2)+val)>>3)+860;
else
#endif
val = 0x0FFF;
if(ch<14)
{
packet[9 + ch*2] = val;
@@ -209,42 +234,6 @@ static void AFHDS2A_build_packet(uint8_t type)
}
}
break;
case AFHDS2A_PACKET_FAILSAFE:
packet[0] = 0x56;
for(uint8_t ch=0; ch<num_ch; ch++)
{
#ifdef FAILSAFE_ENABLE
if(ch<16)
val = Failsafe_data[CH_AETR[ch]];
else
val = FAILSAFE_CHANNEL_NOPULSES;
if(val!=FAILSAFE_CHANNEL_HOLD && val!=FAILSAFE_CHANNEL_NOPULSES)
{ // Failsafe values
val = (((val<<2)+val)>>3)+860;
if(ch<14)
{
packet[9 + ch*2] = val;
packet[10 + ch*2] = (val>>8)&0x0F;
}
else
{
packet[10 + (ch-14)*6] &= 0x0F;
packet[10 + (ch-14)*6] |= (val)<<4;
packet[12 + (ch-14)*6] &= 0x0F;
packet[12 + (ch-14)*6] |= (val)&0xF0;
packet[14 + (ch-14)*6] &= 0x0F;
packet[14 + (ch-14)*6] |= (val>>4)&0xF0;
}
}
else
#endif
if(ch<14)
{ // no values
packet[9 + ch*2] = 0xff;
packet[10+ ch*2] = 0xff;
}
}
break;
case AFHDS2A_PACKET_SETTINGS:
packet[0] = 0xaa;
packet[9] = 0xfd;
@@ -253,17 +242,43 @@ static void AFHDS2A_build_packet(uint8_t type)
if(val<50 || val>400) val=50; // default is 50Hz
packet[11]= val;
packet[12]= val >> 8;
packet[13] = sub_protocol & 0x01; // 1 -> PPM output enabled
packet[14]= 0x00;
for(uint8_t i=15; i<37; i++)
packet[i] = 0xff;
packet[18] = 0x05; // ?
packet[19] = 0xdc; // ?
packet[20] = 0x05; // ?
if(sub_protocol&2)
packet[21] = 0xdd; // SBUS output enabled
memset(&packet[15],0xFF,22);
#ifndef MULTI_AIR
if(sub_protocol < AFHDS2A_GYRO_OFF)
{
#endif
packet[13] = sub_protocol & 0x01; // 1 -> PPM output enabled
packet[14] = 0x00; // ?
packet[18] = 0x05; // ?
packet[19] = 0xdc; // ?
packet[20] = 0x05; // ?
if(sub_protocol&2)
packet[21] = 0xdd; // SBUS output enabled
else
packet[21] = 0xde; // IBUS
#ifndef MULTI_AIR
}
else
packet[21] = 0xde; // IBUS
{//BS receivers
if(sub_protocol == AFHDS2A_GYRO_OFF)
{
memset(&packet[15],0x00,4);
packet[22] = 0xFC; // ?
}
else
{//AFHDS2A_GYRO_ON & AFHDS2A_GYRO_ON_REV
packet[15] = convert_channel_16b_limit(CH13,0,100); // ST Gain
packet[16] = convert_channel_16b_limit(CH14,0,100); // TH Gain
packet[17] = convert_channel_16b_limit(CH15,0,100); // Priority
if(sub_protocol == AFHDS2A_GYRO_ON_REV)
packet[17] |= 0x80; // Reverse
packet[18] = CH16_SW?(0x32|0x80):0x32; // Calib|50?
packet[19] = 0x64; // 100?
packet[20] = 0x64; // 100?
packet[22] = 0xFE; // ?
}
}
#endif
break;
}
packet[37] = 0x00;
@@ -283,6 +298,9 @@ uint16_t AFHDS2A_callback()
static uint16_t packet_counter;
uint8_t data_rx=0;
uint16_t start;
#ifndef MULTI_AIR
static uint16_t Prev_Channel[4] = { 0,0,0,0 };
#endif
#ifndef FORCE_AFHDS2A_TUNING
A7105_AdjustLOBaseFreq(1);
#endif
@@ -367,10 +385,39 @@ uint16_t AFHDS2A_callback()
AFHDS2A_build_packet(packet_type);
data_rx=A7105_ReadReg(A7105_00_MODE); // Check if something has been received...
A7105_WriteData(AFHDS2A_TXPACKET_SIZE, hopping_frequency[hopping_frequency_no++]);
if(hopping_frequency_no >= AFHDS2A_NUMFREQ)
hopping_frequency_no = 0;
hopping_frequency_no &= 0x0F; // AFHDS2A_NUMFREQ
#if 0
for(uint8_t i=0; i<AFHDS2A_TXPACKET_SIZE; i++)
debug(" %02X",packet[i]);
debugln("");
#endif
#ifndef MULTI_AIR
if(sub_protocol > AFHDS2A_GYRO_OFF)
{//Gyro is on
//Check if gyro settings have changed
uint16_t val;
for(uint8_t i=0;i<4;i++)
{
val = Channel_data[CH13+i] - Prev_Channel[i];
if(val&0x8000) val ^= 0xFFFF;
if(val > 10)
{//This setting has significantly changed
Prev_Channel[i] = Channel_data[CH13+i];
packet_sent = 5;
}
}
}
if(packet_sent && (packet_counter%5)==0)
{//Inform the RX of the change
packet_type = AFHDS2A_PACKET_SETTINGS;
packet_sent--;
}
else
#endif
if(!(packet_counter % 1313))
{//Send settings every 5s
packet_type = AFHDS2A_PACKET_SETTINGS;
}
else
{
#ifdef FAILSAFE_ENABLE
@@ -448,9 +495,6 @@ void AFHDS2A_init()
rx_id[i]=eeprom_read_byte((EE_ADDR)(addr+i));
}
hopping_frequency_no = 0;
if(sub_protocol&0x04)
num_ch=17;
else
num_ch=14;
packet_sent = 0;
}
#endif

View File

@@ -292,7 +292,7 @@ uint16_t DSM_callback()
#define DSM_CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
#ifdef STM32_BOARD
#define DSM_WRITE_DELAY 1600 // Time after write to verify write complete
#define DSM_READ_DELAY 400 // Time before write to check read phase, and switch channels.
#define DSM_READ_DELAY 300 // Time before write to check read phase, and switch channels.
#else
#define DSM_WRITE_DELAY 1950 // Time after write to verify write complete
#define DSM_READ_DELAY 600 // Time before write to check read phase, and switch channels.
@@ -470,15 +470,15 @@ uint16_t DSM_callback()
case DSM_CH2_READ_B:
//Read telemetry
rx_phase = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
debug("ST1:%02X ",rx_phase);
//debug("ST1:%02X ",rx_phase);
if((rx_phase & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_phase |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
debug("ST2:%02X ",rx_phase);
//debug("ST2:%02X ",rx_phase);
if((rx_phase & 0x07) == 0x02)
{ // good data (complete with no errors)
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
length=CYRF_ReadRegister(CYRF_09_RX_COUNT);
debug("RX(%d)",length);
//debug("RX(%d)",length);
if(length>TELEMETRY_BUFFER_SIZE-2)
length=TELEMETRY_BUFFER_SIZE-2;
CYRF_ReadDataPacketLen(packet_in+1, length);
@@ -496,7 +496,7 @@ uint16_t DSM_callback()
// debug(" %02X", packet_in[i]);
telemetry_link=1;
}
debugln("");
//debugln("");
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
if (phase == DSM_CH2_READ_A && (sub_protocol==DSM2_1F || sub_protocol==DSMX_1F) && num_ch < 8) // 22ms mode
{

View File

@@ -34,12 +34,14 @@ Multiprotocol is distributed in the hope that it will be useful,
#define FX620_CH_OFFSET 1
#define FX9630_PACKET_PERIOD 8124 //8156 on QIDI-560
#define FX9630_BIND_PACKET_PERIOD 8124
#define FX9630_BIND_CHANNEL 51
#define FX9630_PAYLOAD_SIZE 8
#define FX9630_NUM_CHANNELS 3
#define FX9630_WRITE_TIME 500
#define FX_QF012_PACKET_PERIOD 12194
#define FX_QF012_RX_PAYLOAD_SIZE 3
//#define FORCE_FX620_ID
//#define FORCE_FX9630_ID
//#define FORCE_QIDI_ID
@@ -83,7 +85,7 @@ static void __attribute__((unused)) FX_send_packet()
//Channels
uint8_t val;
if (sub_protocol >= FX9630)
{ // FX9630 & FX_Q560
{ // FX9630 & FX_Q560 & FX_QF012
packet[0] = convert_channel_8b(THROTTLE);
packet[1] = convert_channel_8b(AILERON);
packet[2] = 0xFF - convert_channel_8b(ELEVATOR);
@@ -102,7 +104,7 @@ static void __attribute__((unused)) FX_send_packet()
packet[5] |= GET_FLAG(CH7_SW, 0x40) // QF012 invert flight
| GET_FLAG(CH8_SW, 0x80); // QF012 Restore fine tunning midpoint
}
else // FX816 and FX620
else // FX816 & FX620
{
uint8_t offset=sub_protocol == FX816 ? FX816_CH_OFFSET:FX620_CH_OFFSET;
val=convert_channel_8b(AILERON);
@@ -140,7 +142,7 @@ static void __attribute__((unused)) FX_send_packet()
packet[5] = 0xAB; // Is it based on ID??
}
}
else // FX9630 & FX_Q560
else // FX9630 & FX_Q560 & FX_QF012
{
if(IS_BIND_IN_PROGRESS)
{
@@ -196,7 +198,7 @@ static void __attribute__((unused)) FX_RF_init()
{
XN297_SetTXAddr((uint8_t *)"\x56\x78\x90\x12", 4);
XN297_RFChannel(FX9630_BIND_CHANNEL);
packet_period = FX9630_BIND_PACKET_PERIOD;
packet_period = sub_protocol == FX_QF012 ? FX_QF012_PACKET_PERIOD : FX9630_PACKET_PERIOD;
packet_length = FX9630_PAYLOAD_SIZE;
}
}
@@ -273,7 +275,7 @@ uint16_t FX_callback()
{ // FX9630 & FX_Q560 & FX_QF012
XN297_SetTXAddr(rx_tx_addr, 4);
#ifdef FX_HUB_TELEMETRY
XN297_SetRXAddr(rx_tx_addr,packet_length);
XN297_SetRXAddr(rx_tx_addr, FX_QF012_RX_PAYLOAD_SIZE);
#endif
}
}
@@ -284,12 +286,13 @@ uint16_t FX_callback()
if(rx)
{
debug("RX");
if(XN297_ReadPayload(packet_in, packet_length))
if(XN297_ReadPayload(packet_in, FX_QF012_RX_PAYLOAD_SIZE))
{//Good CRC
//packets: A5 00 11 -> A5 01 11
telemetry_link = 1;
//v_lipo1 = packet_in[1] == 0x03 ? 0x00:0xFF; // low voltage
#if 1
for(uint8_t i=0; i < packet_length; i++)
v_lipo1 = packet_in[1] ? 60:81; // low voltage 3.7V
#if 0
for(uint8_t i=0; i < FX_QF012_RX_PAYLOAD_SIZE; i++)
debug(" %02X", packet_in[i]);
#endif
}

View File

@@ -530,7 +530,7 @@ void MT99XX_init(void)
bind_counter = MT99XX_BIND_COUNT;
if(IS_BIND_DONE)
{
if(sub_protocol != A180 && sub_protocol != DRAGON && sub_protocol != F949G && sub_protocol != PA18+8)
if(sub_protocol != A180 && sub_protocol != DRAGON && sub_protocol != F949G && sub_protocol != PA18+8 && sub_protocol != SU35+8)
BIND_IN_PROGRESS; // autobind protocol
else
bind_counter = 1;

View File

@@ -58,7 +58,7 @@ static void __attribute__((unused)) MOULDKG_send_packet()
n += num_ch<<1;
for(uint8_t i=0;i<6;i++)
{
if(i > 3 && (sub_protocol == MOULDKG_ANALOG4 || i + n > 15))
if( (i > 3 && sub_protocol == MOULDKG_ANALOG4) || i + n > 15)
packet[i+4] = 0x80; //Centered channel
else
packet[i+4] = convert_channel_8b(ch[i]+n);

View File

@@ -25,7 +25,7 @@
25,FrskyV
26,HONTAI,HONTAI,JJRCX1,X5C1,FQ777_951,XKK170
27,OpnLrs
28,AFHDS2A,PWM_IBUS,PPM_IBUS,PWM_SBUS,PPM_SBUS,PWM_IB16,PPM_IB16,PWM_SB16,PPM_SB16
28,AFHDS2A,PWM_IBUS,PPM_IBUS,PWM_SBUS,PPM_SBUS,Gyro_Off,Gyro_On,G_On_Rev
29,Q2X2,Q222,Q242,Q282
30,WK2x01,WK2801,WK2401,W6_5_1,W6_6_1,W6_HEL,W6_HEL_I
31,Q303,Q303,CX35,CX10D,CX10WD

View File

@@ -118,6 +118,7 @@ const char STR_UDIRC[] ="UDIRC";
const char STR_JIABAILE[] ="JIABAILE";
const char STR_KAMTOM[] ="KAMTOM";
const char STR_WL91X[] ="WL91x";
const char STR_WPL[] ="WPL";
const char STR_SUBTYPE_FLYSKY[] = "\x04""Std\0""V9x9""V6x6""V912""CX20";
const char STR_SUBTYPE_HUBSAN[] = "\x04""H107""H301""H501";
@@ -147,7 +148,7 @@ const char STR_SUBTYPE_MT992[] = "\x04""PA18""SU35";
const char STR_SUBTYPE_MJXQ[] = "\x07""WLH08\0 ""X600\0 ""X800\0 ""H26D\0 ""E010\0 ""H26WH\0 ""Phoenix";
const char STR_SUBTYPE_FY326[] = "\x05""Std\0 ""FY319";
const char STR_SUBTYPE_HONTAI[] = "\x06""Std\0 ""JJRCX1""X5C1\0 ""FQ_951""XKK170";
const char STR_SUBTYPE_AFHDS2A[] = "\x08""PWM,IBUS""PPM,IBUS""PWM,SBUS""PPM,SBUS""PWM,IB16""PPM,IB16""PWM,SB16""PPM,SB16";
const char STR_SUBTYPE_AFHDS2A[] = "\x08""PWM,IBUS""PPM,IBUS""PWM,SBUS""PPM,SBUS""Gyro_Off""Gyro_On\0""G_On_Rev";
const char STR_SUBTYPE_Q2X2[] = "\x04""Q222""Q242""Q282";
const char STR_SUBTYPE_WK2x01[] = "\x06""WK2801""WK2401""W6_5_1""W6_6_1""W6_HeL""W6_HeI";
const char STR_SUBTYPE_Q303[] = "\x06""Std\0 ""CX35\0 ""CX10D\0""CX10WD";
@@ -188,7 +189,7 @@ const char STR_SUBTYPE_MOULDKG[] = "\x05""A4444""D4444""A664\0";
const char STR_SUBTYPE_KF606[] = "\x06""KF606\0""MIG320""ZCZ50\0";
const char STR_SUBTYPE_E129[] = "\x04""E129""C186";
const char STR_SUBTYPE_FX[] = "\x05""816\0 ""620\0 ""9630\0""Q560\0""QF012";
const char STR_SUBTYPE_SGF22[] = "\x04""F22\0""F22S""J20\0";
const char STR_SUBTYPE_SGF22[] = "\x04""F22\0""F22S""J20\0""CX10";
const char STR_SUBTYPE_JIABAILE[] = "\x04""Std\0""Gyro";
#define NO_SUBTYPE nullptr
@@ -307,7 +308,7 @@ const mm_protocol_definition multi_protocols[] = {
{PROTO_FLYSKY, STR_FLYSKY, STR_SUBTYPE_FLYSKY, 5, OPTION_NONE, 0, 1, SW_A7105, FLYSKY_init, FLYSKY_callback },
#endif
#if defined(AFHDS2A_A7105_INO)
{PROTO_AFHDS2A, STR_AFHDS2A, STR_SUBTYPE_AFHDS2A, 8, OPTION_SRVFREQ, 1, 1, SW_A7105, AFHDS2A_init, AFHDS2A_callback },
{PROTO_AFHDS2A, STR_AFHDS2A, STR_SUBTYPE_AFHDS2A, 7, OPTION_SRVFREQ, 1, 1, SW_A7105, AFHDS2A_init, AFHDS2A_callback },
#endif
#if defined(AFHDS2A_RX_A7105_INO)
{PROTO_AFHDS2A_RX, STR_AFHDS2A_RX,STR_CPPM, NBR_CPPM, OPTION_NONE, 0, 0, SW_A7105, AFHDS2A_RX_init, AFHDS2A_RX_callback },
@@ -473,7 +474,7 @@ const mm_protocol_definition multi_protocols[] = {
{PROTO_SCORPIO, STR_SCORPIO, NO_SUBTYPE, 0, OPTION_NONE, 0, 0, SW_CYRF, SCORPIO_init, SCORPIO_callback },
#endif
#if defined(SGF22_NRF24L01_INO)
{PROTO_SGF22, STR_SGF22, STR_SUBTYPE_SGF22, 3, OPTION_NONE, 0, 0, SW_NRF, SGF22_init, SGF22_callback },
{PROTO_SGF22, STR_SGF22, STR_SUBTYPE_SGF22, 4, OPTION_NONE, 0, 0, SW_NRF, SGF22_init, SGF22_callback },
#endif
#if defined(SHENQI_NRF24L01_INO)
{PROTO_SHENQI, STR_SHENQI, NO_SUBTYPE, 0, OPTION_NONE, 0, 0, SW_NRF, SHENQI_init, SHENQI_callback },
@@ -518,7 +519,9 @@ const mm_protocol_definition multi_protocols[] = {
#if defined(WL91X_CCNRF_INO)
{PROTO_WL91X, STR_WL91X, NO_SUBTYPE, 0, OPTION_NONE, 0, 0, SW_NRF, WL91X_init, WL91X_callback },
#endif
#if defined(WPL_NRF24L01_INO)
{PROTO_WPL, STR_WPL, NO_SUBTYPE, 0, OPTION_NONE, 0, 0, SW_NRF, WPL_init, WPL_callback },
#endif
#if defined(XERALL_NRF24L01_INO)
{PROTO_XERALL, STR_XERALL, NO_SUBTYPE, 0, OPTION_NONE, 0, 0, SW_NRF, XERALL_init, XERALL_callback },
#endif

View File

@@ -19,7 +19,7 @@
#define VERSION_MAJOR 1
#define VERSION_MINOR 3
#define VERSION_REVISION 4
#define VERSION_PATCH_LEVEL 46
#define VERSION_PATCH_LEVEL 52
#define MODE_SERIAL 0
@@ -134,6 +134,7 @@ enum PROTOCOLS
PROTO_KAMTOM = 104, // =>NRF24L01
PROTO_SHENQI2 = 105, // =>NRF24L01
PROTO_WL91X = 106, // =>CC2500 & NRF24L01
PROTO_WPL = 107, // =>NRF24L01
PROTO_NANORF = 126, // =>NRF24L01
PROTO_TEST = 127, // =>CC2500
@@ -159,14 +160,13 @@ enum Hubsan
};
enum AFHDS2A
{
PWM_IBUS = 0,
PPM_IBUS = 1,
PWM_SBUS = 2,
PPM_SBUS = 3,
PWM_IB16 = 4,
PPM_IB16 = 5,
PWM_SB16 = 6,
PPM_SB16 = 7,
PWM_IBUS = 0,
PPM_IBUS = 1,
PWM_SBUS = 2,
PPM_SBUS = 3,
AFHDS2A_GYRO_OFF = 4,
AFHDS2A_GYRO_ON = 5,
AFHDS2A_GYRO_ON_REV = 6,
};
enum Hisky
{
@@ -499,6 +499,7 @@ enum SGF22
SGF22_F22 = 0,
SGF22_F22S = 1,
SGF22_J20 = 2,
SGF22_CX10 = 3,
};
enum JIABAILE
{

View File

@@ -232,7 +232,7 @@ static void __attribute__((unused)) RLINK_send_packet()
packet[1] |= 0x21; //air 0x21 on dump but it looks to support telemetry at least RSSI
break;
case RLINK_DUMBORC:
packet[1] = 0x00; //always 0x00 on dump
packet[1] |= 0x01; //always 0x00 on dump but does appear to support telemtry on newer transmitters
break;
}
@@ -384,8 +384,9 @@ uint16_t RLINK_callback()
debug("Telem:");
#endif
CC2500_ReadData(packet_in, len);
if(packet_in[0]==RLINK_RX_PACKET_LEN && (packet_in[len-1] & 0x80) && memcmp(&packet[2],rx_tx_addr,RLINK_TX_ID_LEN)==0 && packet_in[6]==packet[1])
if(packet_in[0]==RLINK_RX_PACKET_LEN && (packet_in[len-1] & 0x80) && memcmp(&packet[2],rx_tx_addr,RLINK_TX_ID_LEN)==0 && (packet_in[6]==packet[1] || sub_protocol == RLINK_DUMBORC))
{//Correct telemetry received: length, CRC, ID and type
//packet_in[6] is 0x00 on almost all DumboRC RX so assume it is always valid
#ifdef RLINK_DEBUG_TELEM
for(uint8_t i=0;i<len;i++)
debug(" %02X",packet_in[i]);

View File

@@ -19,22 +19,24 @@ Multiprotocol is distributed in the hope that it will be useful,
#include "iface_xn297.h"
//#define FORCE_SGF22_ORIGINAL_ID
#define FORCE_SGF22_CX10_ORIGINAL_ID
#define SGF22_PACKET_PERIOD 11950 //10240
#define SGF22_BIND_RF_CHANNEL 78
#define SGF22_PAYLOAD_SIZE 12
#define SGF22_BIND_COUNT 50
#define SGF22_RF_NUM_CHANNELS 4
#define SGF22_F22S_BIND_RF_CHANNEL 10
#define SGF22_J20_BIND_RF_CHANNEL 28
#define SGF22_PACKET_PERIOD 11950 //10240
#define SGF22_PAYLOAD_SIZE 12
#define SGF22_BIND_COUNT 50
#define SGF22_RF_NUM_CHANNELS 4
#define SGF22_BIND_RF_CHANNEL 78
#define SGF22_F22S_BIND_RF_CHANNEL 10
#define SGF22_J20_BIND_RF_CHANNEL 28
#define SGF22_CX10_BIND_RF_CHANNEL 48
//packet[8]
#define SGF22_FLAG_3D 0x00
#define SGF22_FLAG_LIGHT 0x04
#define SGF22_FLAG_ROLL 0x08
#define SGF22_FLAG_VIDEO 0x10
#define SGF22_FLAG_6G 0x40
#define SGF22_FLAG_VERTICAL 0xC0
#define SGF22_FLAG_3D 0x00
#define SGF22_FLAG_LIGHT 0x04
#define SGF22_FLAG_ROLL 0x08
#define SGF22_FLAG_VIDEO 0x10
#define SGF22_FLAG_6G 0x40
#define SGF22_FLAG_VERTICAL 0xC0
#define SGF22_J20_FLAG_HORIZONTAL 0x80
//#define SGF22_J20_FLAG_SPEED 0x01 // Up/Down trim, not implemented
@@ -44,9 +46,18 @@ Multiprotocol is distributed in the hope that it will be useful,
//packet[9]
#define SGF22_FLAG_TRIMRESET 0x04
#define SGF22_FLAG_PHOTO 0x40 // #define SGF22_J20_FLAG_INVERT 0x40
#define SGF22_J20_FLAG_FIXHEIGHT 0x80
#define SGF22_FLAG_TRIMRESET 0x04
#define SGF22_FLAG_PHOTO 0x40 // #define SGF22_J20_FLAG_INVERT 0x40
#define SGF22_J20_FLAG_FIXHEIGHT 0x80
#define SGF22_WRITE_TIME 1000
enum {
SGF22_DATA1,
SGF22_DATA2,
SGF22_DATA3,
SGF22_RX,
};
static void __attribute__((unused)) SGF22_send_packet()
{
@@ -70,26 +81,43 @@ static void __attribute__((unused)) SGF22_send_packet()
packet_sent = 0;
//packet
packet[0] = 0x1B;
packet[8] = SGF22_FLAG_3D // CH5 -100%, F22 & F22S - 3D mode, J20 - Gyro off
| GET_FLAG(CH6_SW, SGF22_FLAG_ROLL) // roll
| GET_FLAG(CH7_SW, SGF22_FLAG_LIGHT) // push up throttle trim for light in the stock TX
| GET_FLAG(CH9_SW, SGF22_FLAG_VIDEO) // push down throttle trim for video in the stock TX
| GET_FLAG(CH11_SW, SGF22_FX922_FLAG_BALANCE)
| GET_FLAG(CH12_SW, SGF22_FX922_FLAG_BALANCEHIGH);
if(Channel_data[CH5] > CHANNEL_MAX_COMMAND)
packet[8] |= SGF22_FLAG_VERTICAL; // CH5 100%, vertical mode (torque)
else if(Channel_data[CH5] > CHANNEL_MIN_COMMAND )
if (sub_protocol != SGF22_CX10)
{//SGF22_F22,SGF22_F22S,SGF22_J20
packet[8] = SGF22_FLAG_3D // CH5 -100%, F22 & F22S - 3D mode, J20 - Gyro off
| GET_FLAG(CH6_SW, SGF22_FLAG_ROLL) // roll
| GET_FLAG(CH7_SW, SGF22_FLAG_LIGHT) // push up throttle trim for light in the stock TX
| GET_FLAG(CH9_SW, SGF22_FLAG_VIDEO) // push down throttle trim for video in the stock TX
| GET_FLAG(CH11_SW, SGF22_FX922_FLAG_BALANCE)
| GET_FLAG(CH12_SW, SGF22_FX922_FLAG_BALANCEHIGH);
if(Channel_data[CH5] > CHANNEL_MAX_COMMAND)
packet[8] |= SGF22_FLAG_VERTICAL; // CH5 100%, vertical mode (torque)
else if(Channel_data[CH5] > CHANNEL_MIN_COMMAND )
packet[8] |= ( sub_protocol == SGF22_J20 ? SGF22_J20_FLAG_HORIZONTAL : SGF22_FLAG_6G ); // CH5 0%, F22 & F22S - 6G mode, J20 - Horizontal mode
packet[9] = GET_FLAG(CH8_SW, SGF22_FLAG_PHOTO) // F22: photo, press in throttle trim in the stock TX, J20: invert flight
}
else //SGF22_CX10 114548
{
if(CH6_SW)
flags = 0x06; // high rate
else
if(Channel_data[CH6] < CHANNEL_MIN_COMMAND)
flags = 0x04; // low rate
else
flags = 0x05; // mid rate
packet[8] = flags
| GET_FLAG(CH5_SW, 0x08); // flip
}
packet[9] = GET_FLAG(CH8_SW, SGF22_FLAG_PHOTO) // F22: photo, press in throttle trim in the stock TX, J20: invert flight
| GET_FLAG(CH10_SW, ( sub_protocol == SGF22_J20 ? SGF22_J20_FLAG_FIXHEIGHT : SGF22_FLAG_TRIMRESET )) ; // F22: Both sticks down inwards in the stock TX, J20: Altitude hold
packet[10] = 0x42; // no fine tune
packet[11] = 0x10; // no fine tune
packet[10] = 0x42; // no fine tune
packet[11] = 0x10; // no fine tune
}
if(sub_protocol == SGF22_F22S)
packet[0] += 6;
else if (sub_protocol == SGF22_J20)
packet[0] += 3;
packet[1] = packet_count; // sequence
else if (sub_protocol == SGF22_CX10)
packet[0] += 0x6A;
packet[1] = packet_count; // sequence
packet[2] = rx_tx_addr[2];
packet[3] = rx_tx_addr[3];
packet[4] = convert_channel_8b(THROTTLE);
@@ -99,7 +127,10 @@ static void __attribute__((unused)) SGF22_send_packet()
XN297_SetPower();
XN297_SetTxRxMode(TX_EN);
XN297_WriteEnhancedPayload(packet, SGF22_PAYLOAD_SIZE,0);
if (sub_protocol != SGF22_CX10)
XN297_WriteEnhancedPayload(packet, SGF22_PAYLOAD_SIZE,0);
else
XN297_WritePayload(packet, SGF22_PAYLOAD_SIZE);
#if 0
debug_time("");
for(uint8_t i=0; i<SGF22_PAYLOAD_SIZE; i++)
@@ -123,7 +154,7 @@ static void __attribute__((unused)) SGF22_initialize_txid()
{ 0x18, 0x37, 0x27, 0x47 } };
memcpy(hopping_frequency, &hop[val], SGF22_RF_NUM_CHANNELS);
/*//Same code sze...
/*//Same code size...
hopping_frequency[0] = 0x0C + 3 * val;
hopping_frequency[1] = hopping_frequency[0] + 0x1E;
if(val > 1) hopping_frequency[1]++;
@@ -136,6 +167,23 @@ static void __attribute__((unused)) SGF22_initialize_txid()
rx_tx_addr[3] = 0x61; // TX2:51 TX3:0C
memcpy(hopping_frequency,"\x15\x34\x24\x44", SGF22_RF_NUM_CHANNELS); //Original dump=>21=0x15,52=0x34,36=0x24,68=0x44
#endif
#ifdef FORCE_SGF22_CX10_ORIGINAL_ID
if(sub_protocol == SGF22_CX10)
{
if(rx_tx_addr[3] & 1)
{
rx_tx_addr[2] = 0x4C;
rx_tx_addr[3] = 0xD7;
memcpy(hopping_frequency, "\x37\x42\x47\x3c", SGF22_RF_NUM_CHANNELS);
}
else
{
rx_tx_addr[2] = 0x50;
rx_tx_addr[3] = 0xE1;
memcpy(hopping_frequency, "\x3b\x4b\x46\x41", SGF22_RF_NUM_CHANNELS);
}
}
#endif
#if 0
debug("ID: %02X %02X, C: ",rx_tx_addr[2],rx_tx_addr[3]);
for(uint8_t i=0; i<SGF22_RF_NUM_CHANNELS; i++)
@@ -148,34 +196,97 @@ static void __attribute__((unused)) SGF22_RF_init()
{
XN297_Configure(XN297_CRCEN, XN297_SCRAMBLED, XN297_1M);
XN297_SetTXAddr((uint8_t*)"\xC7\x95\x3C\xBB\xA5", 5);
const uint8_t bind_chan[] = {SGF22_BIND_RF_CHANNEL, SGF22_F22S_BIND_RF_CHANNEL, SGF22_J20_BIND_RF_CHANNEL};
#ifdef SGF22_HUB_TELEMETRY
XN297_SetRXAddr((uint8_t*)"\xC7\x95\x3C\xBB\xA5", SGF22_PAYLOAD_SIZE);
#endif
const uint8_t bind_chan[] = {SGF22_BIND_RF_CHANNEL, SGF22_F22S_BIND_RF_CHANNEL, SGF22_J20_BIND_RF_CHANNEL, SGF22_CX10_BIND_RF_CHANNEL};
XN297_RFChannel(bind_chan[sub_protocol]); // Set bind channel
}
uint16_t SGF22_callback()
{
if(phase == 0)
#ifdef SGF22_HUB_TELEMETRY
bool rx = false;
static uint8_t telem_count = 0;
#endif
switch(phase)
{
phase++;
#ifdef MULTI_SYNC
telemetry_set_input_sync(SGF22_PACKET_PERIOD);
#endif
SGF22_send_packet();
if(IS_BIND_IN_PROGRESS)
{
if(--bind_counter==0)
BIND_DONE;
}
}
else
{//send 3 times in total the same packet
XN297_ReSendPayload();
phase++;
if(phase > 2)
{
phase = 0;
return SGF22_PACKET_PERIOD - 2*1550;
}
case SGF22_DATA1:
#ifdef MULTI_SYNC
telemetry_set_input_sync(SGF22_PACKET_PERIOD);
#endif
#ifdef SGF22_HUB_TELEMETRY
rx = XN297_IsRX();
XN297_SetTxRxMode(TXRX_OFF);
#endif
SGF22_send_packet();
if(IS_BIND_IN_PROGRESS)
{
if(--bind_counter==0)
BIND_DONE;
}
#ifdef SGF22_HUB_TELEMETRY
if(rx)
{
uint8_t p_len = XN297_ReadEnhancedPayload(packet_in, SGF22_PAYLOAD_SIZE);
if(p_len == 3 && packet_in[0] == rx_tx_addr[2] && packet_in[1] == rx_tx_addr[3])
{//packets: 00 0B 00 -> 00 0B 01
telemetry_link = 1;
v_lipo1 = packet_in[2] ? 0 : 255; //2.9V for 1S, 7.0V for 2S
telemetry_lost = 0;
telem_count = 0;
}
#if 0
debug("L %d ",p_len);
debug("RX");
for(uint8_t i=0; i<SGF22_PAYLOAD_SIZE; i++)
debug(" %02X",packet_in[i]);
debugln("");
#endif
}
if(telem_count > 4*63) // Around 3.5sec with no telemetry
telemetry_lost = 1;
else
{
telem_count++;
if(!telemetry_lost && (telem_count & 0x3F) == 0)
{// Should have received a telem packet but... Send telem to the radio to keep it alive
telemetry_link = 1;
#if 0
debugln("Miss");
#endif
}
}
#endif
phase++;
break;
case SGF22_DATA2:
case SGF22_DATA3:
//send 3 times in total the same packet
XN297_ReSendPayload();
phase++;
break;
default: //SGF22_RX
#ifdef SGF22_HUB_TELEMETRY
/*{ // Wait for packet to be sent before switching to receive mode
uint16_t start=(uint16_t)micros(), count=0;
while ((uint16_t)((uint16_t)micros()-(uint16_t)start) < 500)
{
if(XN297_IsPacketSent())
break;
count++;
}
debugln("%d",count);
}*/
//Switch to RX
XN297_SetTxRxMode(TXRX_OFF);
XN297_SetTxRxMode(RX_EN);
#endif
phase = SGF22_DATA1;
return SGF22_PACKET_PERIOD - 3*1550;
}
return 1550;
}
@@ -187,7 +298,11 @@ void SGF22_init()
SGF22_RF_init();
bind_counter=SGF22_BIND_COUNT;
packet_sent = packet_count = 0x26; // TX2:26 TX3:26
phase = 0;
phase = SGF22_DATA1;
#ifdef SGF22_HUB_TELEMETRY
RX_RSSI = 100; // Dummy value
telemetry_lost = 1;
#endif
}
#endif

View File

@@ -244,7 +244,7 @@ uint16_t V761_callback()
else
{
packet_count++;
if(!telemetry_lost && !rx && (packet_count%64) == 0)
if(!telemetry_lost && !rx && (packet_count & 0x3F) == 0)
{// Should have received a telem packet but... Send telem to the radio to keep it alive
telemetry_link = 1;
#ifdef V761_TELEM_DEBUG

View File

@@ -341,6 +341,7 @@
#undef SYMAX_NRF24L01_INO
#undef V2X2_NRF24L01_INO
#undef V761_NRF24L01_INO
#undef WPL_NRF24L01_INO
#undef XERALL_NRF24L01_INO
#undef YD717_NRF24L01_INO
#undef YUXIANG_NRF24L01_INO
@@ -390,7 +391,7 @@
#undef LOSI_CYRF6936_INO //Need DSM to be enabled
#undef TRAXXAS_CYRF6936_INO
#undef EAZYRC_NRF24L01_INO
#undef KYOSHO2_NRF24L01_INO
//#undef KYOSHO2_NRF24L01_INO
#undef KYOSHO3_CYRF6936_INO
#undef MOULDKG_NRF24L01_INO
#undef SHENQI_NRF24L01_INO
@@ -399,6 +400,10 @@
#undef UDIRC_CCNRF_INO
#undef KAMTOM_NRF24L01_INO
#undef WL91X_CCNRF_INO
#undef WPL_NRF24L01_INO
//Save flash space...
#undef CABELL_NRF24L01_INO
#undef REDPINE_CC2500_INO
#endif
#ifdef MULTI_SURFACE
@@ -495,6 +500,8 @@
#undef OMP_HUB_TELEMETRY
#undef V761_HUB_TELEMETRY
#undef FX_HUB_TELEMETRY
#undef XK2_HUB_TELEMETRY
#undef SGF22_HUB_TELEMETRY
#undef KAMTOM_HUB_TELEMETRY
#undef YUXIANG_HUB_TELEMETRY
#undef RLINK_HUB_TELEMETRY
@@ -538,6 +545,12 @@
#if not defined(FX_NRF24L01_INO)
#undef FX_HUB_TELEMETRY
#endif
#if not defined(XK2_CCNRF_INO)
#undef XK2_HUB_TELEMETRY
#endif
#if not defined(SGF22_NRF24L01_INO)
#undef SGF22_HUB_TELEMETRY
#endif
#if not defined(KAMTOM_NRF24L01_INO)
#undef KAMTOM_HUB_TELEMETRY
#endif
@@ -601,7 +614,7 @@
//protocols using FRSKYD user frames
#undef HUB_TELEMETRY
#endif
#if not defined(HOTT_FW_TELEMETRY) && not defined(DSM_TELEMETRY) && not defined(SPORT_TELEMETRY) && not defined(HUB_TELEMETRY) && not defined(HUBSAN_HUB_TELEMETRY) && not defined(BUGS_HUB_TELEMETRY) && not defined(NCC1701_HUB_TELEMETRY) && not defined(BAYANG_HUB_TELEMETRY) && not defined(CABELL_HUB_TELEMETRY) && not defined(RLINK_HUB_TELEMETRY) && not defined(AFHDS2A_HUB_TELEMETRY) && not defined(AFHDS2A_FW_TELEMETRY) && not defined(MULTI_TELEMETRY) && not defined(MULTI_STATUS) && not defined(HITEC_HUB_TELEMETRY) && not defined(HITEC_FW_TELEMETRY) && not defined(SCANNER_TELEMETRY) && not defined(FRSKY_RX_TELEMETRY) && not defined(AFHDS2A_RX_TELEMETRY) && not defined(BAYANG_RX_TELEMETRY) && not defined(DEVO_HUB_TELEMETRY) && not defined(PROPEL_HUB_TELEMETRY) && not defined(OMP_HUB_TELEMETRY) && not defined(V761_HUB_TELEMETRY) && not defined(FX_HUB_TELEMETRY) && not defined(KAMTOM_HUB_TELEMETRY) && not defined(YUXIANG_HUB_TELEMETRY) && not defined(WFLY2_HUB_TELEMETRY) && not defined(LOLI_HUB_TELEMETRY) && not defined(MLINK_HUB_TELEMETRY) && not defined(MLINK_FW_TELEMETRY) && not defined(MT99XX_HUB_TELEMETRY) && not defined(MULTI_CONFIG_INO)
#if not defined(HOTT_FW_TELEMETRY) && not defined(DSM_TELEMETRY) && not defined(SPORT_TELEMETRY) && not defined(HUB_TELEMETRY) && not defined(HUBSAN_HUB_TELEMETRY) && not defined(BUGS_HUB_TELEMETRY) && not defined(NCC1701_HUB_TELEMETRY) && not defined(BAYANG_HUB_TELEMETRY) && not defined(CABELL_HUB_TELEMETRY) && not defined(RLINK_HUB_TELEMETRY) && not defined(AFHDS2A_HUB_TELEMETRY) && not defined(AFHDS2A_FW_TELEMETRY) && not defined(MULTI_TELEMETRY) && not defined(MULTI_STATUS) && not defined(HITEC_HUB_TELEMETRY) && not defined(HITEC_FW_TELEMETRY) && not defined(SCANNER_TELEMETRY) && not defined(FRSKY_RX_TELEMETRY) && not defined(AFHDS2A_RX_TELEMETRY) && not defined(BAYANG_RX_TELEMETRY) && not defined(DEVO_HUB_TELEMETRY) && not defined(PROPEL_HUB_TELEMETRY) && not defined(OMP_HUB_TELEMETRY) && not defined(V761_HUB_TELEMETRY) && not defined(SGF22_HUB_TELEMETRY) && not defined(XK2_HUB_TELEMETRY) && not defined(FX_HUB_TELEMETRY) && not defined(KAMTOM_HUB_TELEMETRY) && not defined(YUXIANG_HUB_TELEMETRY) && not defined(WFLY2_HUB_TELEMETRY) && not defined(LOLI_HUB_TELEMETRY) && not defined(MLINK_HUB_TELEMETRY) && not defined(MLINK_FW_TELEMETRY) && not defined(MT99XX_HUB_TELEMETRY) && not defined(MULTI_CONFIG_INO)
#undef TELEMETRY
#undef INVERT_TELEMETRY
#undef MULTI_TELEMETRY

View File

@@ -0,0 +1,158 @@
/*
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 WPL "Basic" TX models D12, D12KM, D22, D32, D42, D14
#if defined(WPL_NRF24L01_INO)
#include "iface_xn297.h"
#define FORCE_WPL_ORIGINAL_ID
#define WPL_PACKET_PERIOD 9875
#define WPL_RF_NUM_CHANNELS 4
#define WPL_PAYLOAD_SIZE 16
#define WPL_BIND_COUNT 303 //3sec
static void __attribute__((unused)) WPL_send_packet()
{
#if 0
debug("no:%d, rf:%d, ",hopping_frequency_no + (IS_BIND_IN_PROGRESS?0:4),hopping_frequency[hopping_frequency_no + (IS_BIND_IN_PROGRESS?0:4)]);
#endif
XN297_Hopping(hopping_frequency_no + (IS_BIND_IN_PROGRESS?0:4) );
hopping_frequency_no++;
hopping_frequency_no &= WPL_RF_NUM_CHANNELS-1; // 4 RF channels
memset(&packet[8],0,7);
packet[0] = 0x94; //??
packet[1] = 0x16; //??
packet[2] = 0xCC; //??
if(IS_BIND_IN_PROGRESS)
{
memcpy(&packet[3],rx_tx_addr,5);
packet[9] = 0x08; // ?? Not bound + Headlights on
}
else
{
packet[3 ] = convert_channel_s8b(CH1); // Throttle
packet[4 ] = convert_channel_s8b(CH2); // Steering
packet[5 ] = convert_channel_16b_limit(CH3,0x22,0x5E); // Steering trim
packet[6 ] = rx_tx_addr[3]; // 0x32??
packet[7 ] = convert_channel_s8b(CH4); // Aux
packet[9 ] = 0x80 // ?? Bound
| GET_FLAG(CH5_SW, 0x08) // Headlights 100%=on
| GET_FLAG(CH6_SW, 0x04) // Throttle rate 100%=high
| GET_FLAG(CH7_SW, 0x02); // Steering rate 100%=high
}
uint8_t sum = 0x66;
for(uint8_t i=0;i<WPL_PAYLOAD_SIZE-1;i++)
sum += packet[i];
packet[WPL_PAYLOAD_SIZE-1] = sum;
// Send
XN297_SetPower();
XN297_SetTxRxMode(TX_EN);
XN297_WritePayload(packet, WPL_PAYLOAD_SIZE);
#if 0
for(uint8_t i=0; i<WPL_PAYLOAD_SIZE; i++)
debug(" %02X",packet[i]);
debugln("");
#endif
}
static void __attribute__((unused)) WPL_RF_init()
{
XN297_Configure(XN297_CRCEN, XN297_SCRAMBLED, XN297_1M);
XN297_SetTXAddr((uint8_t*)"\x69\xA5\x37\x4D\x8B", 5);
XN297_HoppingCalib(WPL_RF_NUM_CHANNELS*2); // Calibrate bind and normal channels
}
static void __attribute__((unused)) WPL_initialize_txid()
{
//Bind frequencies
memcpy(hopping_frequency ,"\x17\x25\x46\x36", WPL_RF_NUM_CHANNELS); //23=17, 37=25, 70=46, 54=36
#ifdef FORCE_WPL_ORIGINAL_ID
//Original ID
memcpy(rx_tx_addr,"\x96\x2A\xA9\x32\xB4",5);
//Normal frequencies
memcpy(hopping_frequency+4,"\x0C\x2A\x3D\x1D", WPL_RF_NUM_CHANNELS); //12=0C, 42=2A, 61=3D, 29=1D
#endif
}
uint16_t WPL_callback()
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(WPL_PACKET_PERIOD);
#endif
if(bind_counter)
if(--bind_counter==0)
{
BIND_DONE;
XN297_SetTXAddr(rx_tx_addr, 5);
}
WPL_send_packet();
return WPL_PACKET_PERIOD;
}
void WPL_init()
{
BIND_IN_PROGRESS; // autobind protocol
WPL_initialize_txid();
WPL_RF_init();
hopping_frequency_no = 0;
bind_counter=WPL_BIND_COUNT;
}
#endif
/* https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues/1120
Bind packet
-----------
XN297 1Mb Scrambled
Bind address: 69 A5 37 4D 8B
RF channels: 23, 37, 70, 54
Timing: 9875µs
Payload 16 bytes: 94 16 CC 96 2A A9 32 B4 00 08 00 00 00 00 00 33
P[0] = 94 ??
P[1] = 16 ??
P[2] = CC ??
P[3..7] = Normal address
P[8] = 00 ??
P[9] = 08 ?? not bound?, Throttle and Steering rate low, Headlights on
P[10..14] = 00 ??
P[15] = sum(P[0..14])+66 why 66...
Normal packet
-----------
XN297 1Mb Scrambled
Normal address: 96 2A A9 32 B4
RF channels: 12=0C, 42=2A, 61=3D, 29=1D -> no idea where they come from...
Timing: 9875µs
Payload 16 bytes: 94 16 CC 80 80 38 32 80 00 88 00 00 00 00 00 4E
P[0] = 94 ??
P[1] = 16 ??
P[2] = CC ??
P[3] = Throttle, not enough data on dumps... Same coding as Steering?
P[4] = Steering, not enough data on dumps, looks like one side goes from 7F to 00 and the other 80 to FF which would be s8b
P[5] = Steering trim 22..5E, mid gives 40 not 38... Was the trim centered on the other dumps with value 38?
P[6] = 32 ?? Left over from the bind packet TX_ADDR[3]?
P[7] = 80 ?? Additional channel? It moves at the same time as the trim but my guess is that it is an unconnected channel.
P[8] = 00 ??
P[9] = 80 ?? bound?, Throttle and Steering rate low, Headlights off
|02 -> Steering rate high
|04 -> Throttle rate high
|08 -> Headlights on
P[10..14] = 00 ??
P[15] = sum(P[0..14])+66 why 66...
*/

View File

@@ -21,19 +21,30 @@ Multiprotocol is distributed in the hope that it will be useful,
//#define FORCE_XK2_ID
//#define FORCE_XK2_P10_ID
#define XK2_RF_BIND_CHANNEL 71
#define XK2_RF_BIND_CHANNEL 71
#define XK2_P10_RF_BIND_CHANNEL 69
#define XK2_PAYLOAD_SIZE 9
#define XK2_PACKET_PERIOD 4911
#define XK2_RF_NUM_CHANNELS 4
#define XK2_PAYLOAD_SIZE 9
#define XK2_PACKET_PERIOD 4911
#define XK2_RF_NUM_CHANNELS 4
#define XK2_WRITE_TIME 1000
enum {
XK2_BIND1,
XK2_BIND2,
XK2_DATA_PREP,
XK2_DATA
XK2_DATA,
XK2_RX,
};
static uint8_t __attribute__((unused)) XK2_checksum(uint8_t init)
{
for(uint8_t i=0; i<XK2_PAYLOAD_SIZE-1; i++)
init += packet[i];
if(sub_protocol == XK2_P10)
init += 0x10;
return init;
}
static void __attribute__((unused)) XK2_send_packet()
{
static uint8_t trim_ch=0;
@@ -47,8 +58,6 @@ static void __attribute__((unused)) XK2_send_packet()
//memcpy(&packet[4], rx_id , 3);
//Unknown
packet[7] = 0x00;
//Checksum seed
packet[8] = 0xC0;
}
else
{
@@ -77,19 +86,13 @@ static void __attribute__((unused)) XK2_send_packet()
packet[5] |= 0x10; //Gyro off (senior mode)
else if(Channel_data[CH6] > CHANNEL_MIN_COMMAND)
packet[5] |= 0x08; //3D
//Telemetry not received=00, Telemetry received=01 but sometimes switch to 1 even if telemetry is not there...
packet[6] = 0x00;
//Requiest telemetry flag
packet[6] = 0x01;
//RXID checksum
packet[7] = crc8; //Sum RX_ID[0..2]
//Checksum seed
packet[8] = num_ch; //Based on TX ID
}
//Checksum
for(uint8_t i=0; i<XK2_PAYLOAD_SIZE-1; i++)
packet[8] += packet[i];
if(sub_protocol == XK2_P10)
packet[8] += 0x10;
packet[8] = XK2_checksum(IS_BIND_IN_PROGRESS ? 0xC0 : num_ch);
// Send
XN297_SetFreqOffset();
@@ -160,6 +163,8 @@ static void __attribute__((unused)) XK2_initialize_txid()
uint16_t XK2_callback()
{
static bool rx = false;
switch(phase)
{
case XK2_BIND1:
@@ -178,13 +183,8 @@ uint16_t XK2_callback()
debug(" %02X",packet[i]);
debugln("");
#endif
crc8 = 0xBF;
for(uint8_t i=0; i<XK2_PAYLOAD_SIZE-1; i++)
crc8 += packet[i];
if(sub_protocol == XK2_P10)
crc8 += 0x10;
if(crc8 != packet[8])
{
if(XK2_checksum(0xBF) != packet[8])
{//Wrong checksum
phase = XK2_BIND1;
return 1000;
}
@@ -209,23 +209,67 @@ uint16_t XK2_callback()
XN297_SetTxRxMode(TXRX_OFF);
XN297_SetTxRxMode(TX_EN);
XN297_SetTXAddr(rx_tx_addr, 5);
#ifdef XK2_HUB_TELEMETRY
XN297_SetRXAddr(rx_tx_addr, XK2_PAYLOAD_SIZE);
#endif
BIND_DONE;
phase++;
case XK2_DATA:
#ifdef MULTI_SYNC
telemetry_set_input_sync(XK2_PACKET_PERIOD);
#endif
#ifdef XK2_HUB_TELEMETRY
rx = XN297_IsRX();
XN297_SetTxRxMode(TXRX_OFF);
#endif
XK2_send_packet();
#ifdef XK2_HUB_TELEMETRY
if(rx)
{
XN297_ReadPayload(packet, XK2_PAYLOAD_SIZE);
#if 0
debug("RX");
for(uint8_t i=0; i<XK2_PAYLOAD_SIZE; i++)
debug(" %02X",packet[i]);
debugln("");
#endif
if(XK2_checksum(0xCC) == packet[8] && memcmp(packet, rx_tx_addr, 3) == 0)
{//Good checksum and TXID
//packets: E5 20 F2 00 00 00 00 00 C3 -> E5 20 F2 80 00 00 00 00 43
telemetry_link = 1;
v_lipo1 = packet[3] ? 137:162; // low voltage 7.1V
}
}
#endif
if(bind_counter)
{
bind_counter--;
if(bind_counter == 0)
{
phase = XK2_DATA_PREP;
//phase = XK2_BIND1;
}
break;
}
XK2_send_packet();
#ifndef XK2_HUB_TELEMETRY
break;
#else
phase++;
return XK2_WRITE_TIME;
default: //XK2_RX
/*{ // Wait for packet to be sent before switching to receive mode
uint16_t start=(uint16_t)micros(), count=0;
while ((uint16_t)((uint16_t)micros()-(uint16_t)start) < 500)
{
if(XN297_IsPacketSent())
break;
count++;
}
debugln("%d",count);
}*/
//Switch to RX
XN297_SetTxRxMode(TXRX_OFF);
XN297_SetTxRxMode(RX_EN);
phase = XK2_DATA;
return XK2_PACKET_PERIOD-XK2_WRITE_TIME;
#endif
}
return XK2_PACKET_PERIOD;
}
@@ -242,6 +286,9 @@ void XK2_init()
phase = XK2_DATA_PREP;
bind_counter = 0;
hopping_frequency_no = 0;
#ifdef XK2_HUB_TELEMETRY
RX_RSSI = 100; // Dummy value
#endif
}
#endif

View File

@@ -211,7 +211,7 @@
#define FRSKYL_CC2500_INO
#define FRSKYD_CC2500_INO
#define FRSKYV_CC2500_INO
#define FRSKYX_CC2500_INO
#define FRSKYX_CC2500_INO //Include FRSKYX2 protocol
#define FRSKY_RX_CC2500_INO
#define HITEC_CC2500_INO
#define HOTT_CC2500_INO
@@ -261,6 +261,7 @@
#define SYMAX_NRF24L01_INO
#define V2X2_NRF24L01_INO
#define V761_NRF24L01_INO
#define WPL_NRF24L01_INO
#define XERALL_NRF24L01_INO
#define YD717_NRF24L01_INO
#define YUXIANG_NRF24L01_INO
@@ -302,11 +303,6 @@
//Enable DSM Forward Programming
#define DSM_FWD_PGM
//AFHDS2A specific settings
//-------------------------
//When enabled (remove the "//"), the below setting makes LQI (Link Quality Indicator) available on one of the RX ouput channel (5-14).
//#define AFHDS2A_LQI_CH 14
/**************************/
/*** FAILSAFE SETTINGS ***/
/**************************/
@@ -355,6 +351,8 @@
#define V761_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define KAMTOM_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define FX_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define XK2_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define SGF22_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define YUXIANG_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define PROPEL_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define CABELL_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
@@ -568,10 +566,9 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
PPM_IBUS
PWM_SBUS
PPM_SBUS
PWM_IB16
PPM_IB16
PWM_SB16
PPM_SB16
AFHDS2A_GYRO_OFF
AFHDS2A_GYRO_ON
AFHDS2A_GYRO_ON_REV
PROTO_AFHDS2A_RX
NONE
PROTO_ASSAN
@@ -838,6 +835,7 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
SGF22
F22S
J20
CX10
PROTO_SHENQI
NONE
PROTO_SHENQI2
@@ -880,6 +878,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
W6_6_1
W6_HEL
W6_HEL_I
PROTO_WPL
NONE
PROTO_XERALL
NONE
PROTO_XK

View File

@@ -61,107 +61,108 @@ You've upgraded the module but the radio does not display the name of the protoc
# Available Protocol Table of Contents (Listed Alphabetically)
Protocol Name|Protocol Number|Sub_Proto 0|Sub_Proto 1|Sub_Proto 2|Sub_Proto 3|Sub_Proto 4|Sub_Proto 5|Sub_Proto 6|Sub_Proto 7|RF Module|Emulation
---|---|---|---|---|---|---|---|---|---|---|---
[Assan](Protocols_Details.md#ASSAN---24)|24|||||||||NRF24L01|
[Bayang](Protocols_Details.md#BAYANG---14)|14|Bayang|H8S3D|X16_AH|IRDRONE|DHD_D4|QX100|||NRF24L01|XN297
[Bayang RX](Protocols_Details.md#BAYANG-RX---59)|59|Multi|CPPM|||||||NRF24L01|XN297
[BlueFly](Protocols_Details.md#BLUEFLY---95)|95|||||||||NRF24L01|
[Bugs](Protocols_Details.md#BUGS---41)|41|||||||||A7105|
[BugsMini](Protocols_Details.md#BUGSMINI---42)|42|BUGSMINI|BUGS3H|||||||NRF24L01|XN297
[Cabell](Protocols_Details.md#Cabell---34)|34|Cabell_V3|C_TELEM|-|-|-|-|F_SAFE|UNBIND|NRF24L01|
CFlie|38|CFlie||||||||NRF24L01|
[CG023](Protocols_Details.md#CG023---13)|13|CG023|YD829|||||||NRF24L01|XN297
[Corona](Protocols_Details.md#CORONA---37)|37|COR_V1|COR_V2|FD_V3||||||CC2500|
[CX10](Protocols_Details.md#CX10---12)|12|GREEN|BLUE|DM007|-|J3015_1|J3015_2|MK33041||NRF24L01|XN297
[Devo](Protocols_Details.md#DEVO---7)|7|Devo|8CH|10CH|12CH|6CH|7CH|||CYRF6936|
[DM002](Protocols_Details.md#DM002---33)|33|||||||||NRF24L01|XN297
[DSM](Protocols_Details.md#DSM---6)|6|DSM2_1F|DSM2_2F|DSMX_1F|DSMX_2F|AUTO|DSMR_1F|DSM2SFC||CYRF6936|
[DSM_RX](Protocols_Details.md#DSM_RX---70)|70|Multi|CPPM|||||||CYRF6936|
[E010R5](Protocols_Details.md#E010R5---81)|81|||||||||CYRF6936|RF2500
[E016H](Protocols_Details.md#E016H---85)|85|||||||||NRF24L01|XN297
[E016HV2](Protocols_Details.md#E016HV2---80)|80|||||||||CC2500/NRF24L01|unknown
[E01X](Protocols_Details.md#E01X---45)|45|E012|E015|||||||CYRF6936|HS6200
[E129](Protocols_Details.md#E129---83)|83|E129|C186|||||||CYRF6936|RF2500
[EazyRC](Protocols_Details.md#EazyRC---61)|61|||||||||NRF24L01|XN297L
[ESky](Protocols_Details.md#ESKY---16)|16|ESky|ET4|||||||NRF24L01|
[ESky150](Protocols_Details.md#ESKY150---35)|35|||||||||NRF24L01|
[ESky150V2](Protocols_Details.md#ESKY150V2---69)|69|||||||||CC2500|NRF51822
[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|PWM_IBUS16|PPM_IBUS16|PWM_SBUS16|PPM_SBUS16|A7105|
[Flysky AFHDS2A RX](Protocols_Details.md#FLYSKY-AFHDS2A-RX---56)|56|Multi|CPPM|||||||A7105|
[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|||||||||CC2500|
[FrskyX](Protocols_Details.md#FRSKYX---15)|15|CH_16|CH_8|EU_16|EU_8|Cloned|Cloned_8|||CC2500|
[FrskyX2](Protocols_Details.md#FRSKYX2---64)|64|CH_16|CH_8|EU_16|EU_8|Cloned|Cloned_8|||CC2500|
[Frsky_RX](Protocols_Details.md#FRSKY_RX---55)|55|Multi|CloneTX|EraseTX|CPPM|||||CC2500|
[Futaba/SFHSS](Protocols_Details.md#Futaba---21)|21|SFHSS||||||||CC2500|
[FX](Protocols_Details.md#FX---58)|28|816|620|9630|Q560|QF012||||NRF24L01|
[FY326](Protocols_Details.md#FY326---20)|20|FY326|FY319|||||||NRF24L01|
[GD00X](Protocols_Details.md#GD00X---47)|47|GD_V1*|GD_V2*|||||||NRF24L01|XN297L
[GW008](Protocols_Details.md#GW008---32)|32|||||||||NRF24L01|XN297
[H36](Protocols_Details.md#H36---103)|H36|||||||||NRF24L01|XN297
[H8_3D](Protocols_Details.md#H8_3D---36)|36|H8_3D|H20H|H20Mini|H30Mini|||||NRF24L01|XN297
[Height](Protocols_Details.md#HEIGHT---53)|53|5ch|8ch|||||||A7105|
[Hisky](Protocols_Details.md#HISKY---4)|4|Hisky|HK310|||||||NRF24L01|
[Hitec](Protocols_Details.md#HITEC---39)|39|OPT_FW|OPT_HUB|MINIMA||||||CC2500|
[Hontai](Protocols_Details.md#HONTAI---26)|26|HONTAI|JJRCX1|X5C1|FQ777_951|XKK170||||NRF24L01|XN297
[HoTT](Protocols_Details.md#HoTT---57)|57|Sync|No_Sync|||||||CC2500|
[Hubsan](Protocols_Details.md#HUBSAN---2)|2|H107|H301|H501||||||A7105|
[J6Pro](Protocols_Details.md#J6Pro---22)|22|||||||||CYRF6936|
[JIABAILE](Protocols_Details.md#JIABAILE---102)|102|Std|Gyro|||||||NRF24L01|XN297
[JJRC345](Protocols_Details.md#JJRC345---71)|71|JJRC345|SkyTmblr|||||||NRF24L01|XN297
[JOYSWAY](Protocols_Details.md#JOYSWAY---84)|84|||||||||NRF24L01|XN297
[KAMTOM](Protocols_Details.md#KAMTOM---104)|104|||||||||NRF24L01|XN297
[KF606](Protocols_Details.md#KF606---49)|49|KF606|MIG320|ZCZ50||||||NRF24L01|XN297
[KN](Protocols_Details.md#KN---9)|9|WLTOYS|FEILUN|||||||NRF24L01|
[Kyosho](Protocols_Details.md#Kyosho---73)|73|FHSS|Hype|||||||A7105|
[Kyosho2](Protocols_Details.md#Kyosho2---93)|93|KT-17||||||||NRF24L01|
[Kyosho3](Protocols_Details.md#Kyosho3---98)|98|ASF||||||||CYRF6936|
[LOLI](Protocols_Details.md#LOLI---82)|82|||||||||NRF24L01|
[Losi](Protocols_Details.md#Losi---89)|89|||||||||CYRF6936|
[MJXq](Protocols_Details.md#MJXQ---18)|18|WLH08|X600|X800|H26D|E010*|H26WH|PHOENIX*||NRF24L01|XN297
[MLINK](Protocols_Details.md#MLINK---78)|78|||||||||CYRF6936|
[MouldKg](Protocols_Details.md#mouldkg---90)|90|A4444|D4444|A664||||||NRF24L01|XN297
[MT99xx](Protocols_Details.md#MT99XX---17)|17|MT|H7|YZ|LS|FY805|A180|DRAGON|F949G|NRF24L01|XN297
[MT99xx2](Protocols_Details.md#MT99XX2---92)|92|PA18|SU35|||||||NRF24L01|XN297
[NCC1701](Protocols_Details.md#NCC1701---44)|44|||||||||NRF24L01|
[OMP](Protocols_Details.md#OMP---77)|77|||||||||CC2500&NRF24L01|XN297L
[OpenLRS](Protocols_Details.md#OpenLRS---27)|27|||||||||None|
[Pelikan](Protocols_Details.md#Pelikan---60)|60|Pro|Lite|SCX24||||||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
[Q90C](Protocols_Details.md#Q90C---72)|72|Q90C*||||||||NRF24L01|XN297
[RadioLink](Protocols_Details.md#RadioLink---74)|74|Surface|Air|DumboRC|RC4G|||||CC2500|
[Realacc](Protocols_Details.md#Realacc---76)|76|R11||||||||NRF24L01|
[Redpine](Protocols_Details.md#Redpine---50)|50|FAST|SLOW|||||||NRF24L01|XN297
[Scanner](Protocols_Details.md#Scanner---54)|54|||||||||CC2500|
[Scorpio](Protocols_Details.md#Scorpio---94)|94|||||||||CYRF6936|
[SGF22](Protocols_Details.md#SGF22---97)|97|F22|F22S|J20||||||NRF24L01|XN297
[Shenqi](Protocols_Details.md#Shenqi---19)|19|Shenqi||||||||NRF24L01|LT8900
[Shenqi2](Protocols_Details.md#Shenqi2---105)|105|Shenqi2||||||||NRF24L01|XN297
[Skyartec](Protocols_Details.md#Skyartec---68)|68|||||||||CC2500|CC2500
[SLT](Protocols_Details.md#SLT---11)|11|SLT_V1|SLT_V2|Q100|Q200|MR100|V1_4CH|RF_SIM||NRF24L01|CC2500
[SymaX](Protocols_Details.md#Symax---10)|10|SYMAX|SYMAX5C|||||||NRF24L01|
[Traxxas](Protocols_Details.md#Traxxas---43)|43|TQ2|TQ1|||||||CYRF6936|
[V2x2](Protocols_Details.md#V2X2---5)|5|V2x2|JXD506|MR101||||||NRF24L01|
[V761](Protocols_Details.md#V761---48)|48|3CH|4CH|TOPRC||||||NRF24L01|XN297
[V911S](Protocols_Details.md#V911S---46)|46|V911S*|E119*|||||||NRF24L01|XN297
[WFLY](Protocols_Details.md#WFLY---40)|40|WFR0x||||||||CYRF6936|
[WFLY2](Protocols_Details.md#WFLY2---79)|79|RF20x||||||||A7105|
[WK2x01](Protocols_Details.md#WK2X01---30)|30|WK2801|WK2401|W6_5_1|W6_6_1|W6_HEL|W6_HEL_I|||CYRF6936|
[WL91X](Protocols_Details.md#WL91X---106)|106|||||||||NRF24L011&CC2500|XN297
[XERALL](Protocols_Details.md#XERALL---91)|91|Tank||||||||NRF24L01|XN297
[XK](Protocols_Details.md#XK---62)|62|X450|X420|Cars||||||NRF24L011&CC2500|XN297
[XK2](Protocols_Details.md#XK2---99)|99|X4|P10|||||||NRF24L01&CC2500|XN297
[YD717](Protocols_Details.md#YD717---8)|8|YD717|SKYWLKR|SYMAX4|XINXUN|NIHUI||||NRF24L01|
[YuXiang](Protocols_Details.md#YuXiang---100)|100|||||||||NRF24L01|XN297
[ZSX](Protocols_Details.md#ZSX---52)|52|280||||||||NRF24L01|XN297
Protocol Name|Build|Protocol Number|Sub_Proto 0|Sub_Proto 1|Sub_Proto 2|Sub_Proto 3|Sub_Proto 4|Sub_Proto 5|Sub_Proto 6|Sub_Proto 7|RF Module|Emulation
---|---|---|---|---|---|---|---|---|---|---|---|---
[Assan](Protocols_Details.md#ASSAN---24)|AIR/SFC|24|||||||||NRF24L01|
[Bayang](Protocols_Details.md#BAYANG---14)|AIR/SFC|14|Bayang|H8S3D|X16_AH|IRDRONE|DHD_D4|QX100|||NRF24L01|XN297
[Bayang RX](Protocols_Details.md#BAYANG-RX---59)|AIR/SFC|59|Multi|CPPM|||||||NRF24L01|XN297
[BlueFly](Protocols_Details.md#BLUEFLY---95)||95|||||||||NRF24L01|
[Bugs](Protocols_Details.md#BUGS---41)|AIR|41|||||||||A7105|
[BugsMini](Protocols_Details.md#BUGSMINI---42)|AIR|42|BUGSMINI|BUGS3H|||||||NRF24L01|XN297
[Cabell](Protocols_Details.md#Cabell---34)||34|Cabell_V3|C_TELEM|-|-|-|-|F_SAFE|UNBIND|NRF24L01|
CFlie|AIR|38|CFlie||||||||NRF24L01|
[CG023](Protocols_Details.md#CG023---13)|AIR|13|CG023|YD829|||||||NRF24L01|XN297
[Corona](Protocols_Details.md#CORONA---37)|AIR/SFC|37|COR_V1|COR_V2|FD_V3||||||CC2500|
[CX10](Protocols_Details.md#CX10---12)|AIR|12|GREEN|BLUE|DM007|-|J3015_1|J3015_2|MK33041||NRF24L01|XN297
[Devo](Protocols_Details.md#DEVO---7)|AIR/SFC|7|Devo|8CH|10CH|12CH|6CH|7CH|||CYRF6936|
[DM002](Protocols_Details.md#DM002---33)|AIR|33|||||||||NRF24L01|XN297
[DSM](Protocols_Details.md#DSM---6)|AIR/SFC|6|DSM2_1F|DSM2_2F|DSMX_1F|DSMX_2F|AUTO|DSMR_1F|DSM2SFC||CYRF6936|
[DSM_RX](Protocols_Details.md#DSM_RX---70)|AIR/SFC|70|Multi|CPPM|||||||CYRF6936|
[E010R5](Protocols_Details.md#E010R5---81)|AIR|81|||||||||CYRF6936|RF2500
[E016H](Protocols_Details.md#E016H---85)||85|||||||||NRF24L01|XN297
[E016HV2](Protocols_Details.md#E016HV2---80)||80|||||||||CC2500/NRF24L01|unknown
[E01X](Protocols_Details.md#E01X---45)||45|E012|E015|||||||CYRF6936|HS6200
[E129](Protocols_Details.md#E129---83)||83|E129|C186|||||||CYRF6936|RF2500
[EazyRC](Protocols_Details.md#EazyRC---61)||61|||||||||NRF24L01|XN297L
[ESky](Protocols_Details.md#ESKY---16)||16|ESky|ET4|||||||NRF24L01|
[ESky150](Protocols_Details.md#ESKY150---35)||35|||||||||NRF24L01|
[ESky150V2](Protocols_Details.md#ESKY150V2---69)||69|||||||||CC2500|NRF51822
[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|Gyro_Off|Gyro_On|Gyro_On_Rev||A7105|
[Flysky AFHDS2A RX](Protocols_Details.md#FLYSKY-AFHDS2A-RX---56)||56|Multi|CPPM|||||||A7105|
[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|||||||||CC2500|
[FrskyX](Protocols_Details.md#FRSKYX---15)||15|CH_16|CH_8|EU_16|EU_8|Cloned|Cloned_8|||CC2500|
[FrskyX2](Protocols_Details.md#FRSKYX2---64)||64|CH_16|CH_8|EU_16|EU_8|Cloned|Cloned_8|||CC2500|
[Frsky_RX](Protocols_Details.md#FRSKY_RX---55)||55|Multi|CloneTX|EraseTX|CPPM|||||CC2500|
[Futaba/SFHSS](Protocols_Details.md#Futaba---21)||21|SFHSS||||||||CC2500|
[FX](Protocols_Details.md#FX---58)||28|816|620|9630|Q560|QF012||||NRF24L01|
[FY326](Protocols_Details.md#FY326---20)||20|FY326|FY319|||||||NRF24L01|
[GD00X](Protocols_Details.md#GD00X---47)||47|GD_V1*|GD_V2*|||||||NRF24L01|XN297L
[GW008](Protocols_Details.md#GW008---32)||32|||||||||NRF24L01|XN297
[H36](Protocols_Details.md#H36---103)||H36|||||||||NRF24L01|XN297
[H8_3D](Protocols_Details.md#H8_3D---36)||36|H8_3D|H20H|H20Mini|H30Mini|||||NRF24L01|XN297
[Height](Protocols_Details.md#HEIGHT---53)||53|5ch|8ch|||||||A7105|
[Hisky](Protocols_Details.md#HISKY---4)||4|Hisky|HK310|||||||NRF24L01|
[Hitec](Protocols_Details.md#HITEC---39)||39|OPT_FW|OPT_HUB|MINIMA||||||CC2500|
[Hontai](Protocols_Details.md#HONTAI---26)||26|HONTAI|JJRCX1|X5C1|FQ777_951|XKK170||||NRF24L01|XN297
[HoTT](Protocols_Details.md#HoTT---57)||57|Sync|No_Sync|||||||CC2500|
[Hubsan](Protocols_Details.md#HUBSAN---2)||2|H107|H301|H501||||||A7105|
[J6Pro](Protocols_Details.md#J6Pro---22)||22|||||||||CYRF6936|
[JIABAILE](Protocols_Details.md#JIABAILE---102)||102|Std|Gyro|||||||NRF24L01|XN297
[JJRC345](Protocols_Details.md#JJRC345---71)||71|JJRC345|SkyTmblr|||||||NRF24L01|XN297
[JOYSWAY](Protocols_Details.md#JOYSWAY---84)||84|||||||||NRF24L01|XN297
[KAMTOM](Protocols_Details.md#KAMTOM---104)||104|||||||||NRF24L01|XN297
[KF606](Protocols_Details.md#KF606---49)||49|KF606|MIG320|ZCZ50||||||NRF24L01|XN297
[KN](Protocols_Details.md#KN---9)||9|WLTOYS|FEILUN|||||||NRF24L01|
[Kyosho](Protocols_Details.md#Kyosho---73)||73|FHSS|Hype|||||||A7105|
[Kyosho2](Protocols_Details.md#Kyosho2---93)||93|KT-17||||||||NRF24L01|
[Kyosho3](Protocols_Details.md#Kyosho3---98)||98|ASF||||||||CYRF6936|
[LOLI](Protocols_Details.md#LOLI---82)||82|||||||||NRF24L01|
[Losi](Protocols_Details.md#Losi---89)||89|||||||||CYRF6936|
[MJXq](Protocols_Details.md#MJXQ---18)||18|WLH08|X600|X800|H26D|E010*|H26WH|PHOENIX*||NRF24L01|XN297
[MLINK](Protocols_Details.md#MLINK---78)||78|||||||||CYRF6936|
[MouldKg](Protocols_Details.md#mouldkg---90)||90|A4444|D4444|A664||||||NRF24L01|XN297
[MT99xx](Protocols_Details.md#MT99XX---17)||17|MT|H7|YZ|LS|FY805|A180|DRAGON|F949G|NRF24L01|XN297
[MT99xx2](Protocols_Details.md#MT99XX2---92)||92|PA18|SU35|||||||NRF24L01|XN297
[NCC1701](Protocols_Details.md#NCC1701---44)||44|||||||||NRF24L01|
[OMP](Protocols_Details.md#OMP---77)||77|||||||||CC2500&NRF24L01|XN297L
[OpenLRS](Protocols_Details.md#OpenLRS---27)||27|||||||||None|
[Pelikan](Protocols_Details.md#Pelikan---60)||60|Pro|Lite|SCX24||||||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
[Q90C](Protocols_Details.md#Q90C---72)||72|Q90C*||||||||NRF24L01|XN297
[RadioLink](Protocols_Details.md#RadioLink---74)||74|Surface|Air|DumboRC|RC4G|||||CC2500|
[Realacc](Protocols_Details.md#Realacc---76)||76|R11||||||||NRF24L01|
[Redpine](Protocols_Details.md#Redpine---50)||50|FAST|SLOW|||||||NRF24L01|XN297
[Scanner](Protocols_Details.md#Scanner---54)||54|||||||||CC2500|
[Scorpio](Protocols_Details.md#Scorpio---94)||94|||||||||CYRF6936|
[SGF22](Protocols_Details.md#SGF22---97)||97|F22|F22S|J20|CX10|||||NRF24L01|XN297
[Shenqi](Protocols_Details.md#Shenqi---19)||19|Shenqi||||||||NRF24L01|LT8900
[Shenqi2](Protocols_Details.md#Shenqi2---105)||105|Shenqi2||||||||NRF24L01|XN297
[Skyartec](Protocols_Details.md#Skyartec---68)||68|||||||||CC2500|CC2500
[SLT](Protocols_Details.md#SLT---11)||11|SLT_V1|SLT_V2|Q100|Q200|MR100|V1_4CH|RF_SIM||NRF24L01|CC2500
[SymaX](Protocols_Details.md#Symax---10)||10|SYMAX|SYMAX5C|||||||NRF24L01|
[Traxxas](Protocols_Details.md#Traxxas---43)||43|TQ2|TQ1|||||||CYRF6936|
[V2x2](Protocols_Details.md#V2X2---5)||5|V2x2|JXD506|MR101||||||NRF24L01|
[V761](Protocols_Details.md#V761---48)||48|3CH|4CH|TOPRC||||||NRF24L01|XN297
[V911S](Protocols_Details.md#V911S---46)||46|V911S*|E119*|||||||NRF24L01|XN297
[WFLY](Protocols_Details.md#WFLY---40)||40|WFR0x||||||||CYRF6936|
[WFLY2](Protocols_Details.md#WFLY2---79)||79|RF20x||||||||A7105|
[WK2x01](Protocols_Details.md#WK2X01---30)||30|WK2801|WK2401|W6_5_1|W6_6_1|W6_HEL|W6_HEL_I|||CYRF6936|
[WL91X](Protocols_Details.md#WL91X---106)||106|||||||||NRF24L01&CC2500|XN297
[WPL](Protocols_Details.md#WPL---107)||107|||||||||NRF24L01|XN297
[XERALL](Protocols_Details.md#XERALL---91)||91|Tank||||||||NRF24L01|XN297
[XK](Protocols_Details.md#XK---62)||62|X450|X420|Cars||||||NRF24L01&CC2500|XN297
[XK2](Protocols_Details.md#XK2---99)||99|X4|P10|||||||NRF24L01&CC2500|XN297
[YD717](Protocols_Details.md#YD717---8)||8|YD717|SKYWLKR|SYMAX4|XINXUN|NIHUI||||NRF24L01|
[YuXiang](Protocols_Details.md#YuXiang---100)||100|||||||||NRF24L01|XN297
[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.
# A7105 RF Module
@@ -227,36 +228,59 @@ Telemetry enabled protocol:
- if using erskyTX and OpenTX: full telemetry information available
- if telemetry is incomplete (missing RX RSSI for example), it means that you have to upgrade your RX firmware to version 1.6 or later. You can do it from an original Flysky TX or using a STLink like explained in [this tutorial](https://www.rcgroups.com/forums/showthread.php?2677694-How-to-upgrade-Flysky-Turnigy-iA6B-RX-to-firmware-1-6-with-a-ST-Link).
LQI: Link Quality Indicator which is sent back to the RX on CH17
Option is used to change the servo refresh rate. A value of 0 gives 50Hz (min), 70 gives 400Hz (max). Specific refresh rate value can be calculated like this option=(refresh_rate-50)/5.
**RX_Num is used to give a number a given RX. You must use a different RX_Num per RX. A maximum of 64 AFHDS2A RXs are supported.**
AFHDS2A_LQI_CH is a feature which is disabled by defaut in the _config.h file. When enabled, it makes LQI (Link Quality Indicator) available on one of the RX ouput channel (5-14).
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14
---|---|---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14
RX output will match the Flysky standard AETR independently of the input configuration AETR, RETA... unless on OpenTX 2.3.3+ you use the "Disable channel mapping" feature on the GUI.
### Sub_protocol PWM_IBUS - *0*
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14CH15|CH16|LQI
RX output will match the Flysky standard AETR.
### Sub_protocol PPM_IBUS - *1*
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14CH15|CH16|LQI
RX output will match the Flysky standard AETR.
### Sub_protocol PWM_SBUS - *2*
### Sub_protocol PPM_SBUS - *3*
As stated above.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14CH15|CH16|LQI
### Sub_protocol PWM_IBUS16 - *4*
### Sub_protocol PPM_IBUS16 - *5*
### Sub_protocol PWM_SBUS16 - *6*
### Sub_protocol PPM_SBUS16 - *7*
RX output will match the Flysky standard AETR.
3 additional channels. Need recent or updated RXs.
### Sub_protocol Gyro_Off - *3*
RXs: FS-BS6, FS-BS4
CH15|CH16|CH17
---|---|---
CH15|CH16|LQI
Gyro is off
LQI: Link Quality Indicator
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|-|-|-|-|LQI
### Sub_protocol Gyro_On - *4*
RXs: FS-BS6, FS-BS4
Gyro is on
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|ST_Gain|TH_Gain|Priority|Calib|LQI
### Sub_protocol Gyro_On_Rev - *5*
RXs: FS-BS6, FS-BS4
Gyro is on and reversed
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16|CH17
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|ST_Gain|TH_Gain|Priority|Calib|LQI
## FLYSKY AFHDS2A RX - *56*
The Flysky AFHDS2A receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
@@ -1556,6 +1580,8 @@ A|E|T|R|Rate|Mode|Hover|Light
The plane does not need to be bound each time if it is powered on **after** the radio/protocol is on.
Telemetry is supported. The plane sends a battery status of good->empty which is visible in A1 (good=8.4V->empty=7.1V) and RSSI gets a dummy value of 100.
The rudder trim is driven from the rudder channel to increase the range (Original TX rudder has no range once the motor has been turned on...).
Mode: -100%=6G, 0%=3D, +100%=Gyro off (Senior mode)
@@ -1854,12 +1880,12 @@ Gyro: -100%=6G, 0%=3D+Gyro, +100%=3D
### Sub_protocol QF012 - *4*
Model: QF012 SBD Dauntless
Telemetry supported. The plane sends a battery status of good->empty which is visible in A1 (good=4.2V->empty=3.1V) and RSSI gets a dummy value of 100.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|FLIP|GYRO|Invert|Reset
FLIP is a toggle channel meaning that -100% to +100% is a command and +100% to -100% is also a command
Gyro: -100%=6G, 0%=3D+Gyro, +100%=3D
Reset: Restore fine tunning midpoint
@@ -2094,7 +2120,7 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
Brick1_A|Brick1_B|Brick1_C|Brick1_D|Brick2_A|Brick2_B|Brick2_C|Brick2_D|Brick3_A|Brick3_B|Brick3_C|Brick3_D|Brick4_A|Brick4_B|Brick4_C|Brick4_D
### Sub_protocol D4444 - *1*
Model: 4 digital ports brick
Model: 4 digital ports brick and Integrated power module
Up to 4 bricks can be controlled at the same time.
@@ -2213,6 +2239,8 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|MODE|FLIP|LIGHT|PHOTO|VIDEO|TRIMRESET|BAL|BALHIG
Telemetry is supported. The plane sends a battery status of good->empty which is visible in A1 (good=13.2V->empty=0V) and RSSI gets a dummy value of 100.
### Sub_protocol F22
Model: SG F22
@@ -2225,12 +2253,19 @@ Manual CH11=-100% & CH12=-100%, Balance CH11=+100% & CH12=-100%, Large Angle Bal
### Sub_protocol F22S
Model: ParkTen F22S
F22S: Mode -100% = 3D, 0% = 6G
Mode -100% = 3D, 0% = 6G
### Sub_protocol J20
Model: KF700 J20
J20: Mode -100% = Gyro off, 0% = Horizontal, 100% = Vertical. CH8 - Invert, CH10 - Fix Height (Altitude hold)
Mode -100% = Gyro off, 0% = Horizontal, 100% = Vertical. CH8 - Invert, CH10 - Fix Height (Altitude hold)
### Sub_protocol CX10
Model: Cheerson CX-10 with red PCB
**Only 2 IDs available**, use RX num to cycle through them.
Mode -100% = Low, 0% = Medium, 100% = High
## Shenqi - *19*
Autobind protocol
@@ -2336,6 +2371,19 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|GYRO|CALIB|FLIP|RTN_ACT|RTN
## WPL - *107*
TX: "Basic", Models: D12 / D12KM / D22 / D32 / D42 / D14
**Only 1 ID** available. If you have a TX contact me on GitHub or RCGroups.
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7
---|---|---|---|---|---|---
TH|ST|ST_Trim|Aux|Light|TH_Rate|ST_Rate
Light: -100%=Off, +100%=On, Rate: -100%=Low, +100%=High
## XERALL - *91*
Model: Xerall TankCopter