Compare commits

...

74 Commits

Author SHA1 Message Date
Pascal Langer
bff68f482e Update Protocols_Details.md 2020-06-03 14:08:09 +02:00
Pascal Langer
32ed758072 Update DSM_Rx_cyrf6936.ino 2020-06-03 12:55:45 +02:00
Pascal Langer
5ce99ee419 Test protocol 2020-06-03 11:43:27 +02:00
Pascal Langer
ceea384a36 Pelikan Lite: force_id update 2020-06-03 10:29:34 +02:00
Pascal Langer
fd3b026e12 Update Pelikan_a7105.ino 2020-06-02 19:10:11 +02:00
Pascal Langer
7e451c13a8 Pelikan: add sub protocol for Lite version 2020-06-02 19:04:05 +02:00
Pascal Langer
3dcf74c2e4 Bayang: renamed CX100 to QX100 2020-06-02 17:17:49 +02:00
Pascal Langer
50f1eca4be Bayang: new subprotocol CX100 2020-06-02 14:59:32 +02:00
Pascal Langer
0d97af5ae2 XN297dump: Auto mode small fix 2020-06-02 14:34:50 +02:00
Pascal Langer
aeb8d67219 HoTT: add subprotocols 2020-06-01 22:55:32 +02:00
Pascal Langer
1f65025036 HoTT: add LBT and telemetry improvment 2020-05-31 23:54:13 +02:00
Pascal Langer
8df3687684 Q90C: channels reverse 2020-05-26 22:26:30 +02:00
MRC3742
adf59a9d0d Misc updates for errors, omissions amd corrections (#359) 2020-05-26 19:52:09 +02:00
Pascal Langer
b9f00bdbc5 Q90C: checksum fix 2020-05-26 12:41:33 +02:00
Pascal Langer
a10e169573 New protocol Q90C 2020-05-24 17:39:14 +02:00
Pascal Langer
317b9a8156 Fix compilation when ESKY150V2 was built without HoTT 2020-05-23 23:34:05 +02:00
Pascal Langer
1c632d462f Update Protocols_Details.md 2020-05-23 22:53:53 +02:00
Pascal Langer
c46b49ccf1 HoTT: cleanup 2020-05-23 22:41:07 +02:00
Pascal Langer
e70708b133 FrSkyX: push more parts to common 2020-05-23 22:39:26 +02:00
Konstantin Tretyakov
62486c2220 JJRC345: Reduce stick sensitivity (#355)
A largely symbolic contribution to record participation in protocol development.
See: https://github.com/DeviationTX/deviation/pull/853
2020-05-23 00:09:46 +02:00
Pascal Langer
cffe66747a JJRC345: last commit 2020-05-22 21:03:01 +02:00
Pascal Langer
b31bbfa04f JJRC345: Change checksum calculation 2020-05-21 23:40:23 +02:00
Pascal Langer
48e4cad3ad JJRC345: add RTH on CH7 2020-05-21 17:49:04 +02:00
Pascal Langer
53f58ce2e1 JJRC345: update 2020-05-21 17:24:11 +02:00
Pascal Langer
eb8b5eac01 JJRC345: update channels range 2020-05-21 11:56:08 +02:00
Pascal Langer
02008a8b2e New protocol JJRC345: WIP
Work in progress
2020-05-21 11:47:51 +02:00
Pascal Langer
5b82599eb9 Update Protocols_Details.md 2020-05-20 12:23:37 +02:00
Pascal Langer
a5e4b2c6fa DSM RX: Fix compilation 2020-05-18 01:30:52 +02:00
Pascal Langer
987753ff73 DSM and DSM RX: fix bind 2020-05-18 01:13:08 +02:00
Pascal Langer
ee080839b1 Update DSM_Rx_cyrf6936.ino 2020-05-17 17:26:43 +02:00
Pascal Langer
4290c75478 HoTT: support for auto sensors discovery and sensors text config 2020-05-17 15:47:56 +02:00
Pascal Langer
cc6be6027d New DSM RX protocol 2020-05-17 15:45:23 +02:00
Pascal Langer
4cfde0a80a Update Protocols_Details.md 2020-05-10 13:41:14 +02:00
Pascal Langer
a77aee0e1a Update Protocols_Details.md 2020-05-09 16:11:36 +02:00
Pascal Langer
6f36473975 Devo basic telemetry 2020-05-09 16:11:10 +02:00
pascallanger
f5720d38bb Update Flash_from_Tx.md 2020-05-09 09:10:09 +02:00
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
pascallanger
d1518d763b Add files via upload 2020-03-30 21:22:12 +02:00
Pascal Langer
44a676b809 Update Multiprotocol.h 2020-03-30 18:22:13 +02:00
Pascal Langer
d66709ea87 Update Protocols_Details.md 2020-03-29 19:23:28 +02:00
Pascal Langer
358a77cf7c Update Protocols_Details.md 2020-03-29 19:15:32 +02:00
Pascal Langer
1a631908f4 Update FrSky_Rx_cc2500.ino 2020-03-29 19:09:56 +02:00
Pascal Langer
9f32a1f22b FrSkyRX protocol: chanskip test 2020-03-29 18:49:37 +02:00
Pascal Langer
dfd3386319 FrSkyX v2.1: initial support
Rewrite of the FrSkyX code to support both v1 and v2.1.0 with FCC and LBT.
FrSky v1 accessible as usual
FrSky v2.1.0 accessible through the protocol 64=FrSkyX2 with the same subprotocols as v1
The LBT feature is now fully implemented on the TX and turned on for both v1 LBT and v2.1.0 LBT.
For v2.1.0, to access the bind functions Telem=on/off, CH1-8/9-16 and bidirectional SPort (SxR setup for example), you need to update OpenTX to the latest 2.3.8 nightly (not available yet).
2020-03-29 18:44:03 +02:00
35 changed files with 4077 additions and 1163 deletions

View File

@@ -67,12 +67,16 @@ static void __attribute__((unused)) BAYANG_send_packet()
else
#endif
packet[0]= 0xA4;
if(sub_protocol==QX100)
packet[0] = 0x53;
for(i=0;i<5;i++)
packet[i+1]=rx_tx_addr[i];
for(i=0;i<4;i++)
packet[i+6]=hopping_frequency[i];
switch (sub_protocol)
{
case QX100:
case X16_AH:
packet[10] = 0x00;
packet[11] = 0x00;
@@ -161,6 +165,7 @@ static void __attribute__((unused)) BAYANG_send_packet()
packet[12] = rx_tx_addr[2]; // txid[2]
packet[13] = 0x34;
break;
case QX100:
case X16_AH:
packet[12] = 0;
packet[13] = 0;

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

@@ -284,7 +284,7 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
}
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
CYRF_SetTxRxMode(TX_EN);
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Clear abort RX
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX
}
#if defined(DEVO_CYRF6936_INO) || defined(J6PRO_CYRF6936_INO)
@@ -313,6 +313,7 @@ const uint8_t PROGMEM DEVO_j6pro_sopcodes[][8] = {
#endif
};
#endif
static void __attribute__((unused)) CYRF_PROGMEM_ConfigSOPCode(const uint8_t *data)
{
uint8_t code[8];

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;
}

182
Multiprotocol/DSM.ino Normal file
View File

@@ -0,0 +1,182 @@
#if defined(DSM_CYRF6936_INO) || defined(DSM_RX_CYRF6936_INO)
#include "iface_cyrf6936.h"
uint8_t sop_col;
const uint8_t PROGMEM DSM_pncodes[5][9][8] = {
/* Note these are in order transmitted (LSB 1st) */
{ /* Row 0 */
/* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8},
/* Col 1 */ {0x88, 0x17, 0x13, 0x3B, 0x2D, 0xBF, 0x06, 0xD6},
/* Col 2 */ {0xF1, 0x94, 0x30, 0x21, 0xA1, 0x1C, 0x88, 0xA9},
/* Col 3 */ {0xD0, 0xD2, 0x8E, 0xBC, 0x82, 0x2F, 0xE3, 0xB4},
/* Col 4 */ {0x8C, 0xFA, 0x47, 0x9B, 0x83, 0xA5, 0x66, 0xD0},
/* Col 5 */ {0x07, 0xBD, 0x9F, 0x26, 0xC8, 0x31, 0x0F, 0xB8},
/* Col 6 */ {0xEF, 0x03, 0x95, 0x89, 0xB4, 0x71, 0x61, 0x9D},
/* Col 7 */ {0x40, 0xBA, 0x97, 0xD5, 0x86, 0x4F, 0xCC, 0xD1},
/* Col 8 */ {0xD7, 0xA1, 0x54, 0xB1, 0x5E, 0x89, 0xAE, 0x86}
},
{ /* Row 1 */
/* Col 0 */ {0x83, 0xF7, 0xA8, 0x2D, 0x7A, 0x44, 0x64, 0xD3},
/* Col 1 */ {0x3F, 0x2C, 0x4E, 0xAA, 0x71, 0x48, 0x7A, 0xC9},
/* Col 2 */ {0x17, 0xFF, 0x9E, 0x21, 0x36, 0x90, 0xC7, 0x82},
/* Col 3 */ {0xBC, 0x5D, 0x9A, 0x5B, 0xEE, 0x7F, 0x42, 0xEB},
/* Col 4 */ {0x24, 0xF5, 0xDD, 0xF8, 0x7A, 0x77, 0x74, 0xE7},
/* Col 5 */ {0x3D, 0x70, 0x7C, 0x94, 0xDC, 0x84, 0xAD, 0x95},
/* Col 6 */ {0x1E, 0x6A, 0xF0, 0x37, 0x52, 0x7B, 0x11, 0xD4},
/* Col 7 */ {0x62, 0xF5, 0x2B, 0xAA, 0xFC, 0x33, 0xBF, 0xAF},
/* Col 8 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97}
},
{ /* Row 2 */
/* Col 0 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97},
/* Col 1 */ {0x8E, 0x4A, 0xD0, 0xA9, 0xA7, 0xFF, 0x20, 0xCA},
/* Col 2 */ {0x4C, 0x97, 0x9D, 0xBF, 0xB8, 0x3D, 0xB5, 0xBE},
/* Col 3 */ {0x0C, 0x5D, 0x24, 0x30, 0x9F, 0xCA, 0x6D, 0xBD},
/* Col 4 */ {0x50, 0x14, 0x33, 0xDE, 0xF1, 0x78, 0x95, 0xAD},
/* Col 5 */ {0x0C, 0x3C, 0xFA, 0xF9, 0xF0, 0xF2, 0x10, 0xC9},
/* Col 6 */ {0xF4, 0xDA, 0x06, 0xDB, 0xBF, 0x4E, 0x6F, 0xB3},
/* Col 7 */ {0x9E, 0x08, 0xD1, 0xAE, 0x59, 0x5E, 0xE8, 0xF0},
/* Col 8 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E}
},
{ /* Row 3 */
/* Col 0 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E},
/* Col 1 */ {0x80, 0x69, 0x26, 0x80, 0x08, 0xF8, 0x49, 0xE7},
/* Col 2 */ {0x7D, 0x2D, 0x49, 0x54, 0xD0, 0x80, 0x40, 0xC1},
/* Col 3 */ {0xB6, 0xF2, 0xE6, 0x1B, 0x80, 0x5A, 0x36, 0xB4},
/* Col 4 */ {0x42, 0xAE, 0x9C, 0x1C, 0xDA, 0x67, 0x05, 0xF6},
/* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
/* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
/* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
/* Col 8 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93}
// Wrong values used by Orange TX/RX
// /* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
},
{ /* Row 4 */
/* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
/* Col 1 */ {0xDC, 0x68, 0x08, 0x99, 0x97, 0xAE, 0xAF, 0x8C},
/* Col 2 */ {0xC3, 0x0E, 0x01, 0x16, 0x0E, 0x32, 0x06, 0xBA},
/* Col 3 */ {0xE0, 0x83, 0x01, 0xFA, 0xAB, 0x3E, 0x8F, 0xAC},
/* Col 4 */ {0x5C, 0xD5, 0x9C, 0xB8, 0x46, 0x9C, 0x7D, 0x84},
/* Col 5 */ {0xF1, 0xC6, 0xFE, 0x5C, 0x9D, 0xA5, 0x4F, 0xB7},
/* Col 6 */ {0x58, 0xB5, 0xB3, 0xDD, 0x0E, 0x28, 0xF1, 0xB0},
/* Col 7 */ {0x5F, 0x30, 0x3B, 0x56, 0x96, 0x45, 0xF4, 0xA1},
/* Col 8 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8}
},
};
static void __attribute__((unused)) DSM_read_code(uint8_t *buf, uint8_t row, uint8_t col, uint8_t len)
{
for(uint8_t i=0;i<len;i++)
buf[i]=pgm_read_byte_near( &DSM_pncodes[row][col][i] );
}
const uint8_t PROGMEM DSM_init_vals[][2] = {
{CYRF_02_TX_CTRL, 0x00}, // All TX interrupt disabled
{CYRF_05_RX_CTRL, 0x00}, // All RX interrupt disabled
{CYRF_28_CLK_EN, 0x02}, // Force receive clock enable
{CYRF_32_AUTO_CAL_TIME, 0x3c}, // Default init value
{CYRF_35_AUTOCAL_OFFSET, 0x14}, // Default init value
{CYRF_26_XTAL_CFG, 0x08}, // Start delay
{CYRF_06_RX_CFG, 0x4A}, // LNA enabled, RX override enabled, Fast turn mode enabled, RX is 1MHz below TX
{CYRF_1B_TX_OFFSET_LSB, 0x55}, // Default init value
{CYRF_1C_TX_OFFSET_MSB, 0x05}, // Default init value
{CYRF_39_ANALOG_CTRL, 0x01}, // All slow for synth setting time
{CYRF_01_TX_LENGTH, 0x10}, // 16 bytes packet
{CYRF_14_EOP_CTRL, 0x02}, // Set EOP Symbol Count to 2
{CYRF_12_DATA64_THOLD, 0x0a}, // 64 Chip Data PN corelator threshold, default datasheet value is 0x0E
//Below is for bind only
{CYRF_03_TX_CFG, 0x38 | CYRF_BIND_POWER}, //64 chip codes, SDR mode
{CYRF_10_FRAMING_CFG, 0x4a}, // SOP disabled, no LEN field and SOP correlator of 0x0a but since SOP is disabled...
{CYRF_1F_TX_OVERRIDE, 0x04}, // Disable TX CRC, no ACK, use TX synthesizer
{CYRF_1E_RX_OVERRIDE, 0x14}, // Disable RX CRC, Force receive data rate, use RX synthesizer
};
const uint8_t PROGMEM DSM_data_vals[][2] = {
{CYRF_29_RX_ABORT, 0x20}, // Abort RX operation in case we are coming from bind
{CYRF_0F_XACT_CFG, 0x24}, // Force Idle
{CYRF_29_RX_ABORT, 0x00}, // Clear abort RX
{CYRF_03_TX_CFG, 0x28 | CYRF_HIGH_POWER}, // 64 chip codes, 8DR mode
{CYRF_10_FRAMING_CFG, 0xea}, // SOP enabled, SOP_CODE_ADR 64 chips, Packet len enabled, SOP correlator 0x0A
{CYRF_1F_TX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
{CYRF_1E_RX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
};
static void __attribute__((unused)) DSM_cyrf_config()
{
for(uint8_t i = 0; i < sizeof(DSM_init_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&DSM_init_vals[i][0]), pgm_read_byte_near(&DSM_init_vals[i][1]));
CYRF_WritePreamble(0x333304);
}
static void __attribute__((unused)) DSM_cyrf_configdata()
{
for(uint8_t i = 0; i < sizeof(DSM_data_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&DSM_data_vals[i][0]), pgm_read_byte_near(&DSM_data_vals[i][1]));
}
static uint8_t __attribute__((unused)) DSM_get_pn_row(uint8_t channel, bool dsmx)
{
return (dsmx ? (channel - 2) % 5 : channel % 5);
}
static void __attribute__((unused)) DSM_set_sop_data_crc(bool ch2, bool dsmx)
{
//The crc for channel '1' is NOT(mfgid[0] << 8 + mfgid[1])
//The crc for channel '2' is (mfgid[0] << 8 + mfgid[1])
if(ch2)
CYRF_ConfigCRCSeed(seed); //CH2
else
CYRF_ConfigCRCSeed(~seed); //CH1
uint8_t pn_row = DSM_get_pn_row(hopping_frequency[hopping_frequency_no], dsmx);
uint8_t code[16];
DSM_read_code(code,pn_row,sop_col,8); // pn_row between 0 and 4, sop_col between 1 and 7
CYRF_ConfigSOPCode(code);
DSM_read_code(code,pn_row,7 - sop_col,8); // 7-sop_col between 0 and 6
DSM_read_code(code+8,pn_row,7 - sop_col + 1,8); // 7-sop_col+1 between 1 and 7
CYRF_ConfigDataCode(code, 16);
CYRF_ConfigRFChannel(hopping_frequency[hopping_frequency_no]);
hopping_frequency_no++;
if(dsmx)
hopping_frequency_no %=23;
else
hopping_frequency_no %=2;
}
static void __attribute__((unused)) DSM_calc_dsmx_channel()
{
uint8_t idx = 0;
uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0));
uint32_t id_tmp = id;
while(idx < 23)
{
uint8_t i;
uint8_t count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
if ( (next_ch ^ cyrfmfg_id[3]) & 0x01 )
continue;
for (i = 0; i < idx; i++)
{
if(hopping_frequency[i] == next_ch)
break;
if(hopping_frequency[i] <= 27)
count_3_27++;
else
if (hopping_frequency[i] <= 51)
count_28_51++;
else
count_52_76++;
}
if (i != idx)
continue;
if ((next_ch < 28 && count_3_27 < 8)
||(next_ch >= 28 && next_ch < 52 && count_28_51 < 7)
||(next_ch >= 52 && count_52_76 < 8))
hopping_frequency[idx++] = next_ch;
}
}
#endif

View File

@@ -0,0 +1,495 @@
/*
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(DSM_RX_CYRF6936_INO)
#include "iface_cyrf6936.h"
//#define DSM_DEBUG_RF
uint8_t DSM_rx_type;
enum {
DSM_RX_BIND1 = 0,
DSM_RX_BIND2,
DSM_RX_DATA_PREP,
DSM2_RX_SCAN,
DSM_RX_DATA_CH1,
DSM_RX_DATA_CH2,
};
static void __attribute__((unused)) DSM_Rx_init()
{
DSM_cyrf_config();
rx_disable_lna = IS_POWER_FLAG_on;
if(IS_BIND_IN_PROGRESS)
{
//64 SDR Mode is configured so only the 8 first values are needed but need to write 16 values...
uint8_t code[16];
DSM_read_code(code,0,8,8);
CYRF_ConfigDataCode(code, 16);
CYRF_ConfigRFChannel(1);
CYRF_SetTxRxMode(RX_EN); // Force end state read
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive
}
else
{
DSM_cyrf_configdata();
CYRF_WriteRegister(CYRF_06_RX_CFG, rx_disable_lna ? 0x0A:0x4A); // AGC disabled, LNA disabled/enabled, Attenuator disabled, RX override enabled, Fast turn mode enabled, RX is 1MHz below TX
}
}
uint16_t convert_channel_DSM_nolimit(int32_t val)
{
val=(val-0x150)*(CHANNEL_MAX_100-CHANNEL_MIN_100)/(0x6B0-0x150)+CHANNEL_MIN_100;
if(val<0)
val=0;
else
if(val>2047)
val=2047;
return (uint16_t)val;
}
static uint8_t __attribute__((unused)) DSM_Rx_check_packet()
{
uint8_t rx_status=CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_status & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_status |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_status & 0x07) == 0x02)
{ // data received with no errors
len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
#ifdef DSM_DEBUG_RF
debugln("l=%d",len);
#endif
if(len>=2 && len<=16)
{
// Read packet
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // Need to set RXOW before data read
CYRF_ReadDataPacketLen(packet, len);
// Check packet ID
if ((DSM_rx_type&0x80) == 0)
{//DSM2
packet[0] ^= 0xff;
packet[1] ^= 0xff;
}
if(packet[0] == cyrfmfg_id[2] && packet[1] == cyrfmfg_id[3])
return 0x02; // Packet ok
}
return 0x00; // Wrong size or ID -> nothing received
}
return rx_status; // Return error code
}
static void __attribute__((unused)) DSM_Rx_build_telemetry_packet()
{
uint8_t nbr_bits = 11;
if((DSM_rx_type&0xF0) == 0x00)
nbr_bits=10; // Only DSM_22 is using a resolution of 1024
// Use packet length to calculate the number of channels
len -= 2; // Remove header length
len >>= 1; // Channels are on 2 bytes
if(len==0) return; // No channels...
// Extract channels
uint8_t idx;
for (uint8_t i = 0; i < len; i++)
{
uint16_t value=(packet[i*2+2]<<8) | packet[i*2+3];
if(value!=0xFFFF)
{
idx=(value&0x7FFF)>>nbr_bits; // retrieve channel index 0..12
if(idx<13)
{
if(nbr_bits==10) value <<= 1; // switch to 11 bits
value &= 0x7FF;
rx_rc_chan[CH_TAER[idx]]=convert_channel_DSM_nolimit(value);
if(IS_DISABLE_CH_MAP_off && (CH_TAER[idx]==AILERON || CH_TAER[idx]==RUDDER))
rx_rc_chan[CH_TAER[idx]]=2047-rx_rc_chan[CH_TAER[idx]]; // Reverse AILERON and RUDDER channels
}
}
}
// Buid telemetry packet
idx=0;
packet_in[idx++] = RX_LQI;
packet_in[idx++] = RX_LQI;
packet_in[idx++] = 0; // start channel
packet_in[idx++] = 12; // number of channels in packet
// Pack channels
uint32_t bits = 0;
uint8_t bitsavailable = 0;
for (uint8_t i = 0; i < 12; i++)
{
bits |= ((uint32_t)rx_rc_chan[i]) << bitsavailable;
bitsavailable += 11;
while (bitsavailable >= 8)
{
packet_in[idx++] = bits & 0xff;
bits >>= 8;
bitsavailable -= 8;
}
}
if(bitsavailable)
packet_in[idx++] = bits & 0xff;
// Send telemetry
telemetry_link = 1;
}
static bool __attribute__((unused)) DSM_Rx_bind_check_validity()
{
uint16_t sum = 384 - 0x10;//
for(uint8_t i = 0; i < 8; i++)
sum += packet_in[i];
if( packet_in[8] != (sum>>8) || packet_in[9] != (sum&0xFF)) //Checksum
return false;
for(uint8_t i = 8; i < 14; i++)
sum += packet_in[i];
if( packet_in[14] != (sum>>8) || packet_in[15] != (sum&0xFF)) //Checksum
return false;
if(memcmp(packet_in,packet_in+4,4)) //Check ID
return false;
return true;
}
static void __attribute__((unused)) DSM_Rx_build_bind_packet()
{
uint16_t sum = 384 - 0x10;//
packet[0] = 0xff ^ cyrfmfg_id[0]; // ID
packet[1] = 0xff ^ cyrfmfg_id[1];
packet[2] = 0xff ^ cyrfmfg_id[2];
packet[3] = 0xff ^ cyrfmfg_id[3];
packet[4] = 0x01; // RX version
packet[5] = num_ch; // Number of channels
packet[6] = DSM_rx_type; // DSM type, let's just send back whatever the TX gave us...
packet[7] = 0x00; // Unknown
for(uint8_t i = 0; i < 8; i++)
sum += packet[i];
packet[8] = sum >> 8;
packet[9] = sum & 0xff;
}
static void __attribute__((unused)) DSM_abort_channel_rx(uint8_t ch)
{
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
CYRF_SetTxRxMode(IS_POWER_FLAG_on ? TXRX_OFF:RX_EN); // Force end state read
if (rx_disable_lna != IS_POWER_FLAG_on && IS_BIND_DONE)
{
rx_disable_lna = IS_POWER_FLAG_on;
CYRF_WriteRegister(CYRF_06_RX_CFG, rx_disable_lna ? 0x0A:0x4A); // AGC disabled, LNA disabled/enabled, Attenuator disabled, RX override enabled, Fast turn mode enabled, RX is 1MHz below TX
}
if(ch&0x02) DSM_set_sop_data_crc(true ,DSM_rx_type&0x80); // Set sop data,crc seed and rf channel using CH1, DSM2/X
if(ch&0x01) DSM_set_sop_data_crc(false,DSM_rx_type&0x80); // Set sop data,crc seed and rf channel using CH1, DSM2/X
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX operation
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive
}
uint16_t DSM_Rx_callback()
{
uint8_t rx_status;
static uint8_t read_retry=0;
static uint16_t pps_counter;
static uint32_t pps_timer = 0;
switch (phase)
{
case DSM_RX_BIND1:
if(packet_count==0)
read_retry=0;
//Check received data
rx_status = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_status & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_status |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_status & 0x07) == 0x02)
{ // data received with no errors
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // Need to set RXOW before data read
len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
debugln("RX:%d, CH:%d",len,hopping_frequency_no);
if(len==16)
{
CYRF_ReadDataPacketLen(packet_in, 16);
if(DSM_Rx_bind_check_validity())
{
// store tx info into eeprom
uint16_t temp = DSM_RX_EEPROM_OFFSET;
debug("ID=");
for(uint8_t i=0;i<4;i++)
{
cyrfmfg_id[i]=packet_in[i]^0xFF;
eeprom_write_byte((EE_ADDR)temp++, cyrfmfg_id[i]);
debug(" %02X", cyrfmfg_id[i]);
}
// check num_ch
num_ch=packet_in[11];
if(num_ch>12) num_ch=12;
//check DSM_rx_type
/*packet[12] 1 byte -> max DSM type allowed:
0x01 => 22ms 1024 DSM2 1 packet => number of channels is <8 and no telemetry
0x02 => 22ms 1024 DSM2 2 packets => either a number of channel >7 or telemetry enable RX
0x12 => 11ms 2048 DSM2 2 packets => can be any number of channels with/without telemetry
0xA2 => 22ms 2048 DSMX 1 packet => number of channels is <8 and no telemetry
0xB2 => 11ms 2048 DSMX => can be any number of channels with/without telemetry
(0x01 or 0xA2) and num_ch < 7 => 22ms else 11ms
&0x80 => false=DSM2, true=DSMX
&0xF0 => false=1024, true=2048 */
DSM_rx_type=packet_in[12];
switch(DSM_rx_type)
{
case 0x01:
if(num_ch>7) DSM_rx_type = 0x02; // Can't be 0x01 with this number of channels
break;
case 0xA2:
if(num_ch>7) DSM_rx_type = 0xB2; // Can't be 0xA2 with this number of channels
break;
case 0x02:
case 0x12:
case 0xB2:
break;
default: // Unknown type, default to DSMX 11ms
DSM_rx_type = 0xB2;
break;
}
eeprom_write_byte((EE_ADDR)temp, DSM_rx_type);
debugln(", num_ch=%d, type=%02X",num_ch, DSM_rx_type);
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
CYRF_SetTxRxMode(TX_EN); // Force end state TX
CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84", 16);
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX
DSM_Rx_build_bind_packet();
bind_counter=500;
phase++; // DSM_RX_BIND2;
return 1000;
}
}
DSM_abort_channel_rx(0); // Abort RX operation and receive
if(read_retry==0)
read_retry=4;
}
else
if(rx_status & 0x02) // RX error
DSM_abort_channel_rx(0); // Abort RX operation and receive
packet_count++;
if(packet_count>12)
{
packet_count=1;
if(read_retry)
read_retry--;
if(read_retry==0)
{
packet_count=0;
hopping_frequency_no++; // Change channel
hopping_frequency_no %= 0x50;
hopping_frequency_no |= 0x01; // Odd channels only
CYRF_ConfigRFChannel(hopping_frequency_no);
DSM_abort_channel_rx(0); // Abort RX operation and receive
}
}
return 1000;
case DSM_RX_BIND2:
//Transmit settings back
CYRF_WriteDataPacketLen(packet,10); // Send packet
if(bind_counter--==0)
{
BIND_DONE;
phase++; // DSM_RX_DATA_PREP
}
break;
case DSM_RX_DATA_PREP:
hopping_frequency_no = 0;
read_retry=0;
rx_data_started = false;
pps_counter = 0;
RX_LQI = 100;
DSM_cyrf_configdata();
pps_timer=millis();
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
seed = (cyrfmfg_id[0] << 8) + cyrfmfg_id[1];
if(DSM_rx_type&0x80)
{ // DSMX
DSM_calc_dsmx_channel(); // Build hop table
DSM_abort_channel_rx(1); // Abort RX operation, set sop&data&seed&rf using CH1, DSM2/X and receive
phase=DSM_RX_DATA_CH1;
}
else
{ // DSM2
rf_ch_num=0;
hopping_frequency_no = 0;
hopping_frequency[0] = 3;
hopping_frequency[1] = 0;
DSM_abort_channel_rx(1); // Abort RX operation, set sop&data&seed&rf using CH1, DSM2/X and receive
phase=DSM2_RX_SCAN;
}
break;
case DSM2_RX_SCAN: // Scan for DSM2 frequencies
//Received something ?
rx_status = DSM_Rx_check_packet();
if(rx_status == 0x02)
{ // data received with no errors
debugln("CH%d:Found %d",rf_ch_num+1,hopping_frequency[rf_ch_num]);
read_retry=0;
if(rf_ch_num)
{ // Both CH1 and CH2 found
read_retry=0;
hopping_frequency_no=0;
DSM_abort_channel_rx(1); // Abort RX operation, set sop&data&seed&rf using CH1, DSM2/X and receive
pps_timer=millis();
phase++; // DSM_RX_DATA_CH1
}
else
{
rf_ch_num++; // CH1 found, scan for CH2
hopping_frequency_no = 1;
if(hopping_frequency[1] < 3) // If no CH2 keep then restart from current
hopping_frequency[1]=hopping_frequency[0]+1;
DSM_abort_channel_rx(2); // Abort RX operation, set sop&data&seed&rf using CH2, DSM2/X and receive
}
}
else
{
read_retry++;
if(read_retry>50) // After 50ms
{ // Try next channel
debugln("CH%d:Next channel",rf_ch_num+1);
read_retry=0;
hopping_frequency_no = rf_ch_num;
hopping_frequency[rf_ch_num]++;
if(hopping_frequency[rf_ch_num] > 73) hopping_frequency[rf_ch_num] = 3;
DSM_abort_channel_rx(rf_ch_num+1); // Abort RX operation, set sop&data&seed&rf using CH1/2, DSM2/X and receive
}
else if(rx_status & 0x02)
{ // data received with errors
if((rx_status & 0x01) && rf_ch_num==0)
hopping_frequency[1] = hopping_frequency[0];// Might be CH2 since it's a CRC error so keep it
debugln("CH%d:RX error",rf_ch_num+1);
DSM_abort_channel_rx(0); // Abort RX operation and receive
}
}
return 1000;
case DSM_RX_DATA_CH1:
//Packets per second
if (millis() - pps_timer >= 1000)
{//182pps @11ms, 91pps @22ms
pps_timer = millis();
if(DSM_rx_type!=0xA2 && DSM_rx_type!=0x01) // if 11ms
pps_counter >>=1; // then /2
debugln("%d pps", pps_counter);
RX_LQI = pps_counter; // max=91pps
pps_counter = 0;
}
//Received something ?
rx_status = DSM_Rx_check_packet();
if(rx_status == 0x02)
{ // data received with no errors
#ifdef DSM_DEBUG_RF
debugln("CH1:RX");
#endif
DSM_Rx_build_telemetry_packet();
rx_data_started = true;
pps_counter++;
DSM_abort_channel_rx(2); // Abort RX operation, set sop&data&seed&rf using CH2, DSM2/X and receive
phase++;
return 5000;
}
else
{
read_retry++;
if(rx_data_started && read_retry>6) // After 6*500=3ms
{ // skip to CH2
#ifdef DSM_DEBUG_RF
debugln("CH1:Skip to CH2");
#endif
DSM_abort_channel_rx(2); // Abort RX operation, set sop&data&seed&rf using CH2, DSM2/X and receive
phase++;
return 4000;
}
if(rx_data_started && RX_LQI==0)
{ // communication lost
#ifdef DSM_DEBUG_RF
debugln("CH1:Restart...");
#endif
phase=DSM_RX_DATA_PREP;
return 1000;
}
if(read_retry>250)
{ // move to next RF channel
#ifdef DSM_DEBUG_RF
debugln("CH1:Scan");
#endif
DSM_abort_channel_rx(3); // Abort RX operation, set sop&data&seed&rf using CH2 then CH1, DSM2/X and receive
read_retry=0;
}
else if(rx_status & 0x02)
{ // data received with errors
#ifdef DSM_DEBUG_RF
debugln("CH1:RX error %02X",rx_status);
#endif
DSM_abort_channel_rx(0); // Abort RX operation and receive
}
}
return 500;
case DSM_RX_DATA_CH2:
rx_status = DSM_Rx_check_packet();
if(rx_status == 0x02)
{ // data received with no errors
#ifdef DSM_DEBUG_RF
debugln("CH2:RX");
#endif
DSM_Rx_build_telemetry_packet();
pps_counter++;
}
#ifdef DSM_DEBUG_RF
else
debugln("CH2:No RX");
#endif
DSM_abort_channel_rx(1); // Abort RX operation, set sop&data&seed&rf using CH1, DSM2/X and receive
read_retry=0;
phase=DSM_RX_DATA_CH1;
if(DSM_rx_type==0xA2) //|| DSM_rx_type==0x01 -> not needed for DSM2 since we are ok to listen even if there will be nothing
return 15000; //22ms
else
return 4000; //11ms
}
return 10000;
}
uint16_t initDSM_Rx()
{
DSM_Rx_init();
hopping_frequency_no = 0;
if (IS_BIND_IN_PROGRESS)
{
packet_count=0;
phase = DSM_RX_BIND1;
}
else
{
uint16_t temp = DSM_RX_EEPROM_OFFSET;
debug("ID=");
for(uint8_t i=0;i<4;i++)
{
cyrfmfg_id[i]=eeprom_read_byte((EE_ADDR)temp++);
debug(" %02X", cyrfmfg_id[i]);
}
DSM_rx_type=eeprom_read_byte((EE_ADDR)temp);
debugln(", type=%02X", DSM_rx_type);
phase = DSM_RX_DATA_PREP;
}
return 15000;
}
#endif

View File

@@ -41,7 +41,6 @@ enum {
};
//
uint8_t sop_col;
uint8_t ch_map[14];
const uint8_t PROGMEM DSM_ch_map_progmem[][14] = {
//22+11ms for 4..7 channels
@@ -61,116 +60,6 @@ const uint8_t PROGMEM DSM_ch_map_progmem[][14] = {
{1, 5, 2, 3, 4, 8, 9, 1, 5, 2, 3, 0, 7, 6 }, //10ch - DX18
};
const uint8_t PROGMEM DSM_pncodes[5][8][8] = {
/* Note these are in order transmitted (LSB 1st) */
{ /* Row 0 */
/* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8},
/* Col 1 */ {0x88, 0x17, 0x13, 0x3B, 0x2D, 0xBF, 0x06, 0xD6},
/* Col 2 */ {0xF1, 0x94, 0x30, 0x21, 0xA1, 0x1C, 0x88, 0xA9},
/* Col 3 */ {0xD0, 0xD2, 0x8E, 0xBC, 0x82, 0x2F, 0xE3, 0xB4},
/* Col 4 */ {0x8C, 0xFA, 0x47, 0x9B, 0x83, 0xA5, 0x66, 0xD0},
/* Col 5 */ {0x07, 0xBD, 0x9F, 0x26, 0xC8, 0x31, 0x0F, 0xB8},
/* Col 6 */ {0xEF, 0x03, 0x95, 0x89, 0xB4, 0x71, 0x61, 0x9D},
/* Col 7 */ {0x40, 0xBA, 0x97, 0xD5, 0x86, 0x4F, 0xCC, 0xD1},
/* Col 8 {0xD7, 0xA1, 0x54, 0xB1, 0x5E, 0x89, 0xAE, 0x86}*/
},
{ /* Row 1 */
/* Col 0 */ {0x83, 0xF7, 0xA8, 0x2D, 0x7A, 0x44, 0x64, 0xD3},
/* Col 1 */ {0x3F, 0x2C, 0x4E, 0xAA, 0x71, 0x48, 0x7A, 0xC9},
/* Col 2 */ {0x17, 0xFF, 0x9E, 0x21, 0x36, 0x90, 0xC7, 0x82},
/* Col 3 */ {0xBC, 0x5D, 0x9A, 0x5B, 0xEE, 0x7F, 0x42, 0xEB},
/* Col 4 */ {0x24, 0xF5, 0xDD, 0xF8, 0x7A, 0x77, 0x74, 0xE7},
/* Col 5 */ {0x3D, 0x70, 0x7C, 0x94, 0xDC, 0x84, 0xAD, 0x95},
/* Col 6 */ {0x1E, 0x6A, 0xF0, 0x37, 0x52, 0x7B, 0x11, 0xD4},
/* Col 7 */ {0x62, 0xF5, 0x2B, 0xAA, 0xFC, 0x33, 0xBF, 0xAF},
/* Col 8 {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97} */
},
{ /* Row 2 */
/* Col 0 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97},
/* Col 1 */ {0x8E, 0x4A, 0xD0, 0xA9, 0xA7, 0xFF, 0x20, 0xCA},
/* Col 2 */ {0x4C, 0x97, 0x9D, 0xBF, 0xB8, 0x3D, 0xB5, 0xBE},
/* Col 3 */ {0x0C, 0x5D, 0x24, 0x30, 0x9F, 0xCA, 0x6D, 0xBD},
/* Col 4 */ {0x50, 0x14, 0x33, 0xDE, 0xF1, 0x78, 0x95, 0xAD},
/* Col 5 */ {0x0C, 0x3C, 0xFA, 0xF9, 0xF0, 0xF2, 0x10, 0xC9},
/* Col 6 */ {0xF4, 0xDA, 0x06, 0xDB, 0xBF, 0x4E, 0x6F, 0xB3},
/* Col 7 */ {0x9E, 0x08, 0xD1, 0xAE, 0x59, 0x5E, 0xE8, 0xF0},
/* Col 8 {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E} */
},
{ /* Row 3 */
/* Col 0 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E},
/* Col 1 */ {0x80, 0x69, 0x26, 0x80, 0x08, 0xF8, 0x49, 0xE7},
/* Col 2 */ {0x7D, 0x2D, 0x49, 0x54, 0xD0, 0x80, 0x40, 0xC1},
/* Col 3 */ {0xB6, 0xF2, 0xE6, 0x1B, 0x80, 0x5A, 0x36, 0xB4},
/* Col 4 */ {0x42, 0xAE, 0x9C, 0x1C, 0xDA, 0x67, 0x05, 0xF6},
/* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
/* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
/* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
/* Col 8 {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93} */
// Wrong values used by Orange TX/RX
// /* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
},
{ /* Row 4 */
/* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
/* Col 1 */ {0xDC, 0x68, 0x08, 0x99, 0x97, 0xAE, 0xAF, 0x8C},
/* Col 2 */ {0xC3, 0x0E, 0x01, 0x16, 0x0E, 0x32, 0x06, 0xBA},
/* Col 3 */ {0xE0, 0x83, 0x01, 0xFA, 0xAB, 0x3E, 0x8F, 0xAC},
/* Col 4 */ {0x5C, 0xD5, 0x9C, 0xB8, 0x46, 0x9C, 0x7D, 0x84},
/* Col 5 */ {0xF1, 0xC6, 0xFE, 0x5C, 0x9D, 0xA5, 0x4F, 0xB7},
/* Col 6 */ {0x58, 0xB5, 0xB3, 0xDD, 0x0E, 0x28, 0xF1, 0xB0},
/* Col 7 */ {0x5F, 0x30, 0x3B, 0x56, 0x96, 0x45, 0xF4, 0xA1},
/* Col 8 {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8} */
},
};
static void __attribute__((unused)) DSM_read_code(uint8_t *buf, uint8_t row, uint8_t col, uint8_t len)
{
for(uint8_t i=0;i<len;i++)
buf[i]=pgm_read_byte_near( &DSM_pncodes[row][col][i] );
}
static uint8_t __attribute__((unused)) DSM_get_pn_row(uint8_t channel)
{
return ((sub_protocol == DSMX_11 || sub_protocol == DSMX_22 )? (channel - 2) % 5 : channel % 5);
}
const uint8_t PROGMEM DSM_init_vals[][2] = {
{CYRF_02_TX_CTRL, 0x00}, // All TX interrupt disabled
{CYRF_05_RX_CTRL, 0x00}, // All RX interrupt disabled
{CYRF_28_CLK_EN, 0x02}, // Force receive clock enable
{CYRF_32_AUTO_CAL_TIME, 0x3c}, // Default init value
{CYRF_35_AUTOCAL_OFFSET, 0x14}, // Default init value
{CYRF_06_RX_CFG, 0x4A}, // LNA enabled, RX override enabled, Fast turn mode enabled, RX is 1MHz below TX
{CYRF_1B_TX_OFFSET_LSB, 0x55}, // Default init value
{CYRF_1C_TX_OFFSET_MSB, 0x05}, // Default init value
{CYRF_39_ANALOG_CTRL, 0x01}, // All slow for synth setting time
{CYRF_01_TX_LENGTH, 0x10}, // 16 bytes packet
{CYRF_14_EOP_CTRL, 0x02}, // Set EOP Symbol Count to 2
{CYRF_12_DATA64_THOLD, 0x0a}, // 64 Chip Data PN corelator threshold, default datasheet value is 0x0E
//Below is for bind only
{CYRF_03_TX_CFG, 0x38 | CYRF_BIND_POWER}, //64 chip codes, SDR mode
{CYRF_10_FRAMING_CFG, 0x4a}, // SOP disabled, no LEN field and SOP correlator of 0x0a but since SOP is disabled...
{CYRF_1F_TX_OVERRIDE, 0x04}, // Disable TX CRC, no ACK, use TX synthesizer
{CYRF_1E_RX_OVERRIDE, 0x14}, // Disable RX CRC, Force receive data rate, use RX synthesizer
};
const uint8_t PROGMEM DSM_data_vals[][2] = {
{CYRF_29_RX_ABORT, 0x20}, // Abort RX operation in case we are coming from bind
{CYRF_0F_XACT_CFG, 0x24}, // Force Idle
{CYRF_29_RX_ABORT, 0x00}, // Clear abort RX
{CYRF_03_TX_CFG, 0x28 | CYRF_HIGH_POWER}, // 64 chip codes, 8DR mode
{CYRF_10_FRAMING_CFG, 0xea}, // SOP enabled, SOP_CODE_ADR 64 chips, Packet len enabled, SOP correlator 0x0A
{CYRF_1F_TX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
{CYRF_1E_RX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
};
static void __attribute__((unused)) DSM_cyrf_config()
{
for(uint8_t i = 0; i < sizeof(DSM_init_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&DSM_init_vals[i][0]), pgm_read_byte_near(&DSM_init_vals[i][1]));
CYRF_WritePreamble(0x333304);
CYRF_ConfigRFChannel(0x61);
}
static void __attribute__((unused)) DSM_build_bind_packet()
{
uint8_t i;
@@ -214,16 +103,12 @@ static void __attribute__((unused)) DSM_initialize_bind_phase()
{
CYRF_ConfigRFChannel(DSM_BIND_CHANNEL); //This seems to be random?
//64 SDR Mode is configured so only the 8 first values are needed but need to write 16 values...
CYRF_ConfigDataCode((const uint8_t*)"\xD7\xA1\x54\xB1\x5E\x89\xAE\x86\xc6\x94\x22\xfe\x48\xe6\x57\x4e", 16);
uint8_t code[16];
DSM_read_code(code,0,8,8);
CYRF_ConfigDataCode(code, 16);
DSM_build_bind_packet();
}
static void __attribute__((unused)) DSM_cyrf_configdata()
{
for(uint8_t i = 0; i < sizeof(DSM_data_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&DSM_data_vals[i][0]), pgm_read_byte_near(&DSM_data_vals[i][1]));
}
static void __attribute__((unused)) DSM_update_channels()
{
prev_option=option;
@@ -259,7 +144,7 @@ static void __attribute__((unused)) DSM_build_data_packet(uint8_t upper)
packet[0] = (0xff ^ cyrfmfg_id[2]);
packet[1] = (0xff ^ cyrfmfg_id[3]);
if(sub_protocol==DSM2_22)
bits=10; // Only DSM_22 is using a resolution of 1024
bits=10; // Only DSM2_22 is using a resolution of 1024
}
#ifdef DSM_THROTTLE_KILL_CH
uint16_t kill_ch=Channel_data[DSM_THROTTLE_KILL_CH-1];
@@ -284,7 +169,7 @@ static void __attribute__((unused)) DSM_build_data_packet(uint8_t upper)
else
#endif
#ifdef DSM_MAX_THROW
value=Channel_data[CH_TAER[idx]]; // -100%..+100% => 1024..1976us and -125%..+125% => 904..2096us based on Redcon 6 channel DSM2 RX
value=Channel_data[CH_TAER[idx]]; // -100%..+100% => 1024..1976us and -125%..+125% => 904..2096us based on Redcon 6 channel DSM2 RX
#else
if(option & 0x80)
value=Channel_data[CH_TAER[idx]]; // -100%..+100% => 1024..1976us and -125%..+125% => 904..2096us based on Redcon 6 channel DSM2 RX
@@ -299,66 +184,6 @@ static void __attribute__((unused)) DSM_build_data_packet(uint8_t upper)
}
}
static void __attribute__((unused)) DSM_set_sop_data_crc()
{
//The crc for channel '1' is NOT(mfgid[0] << 8 + mfgid[1])
//The crc for channel '2' is (mfgid[0] << 8 + mfgid[1])
uint16_t crc = (cyrfmfg_id[0] << 8) + cyrfmfg_id[1];
if(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B)
CYRF_ConfigCRCSeed(crc); //CH2
else
CYRF_ConfigCRCSeed(~crc); //CH1
uint8_t pn_row = DSM_get_pn_row(hopping_frequency[hopping_frequency_no]);
uint8_t code[16];
DSM_read_code(code,pn_row,sop_col,8); // pn_row between 0 and 4, sop_col between 1 and 7
CYRF_ConfigSOPCode(code);
DSM_read_code(code,pn_row,7 - sop_col,8); // 7-sop_col between 0 and 6
DSM_read_code(code+8,pn_row,7 - sop_col + 1,8); // 7-sop_col+1 between 1 and 7
CYRF_ConfigDataCode(code, 16);
CYRF_ConfigRFChannel(hopping_frequency[hopping_frequency_no]);
hopping_frequency_no++;
if(sub_protocol == DSMX_11 || sub_protocol == DSMX_22)
hopping_frequency_no %=23;
else
hopping_frequency_no %=2;
}
static void __attribute__((unused)) DSM_calc_dsmx_channel()
{
uint8_t idx = 0;
uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0));
uint32_t id_tmp = id;
while(idx < 23)
{
uint8_t i;
uint8_t count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
if ( (next_ch ^ cyrfmfg_id[3]) & 0x01 )
continue;
for (i = 0; i < idx; i++)
{
if(hopping_frequency[i] == next_ch)
break;
if(hopping_frequency[i] <= 27)
count_3_27++;
else
if (hopping_frequency[i] <= 51)
count_28_51++;
else
count_52_76++;
}
if (i != idx)
continue;
if ((next_ch < 28 && count_3_27 < 8)
||(next_ch >= 28 && next_ch < 52 && count_28_51 < 7)
||(next_ch >= 52 && count_52_76 < 8))
hopping_frequency[idx++] = next_ch;
}
}
static uint8_t __attribute__((unused)) DSM_Check_RX_packet()
{
uint8_t result=1; // assume good packet
@@ -405,7 +230,7 @@ uint16_t ReadDsm()
#if defined DSM_TELEMETRY
case DSM_BIND_CHECK:
//64 SDR Mode is configured so only the 8 first values are needed but we need to write 16 values...
CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84\xC9\x2C\x06\x93\x86\xB9\x9E\xD7", 16);
CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84", 16);
CYRF_SetTxRxMode(RX_EN); //Receive mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //Prepare to receive
bind_counter=2*DSM_BIND_COUNT; //Timeout of 4.2s if no packet received
@@ -418,18 +243,22 @@ uint16_t ReadDsm()
rx_phase |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_phase & 0x07) == 0x02)
{ // data received with no errors
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
if(len>TELEMETRY_BUFFER_SIZE-2)
len=TELEMETRY_BUFFER_SIZE-2;
CYRF_ReadDataPacketLen(packet_in+1, len);
if(len==10 && DSM_Check_RX_packet())
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // Need to set RXOW before data read
if(CYRF_ReadRegister(CYRF_09_RX_COUNT)==10) // Len
{
packet_in[0]=0x80;
telemetry_link=1; // send received data on serial
phase++;
return 2000;
CYRF_ReadDataPacketLen(packet_in+1, 10);
if(DSM_Check_RX_packet())
{
packet_in[0]=0x80;
telemetry_link=1; // Send received data on serial
phase++;
return 2000;
}
}
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
CYRF_SetTxRxMode(RX_EN); // Force end state read
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX operation
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive
}
else
if((rx_phase & 0x02) != 0x02)
@@ -441,7 +270,7 @@ uint16_t ReadDsm()
}
if( --bind_counter == 0 )
{ // Exit if no answer has been received for some time
phase++; // DSM_CHANSEL
phase++; // DSM_CHANSEL
return 7000 ;
}
return 7000;
@@ -452,7 +281,7 @@ uint16_t ReadDsm()
CYRF_SetTxRxMode(TX_EN);
hopping_frequency_no = 0;
phase = DSM_CH1_WRITE_A; // in fact phase++
DSM_set_sop_data_crc();
DSM_set_sop_data_crc(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B, sub_protocol==DSMX_11||sub_protocol==DSMX_22);
return 10000;
case DSM_CH1_WRITE_A:
#ifdef MULTI_SYNC
@@ -487,7 +316,7 @@ uint16_t ReadDsm()
CYRF_SetTxRxMode(TX_EN);
}
#endif
DSM_set_sop_data_crc();
DSM_set_sop_data_crc(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B, sub_protocol==DSMX_11 || sub_protocol==DSMX_22);
phase++; // change from CH1_CHECK to CH2_WRITE
return DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
}
@@ -529,11 +358,11 @@ uint16_t ReadDsm()
phase = DSM_CH1_WRITE_A; //Transmit lower
CYRF_SetTxRxMode(TX_EN); //TX mode
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); //Clear abort RX operation
DSM_set_sop_data_crc();
DSM_set_sop_data_crc(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B, sub_protocol==DSMX_11||sub_protocol==DSMX_22);
return DSM_READ_DELAY;
#else
// No telemetry
DSM_set_sop_data_crc();
DSM_set_sop_data_crc(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B, sub_protocol==DSMX_11||sub_protocol==DSMX_22);
if (phase == DSM_CH2_CHECK_A)
{
if(num_ch > 7 || sub_protocol==DSM2_11 || sub_protocol==DSMX_11)
@@ -565,6 +394,8 @@ uint16_t initDsm()
cyrfmfg_id[rx_tx_addr[0]%3]^=0x01; //Change a bit so sop_col will be different from 0
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
}
//Calc CRC seed
seed = (cyrfmfg_id[0] << 8) + cyrfmfg_id[1];
//Hopping frequencies
if (sub_protocol == DSMX_11 || sub_protocol == DSMX_22)
DSM_calc_dsmx_channel();

View File

@@ -162,6 +162,31 @@ static void __attribute__((unused)) DEVO_build_data_pkt()
DEVO_add_pkt_suffix();
}
static void __attribute__((unused)) DEVO_parse_telemetry_packet()
{
DEVO_scramble_pkt(); //This will unscramble the packet
debugln("RX");
if ((((uint32_t)packet[15] << 16) | ((uint32_t)packet[14] << 8) | packet[13]) != (MProtocol_id & 0x00ffffff))
return; // ID does not match
//RSSI
TX_RSSI = CYRF_ReadRegister(CYRF_13_RSSI) & 0x1F;
TX_RSSI = (TX_RSSI << 1) + TX_RSSI;
RX_RSSI = TX_RSSI;
telemetry_link = 1;
//TODO: FW telemetry https://github.com/DeviationTX/deviation/blob/5efb6a28bea697af9a61b5a0ed2528cc8d203f90/src/protocol/devo_cyrf6936.c#L232
debug("P[0]=%02X",packet[0]);
if (packet[0] == 0x30) // Volt packet
{
v_lipo1 = packet[1] << 1;
v_lipo2 = packet[3] << 1;
}
}
static void __attribute__((unused)) DEVO_cyrf_set_bound_sop_code()
{
/* crc == 0 isn't allowed, so use 1 if the math results in 0 */
@@ -270,6 +295,82 @@ static void __attribute__((unused)) DEVO_BuildPacket()
uint16_t devo_callback()
{
static uint8_t txState=0;
#if defined DEVO_HUB_TELEMETRY
int delay;
if (txState == 0)
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(2400);
#endif
DEVO_BuildPacket();
CYRF_WriteDataPacket(packet);
txState = 1;
return 900;
}
if (txState == 1)
{
int i = 0;
uint8_t reg;
while (! ((reg = CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS)) & 0x02))
{
if (++i >= DEVO_NUM_WAIT_LOOPS)
break;
}
if (((reg & 0x22) == 0x20) || (CYRF_ReadRegister(CYRF_02_TX_CTRL) & 0x80))
{
CYRF_Reset();
DEVO_cyrf_init();
DEVO_cyrf_set_bound_sop_code();
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
//printf("Rst CYRF\n");
delay = 1500;
txState = 15;
}
else
{
if (phase == DEVO_BOUND)
{
/* exit binding state */
phase = DEVO_BOUND_3;
DEVO_cyrf_set_bound_sop_code();
}
if((packet_count != 0) && (bind_counter == 0))
{
CYRF_SetTxRxMode(RX_EN); //Receive mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
txState = 2;
return 1300;
}
}
if(packet_count == 0)
{
CYRF_SetPower(0x08); //Keep tx power updated
hopping_frequency_ptr = hopping_frequency_ptr == &hopping_frequency[2] ? hopping_frequency : hopping_frequency_ptr + 1;
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
}
delay = 1500;
}
if(txState == 2)
{
uint8_t rx_state = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_state & 0x03) == 0x02)
{ // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_state |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
}
if((rx_state & 0x07) == 0x02)
{ // good data (complete with no errors)
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
CYRF_ReadDataPacketLen(packet, CYRF_ReadRegister(CYRF_09_RX_COUNT));
DEVO_parse_telemetry_packet();
}
CYRF_SetTxRxMode(TX_EN); //Write mode
delay = 200;
}
txState = 0;
return delay;
#else
if (txState == 0)
{
#ifdef MULTI_SYNC
@@ -298,6 +399,7 @@ uint16_t devo_callback()
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
}
return 1200;
#endif
}
uint16_t DevoInit()

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,11 @@
/** FrSky D and X routines **/
/******************************/
#if defined(FRSKYX_CC2500_INO) || defined(FRSKY_RX_CC2500_INO) || defined(FRSKYR9_SX1276_INO)
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO) || defined(FRSKY_RX_CC2500_INO) || defined(FRSKYR9_SX1276_INO)
uint8_t FrSkyFormat=0;
#endif
#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,17 +33,80 @@ 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;
}
#endif
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYR9_SX1276_INO)
static void __attribute__((unused)) FrSkyX_channels(uint8_t offset)
{
static uint8_t chan_start=0;
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
//packet[7] = FLAGS 00 - standard packet
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
//20 - range check packet
#ifdef FAILSAFE_ENABLE
#define FRSKYX_FAILSAFE_TIMEOUT 1032
static uint16_t failsafe_count=0;
static uint8_t FS_flag=0,failsafe_chan=0;
if (FS_flag == 0 && failsafe_count > FRSKYX_FAILSAFE_TIMEOUT && chan_start == 0 && IS_FAILSAFE_VALUES_on)
{
FS_flag = 0x10;
failsafe_chan = 0;
} 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 ++;
} else if (FS_flag & 0x10)
{
FS_flag = 0;
failsafe_count = 0;
FAILSAFE_VALUES_off;
}
failsafe_count++;
packet[7] = FS_flag;
#else
packet[7] = 0;
#endif
//
uint8_t chan_index = chan_start;
uint16_t ch1,ch2;
for(uint8_t i = offset; i < 12+offset ; i+=3)
{//12 bytes of channel data
#ifdef FAILSAFE_ENABLE
if( (FS_flag & 0x10) && ((failsafe_chan & 0x07) == (chan_index & 0x07)) )
ch1 = FrSkyX_scaleForPXX_FS(failsafe_chan);
else
#endif
ch1 = FrSkyX_scaleForPXX(chan_index);
chan_index++;
//
#ifdef FAILSAFE_ENABLE
if( (FS_flag & 0x10) && ((failsafe_chan & 0x07) == (chan_index & 0x07)) )
ch2 = FrSkyX_scaleForPXX_FS(failsafe_chan);
else
#endif
ch2 = FrSkyX_scaleForPXX(chan_index);
chan_index++;
//3 bytes per channel
packet[i] = ch1;
packet[i+1]=(((ch1>>8) & 0x0F)|(ch2 << 4));
packet[i+2]=ch2>>4;
}
if(FrSkyFormat & 0x01) //In X8 mode send only 8ch every 9ms
chan_start = 0 ;
else
chan_start^=0x08;
}
#endif
#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,
@@ -70,11 +137,72 @@ void Frsky_init_hop(void)
hopping_frequency[i]=i>46?0:val;
}
}
void FrSkyX2_init_hop(void)
{
uint16_t id=(rx_tx_addr[2]<<8) + rx_tx_addr[3];
//Increment
uint8_t inc = (id % 46) + 1;
if( inc == 12 || inc ==35 ) inc++; //Exception list from dumps
//Start offset
uint8_t offset = id % 5;
debug("hop: ");
uint8_t channel;
for(uint8_t i=0; i<47; i++)
{
channel = 5 * (uint16_t(inc * i) % 47) + offset;
//Exception list from dumps
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
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
hopping_frequency[i] = channel;
debug(" %02X",channel);
}
debugln("");
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 ,
@@ -142,48 +270,68 @@ void Frsky_init_hop(void)
/*15_DEVIATN*/ 0x42 };
#endif
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYX2_CC2500_INO)
#if defined(FRSKYX_CC2500_INO) || defined(FRSKYL_CC2500_INO)
const PROGMEM uint8_t FRSKYX_cc2500_conf[]= {
//FRSKYX
/*02_IOCFG0*/ 0x06 ,
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
/*17_MCSM1*/ 0x0c ,
/*17_MCSM1*/ 0x0c , //X2->0x0E -> Go/Stay in RX mode
/*18_MCSM0*/ 0x18 ,
/*06_PKTLEN*/ 0x1E ,
/*07_PKTCTRL1*/ 0x04 ,
/*08_PKTCTRL0*/ 0x01 ,
/*08_PKTCTRL0*/ 0x01 , //X2->0x05 -> CRC enabled
/*3E_PATABLE*/ 0xff ,
/*0B_FSCTRL1*/ 0x0A ,
/*0C_FSCTRL0*/ 0x00 ,
/*0D_FREQ2*/ 0x5c ,
/*0E_FREQ1*/ 0x76 ,
/*0F_FREQ0*/ 0x27 ,
/*10_MDMCFG4*/ 0x7B ,
/*11_MDMCFG3*/ 0x61 ,
/*10_MDMCFG4*/ 0x7B ,
/*11_MDMCFG3*/ 0x61 , //X2->0x84 -> bitrate 70K->77K
/*12_MDMCFG2*/ 0x13 ,
/*13_MDMCFG1*/ 0x23 ,
/*14_MDMCFG0*/ 0x7a ,
/*15_DEVIATN*/ 0x51 };
const PROGMEM uint8_t FRSKYXEU_cc2500_conf[]= {
/*02_IOCFG0*/ 0x06 ,
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
/*17_MCSM1*/ 0x0E ,
/*18_MCSM0*/ 0x18 ,
/*06_PKTLEN*/ 0x23 ,
/*07_PKTCTRL1*/ 0x04 ,
/*08_PKTCTRL0*/ 0x01 ,
/*08_PKTCTRL0*/ 0x01 , //X2->0x05 -> CRC enabled
/*3E_PATABLE*/ 0xff ,
/*0B_FSCTRL1*/ 0x08 ,
/*0C_FSCTRL0*/ 0x00 ,
/*0D_FREQ2*/ 0x5c ,
/*0D_FREQ2*/ 0x5c ,
/*0E_FREQ1*/ 0x80 ,
/*0F_FREQ0*/ 0x00 ,
/*10_MDMCFG4*/ 0x7B ,
/*10_MDMCFG4*/ 0x7B ,
/*11_MDMCFG3*/ 0xF8 ,
/*12_MDMCFG2*/ 0x03 ,
/*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]= {
@@ -222,15 +370,13 @@ void Frsky_init_hop(void)
uint8_t val=pgm_read_byte_near(&FRSKY_common_end_cc2500_conf[i][1]);
CC2500_WriteReg(reg,val);
}
if(protocol==PROTO_FRSKYX2)
CC2500_WriteReg(CC2500_08_PKTCTRL0, 0x05); // enable CRC
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
}
#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 ;
@@ -245,8 +391,6 @@ uint8_t FrSkyX_RX_Seq ;
struct t_FrSkyX_TX_Frame FrSkyX_TX_Frames[4] ;
#endif
#define FRSKYX_FAILSAFE_TIMEOUT 1032
static void __attribute__((unused)) FrSkyX_set_start(uint8_t ch )
{
CC2500_Strobe(CC2500_SIDLE);
@@ -256,7 +400,19 @@ 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(!(FrSkyFormat&2))
{ // FCC
CC2500_WriteReg(CC2500_17_MCSM1, 0x0E); // Go/Stay in RX mode
CC2500_WriteReg(CC2500_11_MDMCFG3, 0x84); // bitrate 70K->77K
}
}
//
for(uint8_t c=0;c < 48;c++)
{//calibrate hop channels

View File

@@ -97,15 +97,18 @@ static void __attribute__((unused)) frsky2way_data_frame()
uint16_t initFrSky_2way()
{
//FrskyD init hop
for(uint8_t i=0;i<50;i++)
{
uint8_t freq = (i * 0x1e) % 0xeb;
if(i == 3 || i == 23 || i == 47)
freq++;
if(i > 47)
freq=0;
hopping_frequency[i]=freq;
}
if (sub_protocol==DCLONE)
Frsky_init_clone();
else
for(uint8_t i=0;i<50;i++)
{
uint8_t freq = (i * 0x1e) % 0xeb;
if(i == 3 || i == 23 || i == 47)
freq++;
if(i > 47)
freq=0;
hopping_frequency[i]=freq;
}
packet_count=0;
if(IS_BIND_IN_PROGRESS)

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,19 +1,17 @@
/* **************************
* 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
(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/>.
*/
/*
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(FRSKYX_CC2500_INO)
@@ -21,115 +19,91 @@
static void __attribute__((unused)) FrSkyX_build_bind_packet()
{
packet[0] = (sub_protocol & 2 ) ? 0x20 : 0x1D ; // LBT or FCC
packet[1] = 0x03;
packet[2] = 0x01;
//
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
int idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = hopping_frequency[idx++];
packet[7] = hopping_frequency[idx++];
packet[8] = hopping_frequency[idx++];
packet[9] = hopping_frequency[idx++];
packet[10] = hopping_frequency[idx++];
packet[11] = 0x02;
packet[12] = RX_num;
//
uint8_t limit = (sub_protocol & 2 ) ? 31 : 28 ;
memset(&packet[13], 0, limit - 13);
if(binding_idx&0x01)
memcpy(&packet[13],(void *)"\x55\xAA\x5A\xA5",4); // Telem off
if(binding_idx&0x02)
memcpy(&packet[17],(void *)"\x55\xAA\x5A\xA5",4); // CH9-16
//
uint16_t lcrc = FrSkyX_crc(&packet[3], limit-3);
//
packet[limit++] = lcrc >> 8;
packet[limit] = lcrc;
//
uint8_t packet_size = 0x1D;
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] = 0x03; // Bind packet
packet[2] = 0x01; // Bind packet
//ID
packet[3] = rx_tx_addr[3]; // ID
packet[4] = rx_tx_addr[2]; // ID
if(protocol==PROTO_FRSKYX)
{
int idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = hopping_frequency[idx++];
packet[7] = hopping_frequency[idx++];
packet[8] = hopping_frequency[idx++];
packet[9] = hopping_frequency[idx++];
packet[10] = hopping_frequency[idx++];
packet[11] = rx_tx_addr[1]; // Unknown but constant ID?
packet[12] = RX_num;
//
memset(&packet[13], 0, packet_size - 14);
if(binding_idx&0x01)
memcpy(&packet[13],(void *)"\x55\xAA\x5A\xA5",4); // Telem off
if(binding_idx&0x02)
memcpy(&packet[17],(void *)"\x55\xAA\x5A\xA5",4); // CH9-16
}
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] = rx_tx_addr[1]; // Unknown but constant ID?
packet[6] = RX_num;
//Bind flags
packet[7]=0;
if(binding_idx&0x01)
packet[7] |= 0x40; // Telem off
if(binding_idx&0x02)
packet[7] |= 0x80; // CH9-16
//Unknown bytes
memcpy(&packet[8],"\x32\x0B\x00\x00\xA8\x26\x28\x01\xA1\x00\x00\x00\x3E\xF6\x87\xC7",16);
packet[20]^= 0x0E ^ rx_tx_addr[3]; // Update the ID
packet[21]^= 0x1C ^ rx_tx_addr[2]; // Update the ID
//Xor
for(uint8_t i=3; i<packet_size-1; i++)
packet[i] ^= 0xA7;
}
//CRC
uint16_t lcrc = FrSkyX_crc(&packet[3], packet_size-4);
packet[packet_size-1] = lcrc >> 8;
packet[packet_size] = lcrc;
/*//Debug
debug("Bind:");
for(uint8_t i=0;i<=packet_size;i++)
debug(" %02X",packet[i]);
debugln("");*/
}
#define FrSkyX_FAILSAFE_TIME 1032
static void __attribute__((unused)) FrSkyX_build_packet()
{
//0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12
//
static uint8_t chan_offset=0;
uint16_t chan_0 ;
uint16_t chan_1 ;
//
// data frames sent every 9ms; failsafe every 9 seconds
#ifdef FAILSAFE_ENABLE
static uint16_t failsafe_count=0;
static uint8_t FS_flag=0,failsafe_chan=0;
if (FS_flag == 0 && failsafe_count > FrSkyX_FAILSAFE_TIME && chan_offset == 0 && IS_FAILSAFE_VALUES_on)
{
FS_flag = 0x10;
failsafe_chan = 0;
} else if (FS_flag & 0x10 && failsafe_chan < (sub_protocol & 0x01 ? 8-1:16-1))
{
FS_flag = 0x10 | ((FS_flag + 2) & 0x0F); //10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
failsafe_chan ++;
} else if (FS_flag & 0x10)
{
FS_flag = 0;
failsafe_count = 0;
FAILSAFE_VALUES_off;
}
failsafe_count++;
#endif
packet[0] = (sub_protocol & 0x02 ) ? 0x20 : 0x1D ; // LBT or FCC
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = 0x02;
//
uint8_t packet_size = 0x1D;
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] = rx_tx_addr[1]; // Unknown but constant ID?
//
packet[4] = (FrSkyX_chanskip<<6)|hopping_frequency_no;
packet[5] = FrSkyX_chanskip>>2;
packet[6] = RX_num;
//packet[7] = FLAGS 00 - standard packet
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
//20 - range check packet
#ifdef FAILSAFE_ENABLE
packet[7] = FS_flag;
#else
packet[7] = 0;
#endif
packet[8] = 0;
//
uint8_t startChan = chan_offset;
for(uint8_t i = 0; i <12 ; i+=3)
{//12 bytes of channel data
#ifdef FAILSAFE_ENABLE
if( (FS_flag & 0x10) && ((failsafe_chan & 0x07) == (startChan & 0x07)) )
chan_0 = FrSkyX_scaleForPXX_FS(failsafe_chan);
else
#endif
chan_0 = FrSkyX_scaleForPXX(startChan);
startChan++;
//
#ifdef FAILSAFE_ENABLE
if( (FS_flag & 0x10) && ((failsafe_chan & 0x07) == (startChan & 0x07)) )
chan_1 = FrSkyX_scaleForPXX_FS(failsafe_chan);
else
#endif
chan_1 = FrSkyX_scaleForPXX(startChan);
startChan++;
//
packet[9+i] = lowByte(chan_0); //3 bytes*4
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
chan_offset = 0 ;
else
chan_offset^=0x08;
packet[8] = 0; //??
FrSkyX_channels(9); // Set packet[7] and packet[9..20] with channels data and failsafe
//sequence and send SPort
uint8_t limit = (sub_protocol & 2 ) ? 31 : 28 ;
for (uint8_t i=22;i<limit;i++)
for (uint8_t i=22;i<packet_size-1;i++)
packet[i]=0;
packet[21] = FrSkyX_RX_Seq << 4; //TX=8 at startup
#ifdef SPORT_SEND
@@ -157,7 +131,7 @@ static void __attribute__((unused)) FrSkyX_build_packet()
//debugln("Send:%d",FrSkyX_TX_Seq);
packet[21] |= FrSkyX_TX_Seq;
uint8_t nbr_bytes=0;
for (uint8_t i=23;i<limit;i++)
for (uint8_t i=23;i<packet_size-1;i++)
{
if(SportHead==SportTail)
break; //buffer empty
@@ -208,18 +182,20 @@ static void __attribute__((unused)) FrSkyX_build_packet()
FrSkyX_TX_Seq = ( FrSkyX_TX_Seq + 1 ) & 0x03 ; // Next iteration send next packet
#endif // SPORT_SEND
uint16_t lcrc = FrSkyX_crc(&packet[3], limit-3);
packet[limit++]=lcrc>>8;//high byte
packet[limit]=lcrc;//low byte
//CRC
uint16_t lcrc = FrSkyX_crc(&packet[3], packet_size-4);
packet[packet_size-1] = lcrc >> 8;
packet[packet_size] = lcrc;
/*//Debug
debug("Norm:");
for(uint8_t i=0;i<=packet_size;i++)
debug(" %02X",packet[i]);
debugln("");*/
}
uint16_t ReadFrSkyX()
{
static bool transmit=true;
#ifdef DEBUG_SERIAL
static uint16_t fr_time=0;
#endif
switch(state)
{
default:
@@ -241,7 +217,61 @@ uint16_t ReadFrSkyX()
BIND_DONE;
state++; //FRSKY_DATA1
break;
case FRSKY_DATA5:
case FRSKY_DATA1:
CC2500_Strobe(CC2500_SIDLE);
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); //Frequency offset hack
prev_option = option ;
}
FrSkyX_set_start(hopping_frequency_no);
FrSkyX_build_packet();
if(FrSkyFormat & 2)
{// LBT
CC2500_Strobe(CC2500_SRX); //Acquire RSSI
state++;
return 400; // LBT v2.1
}
case FRSKY_DATA2:
if(FrSkyFormat & 2)
{
uint16_t rssi=0;
for(uint8_t i=0;i<4;i++)
rssi += CC2500_ReadReg(CC2500_34_RSSI | CC2500_READ_BURST); // 0.5 db/count, RSSI value read from the RSSI status register is a 2's complement number
rssi>>=2;
#if 0
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 > 14 && rssi < 128) // if RSSI above -65dBm (12=-70) => ETSI requirement
#endif
{
LBT_POWER_on; // Reduce to low power before transmitting
debugln("Busy %d %d",hopping_frequency_no,rssi);
}
}
CC2500_Strobe(CC2500_SIDLE);
CC2500_Strobe(CC2500_SFTX);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
hopping_frequency_no = (hopping_frequency_no+FrSkyX_chanskip)%47;
CC2500_WriteData(packet, packet[0]+1);
state=FRSKY_DATA3;
if(FrSkyFormat & 2)
return 4000; // LBT v2.1
else
return 5200; // FCC v2.1
case FRSKY_DATA3:
CC2500_Strobe(CC2500_SIDLE);
CC2500_SetTxRxMode(RX_EN);
CC2500_Strobe(CC2500_SRX);
state++;
if(FrSkyFormat & 2)
return 4100; // LBT v2.1
else
return 3300; // FCC v2.1
case FRSKY_DATA4:
#ifdef MULTI_SYNC
telemetry_set_input_sync(9000);
#endif
@@ -251,11 +281,19 @@ uint16_t ReadFrSkyX()
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len && (len<=(0x0E + 3))) //Telemetry frame is 17
{
//debug("Telem:");
packet_count=0;
CC2500_ReadData(packet_in, len);
#if defined TELEMETRY
frsky_check_telemetry(packet_in,len); //Check and parse telemetry packets
if(protocol==PROTO_FRSKYX || (protocol==PROTO_FRSKYX2 && (packet_in[len-1] & 0x80)) )
{//with valid crc for FRSKYX2
//Debug
//for(uint8_t i=0;i<len;i++)
// debug(" %02X",packet_in[i]);
frsky_check_telemetry(packet_in,len); //Check and parse telemetry packets
}
#endif
//debugln("");
}
else
{
@@ -278,61 +316,8 @@ uint16_t ReadFrSkyX()
}
CC2500_Strobe(CC2500_SFRX); //Flush the RXFIFO
}
FrSkyX_build_packet();
state = FRSKY_DATA1;
#if not defined(FRSKYX_LBT)
return 500;
#endif // for LBT just continue to DATA1 right away
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);
transmit=true;
#ifdef FRSKYX_LBT
CC2500_Strobe(CC2500_SIDLE);
delayMicroseconds(90); //Wait for the freq to stabilize
CC2500_Strobe(CC2500_SRX); //Acquire RSSI
state++;
return 500;
case FRSKY_DATA2:
uint8_t rssi;
rssi = CC2500_ReadReg(CC2500_34_RSSI | CC2500_READ_BURST); // 0.5 db/count, RSSI value read from the RSSI status register is a 2's complement number
if ((sub_protocol & 2) && rssi > 72 && rssi < 128) //LBT and RSSI between -36 and -8.5 dBm
{
transmit=false;
debugln("Busy %d %d",hopping_frequency_no,rssi);
}
#endif
CC2500_Strobe(CC2500_SIDLE);
CC2500_Strobe(CC2500_SFRX);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
hopping_frequency_no = (hopping_frequency_no+FrSkyX_chanskip)%47;
if(transmit)
{
#ifdef DEBUG_SERIAL
uint16_t fr_cur=millis();
fr_time=fr_cur-fr_time;
if(fr_time!=9)
debugln("Bad timing: %d",fr_time);
fr_time=fr_cur;
#endif
CC2500_WriteData(packet, packet[0]+1);
}
state=FRSKY_DATA3;
return 5200;
case FRSKY_DATA3:
CC2500_SetTxRxMode(RX_EN);
CC2500_Strobe(CC2500_SIDLE);
state++;
return 200;
case FRSKY_DATA4:
CC2500_Strobe(CC2500_SRX);
state++;
return 3100;
return 500; // FCC & LBT v2.1
}
return 1;
}
@@ -340,15 +325,30 @@ uint16_t ReadFrSkyX()
uint16_t initFrSkyX()
{
set_rx_tx_addr(MProtocol_id_master);
Frsky_init_hop();
FrSkyFormat = sub_protocol;
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
rx_tx_addr[3]=0x0E;
rx_tx_addr[2]=0x1C;
FrSkyX_chanskip=18;
#endif
rx_tx_addr[1]=0x02; // ID related, hw version?
FrSkyX2_init_hop();
}
packet_count=0;
while(!FrSkyX_chanskip)
FrSkyX_chanskip=random(0xfefefefe)%47;
//for test***************
//rx_tx_addr[3]=0xB3;
//rx_tx_addr[2]=0xFD;
//************************
FrSkyX_init();
if(IS_BIND_IN_PROGRESS)
@@ -372,4 +372,4 @@ uint16_t initFrSkyX()
binding_idx=0; // CH1-8 and Telem on
return 10000;
}
#endif
#endif

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,29 +119,38 @@ 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) {
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]));
break;
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]));
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;
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_23_FSCAL3, 0x89);
break;
}
CC2500_WriteReg(CC2500_0A_CHANNR, 0); // bind channel
rx_disable_lna = IS_POWER_FLAG_on;
@@ -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;
}
else
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,154 +393,199 @@ 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) {
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
frsky_rx_finetune = -127;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
phase = 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_initialise_cc2500();
frsky_rx_finetune += 10;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
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]) {
tune_low = frsky_rx_finetune;
frsky_rx_finetune = 127;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
phase = FRSKY_RX_TUNE_HIGH;
frsky_rx_strobe_rx();
return 1000;
}
}
frsky_rx_finetune += 1;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
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]) {
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;
else
phase = FRSKY_RX_TUNE_START;
frsky_rx_strobe_rx();
return 1000;
}
}
frsky_rx_finetune -= 1;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
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) {
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);
// 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++)
{
eeprom_write_byte((EE_ADDR)temp++, hopping_frequency[ch]);
debug("%02X ", hopping_frequency[ch]);
}
debugln("");
BIND_DONE;
switch(phase)
{
case FRSKY_RX_TUNE_START:
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 (D8, D16FCC, D16LBT, D16v2FCC, D16v2LBT)
frsky_rx_initialise_cc2500();
frsky_rx_finetune += 10;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
}
return 1000;
return 18000;
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(RX_RSSI >= 128)
RX_RSSI -= 128;
else
RX_RSSI += 128;
// hop to next channel
if (frsky_rx_format == FRSKY_RX_D16FCC || frsky_rx_format == FRSKY_RX_D16LBT)
frsky_rx_chanskip = ((packet[4] & 0xC0) >> 6) | ((packet[5] & 0x3F) << 2);
case FRSKY_RX_TUNE_LOW:
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;
}
}
frsky_rx_finetune += 1;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
return 18000;
case FRSKY_RX_TUNE_HIGH:
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;
}
}
frsky_rx_finetune -= 1;
CC2500_WriteReg(CC2500_0C_FSCTRL0, frsky_rx_finetune);
frsky_rx_strobe_rx();
return 18000;
case FRSKY_RX_BIND:
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);
}
}
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;
if(sub_protocol==FRSKY_CLONE)
{
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;
}
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();
}
return 1000;
case FRSKY_RX_DATA:
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_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(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;
}
}
// packets per second
if (millis() - pps_timer >= 1000) {
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;
}
// skip channel if no packet received in time
if (read_retry++ >= 9) {
hopping_frequency_no = (hopping_frequency_no + frsky_rx_chanskip) % 47;
frsky_rx_set_channel(hopping_frequency_no);
if (telemetry_link == 0) { // send channels to TX
frsky_rx_build_telemetry_packet();
telemetry_link = 1;
}
rx_data_started = true;
read_retry = 0;
pps_counter++;
if(rx_data_started)
read_retry = 0;
else
read_retry = -50; // retry longer until first packet is catched
}
}
// packets per second
if (millis() - pps_timer >= 1000) {
pps_timer = millis();
debugln("%d pps", pps_counter);
RX_LQI = pps_counter;
pps_counter = 0;
}
// skip channel if no packet received in time
if (read_retry++ >= 9) {
hopping_frequency_no = (hopping_frequency_no + frsky_rx_chanskip) % 47;
frsky_rx_set_channel(hopping_frequency_no);
if(rx_data_started)
read_retry = 0;
else
read_retry = -50; // retry longer until first packet is catched
}
break;
break;
}
return 1000;
}

View File

@@ -29,10 +29,21 @@ enum {
HOTT_START = 0x00,
HOTT_CAL = 0x01,
HOTT_DATA1 = 0x02,
HOTT_RX1 = 0x03,
HOTT_RX2 = 0x04,
HOTT_DATA2 = 0x03,
HOTT_RX1 = 0x04,
HOTT_RX2 = 0x05,
};
#ifdef HOTT_FW_TELEMETRY
#define HOTT_SENSOR_TYPE 6
#define HOTT_SENSOR_SEARCH_PERIOD 2000
uint8_t HOTT_sensor_cur=0;
uint8_t HOTT_sensor_pages=0;
uint8_t HOTT_sensor_valid=false;
uint8_t HOTT_sensor_ok[HOTT_SENSOR_TYPE];
uint8_t HOTT_sensor_seq=0;
#endif
#define HOTT_FREQ0_VAL 0x6E
// Some important initialization parameters, all others are either default,
@@ -103,7 +114,7 @@ static void __attribute__((unused)) HOTT_tune_freq()
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_WriteReg(CC2500_0F_FREQ0, HOTT_FREQ0_VAL + HOTT_COARSE);
prev_option = option ;
phase = HOTT_START; // Restart the tune process if option is changed to get good tuned values
phase = HOTT_START; // Restart the tune process if option is changed to get good tuned values
}
}
@@ -134,36 +145,37 @@ static void __attribute__((unused)) HOTT_init()
for(uint8_t i=0; i<HOTT_NUM_RF_CHANNELS; i++)
hopping_frequency[i]=pgm_read_byte_near( &HOTT_hop[num_ch][i] );
#ifdef HOTT_FORCE_ID
memcpy(rx_tx_addr,"\x7C\x94\x00\x0D\x50",5);
memcpy(rx_tx_addr,"\x7C\x94\x00\x0D\x50",5); //TX1
memcpy(rx_tx_addr,"\xEA\x4D\x00\x01\x50",5); //TX2
#endif
memset(&packet[30],0xFF,9);
packet[39]=0x07; // unknown and constant
packet[39]=0x07; // unknown and constant
if(IS_BIND_IN_PROGRESS)
{
packet[28] = 0x80; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets
memset(&packet[40],0xFA,5);
memcpy(&packet[45],rx_tx_addr,5);
}
else
{
packet[28] = 0x8C; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets, 0x0F->config menu
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets, 0x01->config menu, 0x0A->no more RX telemetry
memcpy(&packet[40],rx_tx_addr,5);
uint8_t addr=HOTT_EEPROM_OFFSET+RX_num*5;
debug("RXID: ");
for(uint8_t i=0;i<5;i++)
{
packet[45+i]=eeprom_read_byte((EE_ADDR)(addr+i));
debug(" %02X",packet[45+i]);
}
debugln("");
}
}
static void __attribute__((unused)) HOTT_data_packet()
static void __attribute__((unused)) HOTT_prep_data_packet()
{
packet[2] = hopping_frequency_no;
packet[3] = 0x00; // used for failsafe but may also be used for additional channels
packet[3] = 0x00; // used for failsafe but may also be used for additional channels
#ifdef FAILSAFE_ENABLE
static uint8_t failsafe_count=0;
if(IS_FAILSAFE_VALUES_on && IS_BIND_DONE)
@@ -210,31 +222,45 @@ static void __attribute__((unused)) HOTT_data_packet()
packet[i] = val;
packet[i+1] = val>>8;
}
#ifdef HOTT_FW_TELEMETRY
static uint8_t prev_SerialRX_val=0;
if(HoTT_SerialRX && HoTT_SerialRX_val >= 0xD7 && HoTT_SerialRX_val <= 0xDF)
if(IS_BIND_DONE)
{
if(prev_SerialRX_val!=HoTT_SerialRX_val)
{
prev_SerialRX_val=HoTT_SerialRX_val;
packet[28] = HoTT_SerialRX_val; // send the touch being pressed only once
static uint8_t prev_SerialRX_val=0;
if(HoTT_SerialRX)
{//Text mode
uint8_t sensor=HoTT_SerialRX_val&0xF0;
if((sensor&0x80) && sensor!=0xF0 && (HoTT_SerialRX_val&0x0F) >= 0x07)
{//Valid Text query
if(sensor==0x80) HoTT_SerialRX_val&=0x0F; // RX only
if(prev_SerialRX_val!=HoTT_SerialRX_val)
{
prev_SerialRX_val=HoTT_SerialRX_val;
packet[28] = HoTT_SerialRX_val; // send the button being pressed only once
}
else
packet[28] = HoTT_SerialRX_val | 0x0F; // no button pressed
packet[29] = 0x01; // 0x01->Text config menu
}
}
else
packet[28] = 0xDF; // no touch pressed
packet[29] = 0x01; // 0x01->config menu
{
packet[28] = 0x89+HOTT_sensor_cur; // 0x89/8A/8B/8C/8D/8E during normal packets
if(sub_protocol == HOTT_SYNC)
packet[29] = ((HOTT_sensor_seq+1)<<3) | 2; // Telemetry packet sequence
else
packet[29] = 0x02;
//debugln("28=%02X,29=%02X",packet[28],packet[29]);
}
}
else
{
packet[28] = 0x8C; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets, 0x0F->config menu
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets, 0x01->config menu, 0x0A->no more RX telemetry
}
#endif
{
packet[28] = 0x80; // no sensor
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets, 0x01->text config menu, 0x0A->no more RX telemetry
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_WriteReg(CC2500_06_PKTLEN, 0x32);
CC2500_WriteData(packet, HOTT_TX_PACKET_LEN);
CC2500_WriteReg(CC2500_06_PKTLEN, HOTT_TX_PACKET_LEN);
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, packet, HOTT_TX_PACKET_LEN);
#if 0
debug("RF:%02X P:",rf_ch_num);
for(uint8_t i=0;i<HOTT_TX_PACKET_LEN;i++)
@@ -268,38 +294,86 @@ uint16_t ReadHOTT()
hopping_frequency_no = 0;
rf_ch_num=hopping_frequency[hopping_frequency_no];
counter = 0;
CC2500_SetTxRxMode(RX_EN);
phase = HOTT_DATA1;
}
return 2000;
/* Work cycle: 10ms */
case HOTT_DATA1:
//TX
//Set RF freq, setup LBT and prep packet
#ifdef MULTI_SYNC
telemetry_set_input_sync(HOTT_PACKET_PERIOD);
#endif
//Clear all
CC2500_Strobe(CC2500_SIDLE);
CC2500_Strobe(CC2500_SNOP);
CC2500_Strobe(CC2500_SFTX);
CC2500_Strobe(CC2500_SFRX);
CC2500_WriteReg(CC2500_04_SYNC1, 0xD3);
CC2500_WriteReg(CC2500_05_SYNC0, 0x91);
//Set RF freq
HOTT_tune_freq();
HOTT_tune_chan_fast();
HOTT_data_packet();
phase = HOTT_RX1;
return 4500;
//Setup LBT
CC2500_WriteReg(CC2500_1B_AGCCTRL2, 0xFF);
CC2500_WriteReg(CC2500_1C_AGCCTRL1, 0x0C);
CC2500_Strobe(CC2500_SRX);
//Prep packet
HOTT_prep_data_packet();
//Listen
CC2500_WriteReg(CC2500_17_MCSM1, 0x10); //??
CC2500_WriteReg(CC2500_18_MCSM0, 0x18); //??
CC2500_Strobe(CC2500_SRX); //??
phase++; //HOTT_DATA2
return 1095;
case HOTT_DATA2:
//LBT
if((CC2500_ReadReg(CC2500_38_PKTSTATUS | CC2500_READ_BURST)&0x10)==0)
{ //Channel is busy
LBT_POWER_on; // Reduce to low power before transmitting
debugln("Busy %d",rf_ch_num);
}
CC2500_WriteReg(CC2500_17_MCSM1, 0x00); //??
CC2500_WriteReg(CC2500_18_MCSM0, 0x08); //??
CC2500_SetPower();
//Send packet
CC2500_SetTxRxMode(TX_EN);
CC2500_Strobe(CC2500_STX);
phase++; //HOTT_RX1
return 3880;
case HOTT_RX1:
//Clear all
CC2500_Strobe(CC2500_SIDLE);
CC2500_Strobe(CC2500_SFTX);
CC2500_Strobe(CC2500_SFRX);
//RX
if(packet[29] & 0xF8)
{// binary telemetry
CC2500_WriteReg(CC2500_04_SYNC1, 0x2C);
CC2500_WriteReg(CC2500_05_SYNC0, 0x6E);
}
CC2500_SetTxRxMode(RX_EN);
CC2500_WriteReg(CC2500_1B_AGCCTRL2, 0xC7);
CC2500_WriteReg(CC2500_1C_AGCCTRL1, 0x09);
CC2500_WriteReg(CC2500_06_PKTLEN, HOTT_RX_PACKET_LEN);
CC2500_Strobe(CC2500_SRX);
phase = HOTT_RX2;
return 4500;
phase++; //HOTT_RX2
return 4025;
case HOTT_RX2:
//Telemetry
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len==HOTT_RX_PACKET_LEN+2)
{
CC2500_ReadData(packet_in, len);
if(memcmp(rx_tx_addr,packet_in,5)==0)
{ // TX ID matches
if((packet_in[HOTT_RX_PACKET_LEN+1]&0x80) && memcmp(rx_tx_addr,packet_in,5)==0)
{ // CRC OK and TX ID matches
if(IS_BIND_IN_PROGRESS)
{
//GR-16: D4 20 F2 E6 F6 31 BD 01 00 90 00 FF 03 00 9E 1B 00 00 00 00 00 00
//GR-12L: D4 20 F2 E6 F6 6E EE 01 00 B1 00 FF 03 00 0E 08 10 00 02 00 00 00
//Vector: D4 20 F2 E6 F6 00 00 3A 01 A1 00 00 1A 24 35 1A 00 24 00 00 00 1A
// -----TXID----- -----RXID----- ---------------Unknown-------------
debug("B:");
for(uint8_t i=0;i<HOTT_RX_PACKET_LEN;i++)
debug(" %02X", packet_in[i]);
@@ -317,16 +391,16 @@ uint16_t ReadHOTT()
// [5..9] = RXID
// [10] = 0x40 bind, 0x00 normal, 0x80 config menu
// [11] = telmetry pages. For sensors 0x00 to 0x04, for config mennu 0x00 to 0x12.
// Normal telem page 0 = 0x00, 0x33, 0x34, 0x46, 0x64, 0x33, 0x0A, 0x00, 0x00, 0x00
// = 0x55, 0x32, 0x38, 0x55, 0x64, 0x32, 0xD0, 0x07, 0x00, 0x55
// Page 0 [12] = [21] = ??
// Page 0 [13] = RX_Voltage*10 in V
// Normal telem page 0 = 0x55, 0x32, 0x38, 0x55, 0x64, 0x32, 0xD0, 0x07, 0x00, 0x55
// Page 0 [12] = [21] = [15]
// Page 0 [13] = RX_Voltage Cur*10 in V
// Page 0 [14] = Temperature-20 in °C
// Page 0 [15] = RX_RSSI
// Page 0 [16] = RX_LQI ??
// Page 0 [17] = RX_STR ??
// Page 0 [18,19] = [19]*256+[18]=max lost packet time in ms, max value seems 2s=0x7D0
// Page 0 [15] = RX_RSSI CC2500 formated (a<128:a/2-71dBm, a>=128:(a-256)/2-71dBm)
// Page 0 [16] = RX_LQI in %
// Page 0 [17] = RX_Voltage Min*10 in V
// Page 0 [18,19] = [19]<<8+[18]=max lost packet time in ms, max value seems 2s=0x7D0
// Page 0 [20] = 0x00 ??
//
// Config menu consists of the different telem pages put all together
// Page X [12] = seems like all the telem pages with the same value are going together to make the full config menu text. Seen so far 'a', 'b', 'c', 'd'
// Page X [13..21] = 9 ascii chars to be displayed, char is highlighted when ascii|0x80
@@ -334,22 +408,73 @@ uint16_t ReadHOTT()
// Menu commands are sent through TX packets:
// packet[28]= 0xXF=>no key press, 0xXD=>down, 0xXB=>up, 0xX9=>enter, 0xXE=>right, 0xX7=>left with X=0 or D
// packet[29]= 0xX1/0xX9 with X=0 or X counting 0,1,1,2,2,..,9,9
TX_RSSI = packet_in[22];
if(TX_RSSI >=128)
TX_RSSI -= 128;
else
TX_RSSI += 128;
// Reduce telemetry to 14 bytes
packet_in[0]= TX_RSSI;
packet_in[0]= packet_in[HOTT_RX_PACKET_LEN];
packet_in[1]= TX_LQI;
debug("T=");
bool send_telem=true;
if(packet[29]==1)
{ //Text mode
HOTT_sensor_pages = 0;
HOTT_sensor_valid = false;
packet_in[10] = 0x80; // Marking telem Text mode
packet_in[12] = 0;
for(uint8_t i=0; i<HOTT_SENSOR_TYPE;i++)
packet_in[12] |= HOTT_sensor_ok[i]<<i; // Send detected sensors
}
else
{ //Binary sensor
HOTT_sensor_seq++; // Increment RX sequence counter
HOTT_sensor_seq %= 5; // 5 pages in binary mode per sensor
if(state==0 && HOTT_sensor_ok[0]==false && HOTT_sensor_ok[1]==false && HOTT_sensor_ok[2]==false && HOTT_sensor_ok[3]==false && HOTT_sensor_ok[4]==false && HOTT_sensor_ok[5]==false)
HOTT_sensor_seq=0; // No sensors always ask page 0
if(state)
state--;
if( packet_in[11]==1 ) // Page 1
{
if( packet_in[12] == (HOTT_sensor_cur+9)<<4 )
{ //Requested sensor is sending: 0x90/A0/B0/C0/D0/E0
HOTT_sensor_pages = 0; // Sensor first page received
HOTT_sensor_valid = true; // Data from the expected sensor is being received
HOTT_sensor_ok[(packet_in[12]>>4)-9]=true;
}
else
{
HOTT_sensor_valid = false;
HOTT_sensor_pages = 0x1E; // Switch to next sensor
}
}
if(HOTT_sensor_valid && packet_in[11] ) // Valid & page !=0
{
packet_in[10] = HOTT_sensor_cur+9; // Marking telem with sensor ID
HOTT_sensor_pages |= 1<<packet_in[11]; // Page received
}
if(packet_in[11] && !HOTT_sensor_valid)
send_telem=false;
}
debug("T%d=",send_telem);
for(uint8_t i=10;i < HOTT_RX_PACKET_LEN; i++)
{
packet_in[i-8]=packet_in[i];
debug(" %02X",packet_in[i]);
}
debugln("");
telemetry_link=2;
if(send_telem)
telemetry_link=2;
if((HOTT_sensor_pages&0x1E) == 0x1E) // All 4 pages received from the sensor
{ //Next sensor
uint8_t loop=0;
do
{
HOTT_sensor_cur++; // Switch to next sensor
HOTT_sensor_cur %= HOTT_SENSOR_TYPE;
loop++;
}
while(HOTT_sensor_ok[HOTT_sensor_cur]==false && loop<HOTT_SENSOR_TYPE+1 && state==0);
HOTT_sensor_valid=false;
HOTT_sensor_pages=0;
HOTT_sensor_seq=0;
debugln("Sensor:%02X",HOTT_sensor_cur+9);
}
}
pps_counter++;
#endif
@@ -360,10 +485,18 @@ uint16_t ReadHOTT()
if(packet_count>=100)
{
TX_LQI=pps_counter;
if(pps_counter==0)
{ // lost connection with RX, power cycle? research sensors again.
HOTT_sensor_cur=3;
HOTT_sensor_seq=0;
HOTT_sensor_valid=false;
for(uint8_t i=0; i<HOTT_SENSOR_TYPE;i++)
HOTT_sensor_ok[i]=false; // no sensors detected
state=HOTT_SENSOR_SEARCH_PERIOD;
}
pps_counter=packet_count=0;
}
#endif
CC2500_Strobe(CC2500_SFRX); //Flush the RXFIFO
phase=HOTT_DATA1;
return 1000;
}
@@ -375,10 +508,17 @@ uint16_t initHOTT()
num_ch=random(0xfefefefe)%16;
HOTT_init();
HOTT_rf_init();
packet_count=0;
#ifdef HOTT_FW_TELEMETRY
HoTT_SerialRX_val=0;
HoTT_SerialRX=false;
HOTT_sensor_cur=3;
HOTT_sensor_pages=0;
HOTT_sensor_valid=false;
HOTT_sensor_seq=0;
for(uint8_t i=0; i<HOTT_SENSOR_TYPE;i++)
HOTT_sensor_ok[i]=false; // no sensors detected
packet_count=0;
state=HOTT_SENSOR_SEARCH_PERIOD;
#endif
phase = HOTT_START;
return 10000;

View File

@@ -0,0 +1,184 @@
/*
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 JJRC345
#if defined(JJRC345_NRF24L01_INO)
#include "iface_nrf24l01.h"
//#define JJRC345_FORCE_ID
#define JJRC345_PACKET_PERIOD 7450 // Timeout for callback in uSec
#define JJRC345_INITIAL_WAIT 500
#define JJRC345_PACKET_SIZE 16
#define JJRC345_RF_BIND_CHANNEL 5
#define JJRC345_BIND_COUNT 500
#define JJRC345_NUM_CHANNELS 4
enum JJRC345_FLAGS {
// flags going to packet[8]
JJRC345_FLAG_HEADLESS = 0x40,
JJRC345_FLAG_RTH = 0x80,
};
static uint8_t __attribute__((unused)) JJRC345_convert_channel(uint8_t num)
{
uint8_t val=convert_channel_8b(num);
// 7E..60..41..01, 80 center, 81..C1..E0..FE
if(val<0x80)
{
val=0x80-val; // 80..01
if(val>0x7E)
val=0x7E; // 7E..01
}
else if(val>0xFE)
val=0xFE; // 81..FE
return val;
}
static void __attribute__((unused)) JJRC345_send_packet()
{
packet[0] = 0x00;
packet[2] = 0x00;
if (IS_BIND_IN_PROGRESS)
{ //00 05 00 0A 46 4A 41 47 00 00 40 46 A5 4A F1 18
packet[1] = JJRC345_RF_BIND_CHANNEL;
packet[4] = hopping_frequency[0];
packet[5] = hopping_frequency[1];
packet[6] = hopping_frequency[2];
packet[7] = hopping_frequency[3];
packet[12] = 0xa5;
}
else
{ //00 41 00 0A 00 80 80 80 00 00 40 46 00 49 F1 18
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
hopping_frequency_no++;
hopping_frequency_no %= JJRC345_NUM_CHANNELS;
packet[1] = hopping_frequency[hopping_frequency_no]; // next packet will be sent on this channel
packet[4] = convert_channel_8b(THROTTLE); // throttle: 00..FF
packet[5] = JJRC345_convert_channel(RUDDER); // rudder: 70..60..41..01, 80 center, 81..C1..E0..F0
packet[6] = JJRC345_convert_channel(ELEVATOR); // elevator: 70..60..41..01, 80 center, 81..C1..E0..F0
packet[7] = JJRC345_convert_channel(AILERON); // aileron: 70..60..41..01, 80 center, 81..C1..E0..F0
if(CH5_SW) //Flip
{
if(packet[6]>0xF0)
packet[6]=0xFF;
else if(packet[6]<0x80 && packet[6]>0x70)
packet[6]=0x7F;
if(packet[7]>0xF0)
packet[7]=0xFF;
else if(packet[7]<0x80 && packet[7]>0x70)
packet[7]=0x7F;
}
packet[12] = 0x02; // Rate: 00-01-02
}
packet[3] = 0x00; // Checksum upper bits
packet[8] = 0x00 // Rudder trim, 00 when not used, 01..1F when trimmed left, 20..3F
| GET_FLAG(CH6_SW,JJRC345_FLAG_HEADLESS) // Headless mode: 00 normal, 40 headless
| GET_FLAG(CH7_SW,JJRC345_FLAG_RTH); // RTH: 80 active
packet[9] = 0; // Elevator trim, 00 when not used, 20..25 when trimmed up, 0..1F when trimmed down
packet[10] = 0x40; // Aileron trim, 40 when not used, 40..5F when trimmed left, 61..7F when trimmed right
packet[11] = hopping_frequency[0]; // First hopping frequency
// Checksum
uint16_t sum=2;
for (uint8_t i = 0; i < 13; i++)
sum += packet[i];
packet[13]=sum;
packet[3]=((sum>>8)<<2)+2;
// TX ID
packet[14] = rx_tx_addr[2];
packet[15] = rx_tx_addr[3];
// Power on, TX mode
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
XN297_WritePayload(packet, JJRC345_PACKET_SIZE);
NRF24L01_SetPower(); // Set tx_power
}
static void __attribute__((unused)) JJRC345_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
XN297_SetTXAddr((uint8_t*)"\xcc\xcc\xcc\xcc\xcc", 5);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, JJRC345_RF_BIND_CHANNEL); // Bind channel
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1 Mbps
NRF24L01_SetPower();
}
uint16_t JJRC345_callback()
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(JJRC345_PACKET_PERIOD);
#endif
if(IS_BIND_IN_PROGRESS)
{
if (bind_counter)
bind_counter--;
else
BIND_DONE;
}
JJRC345_send_packet();
return JJRC345_PACKET_PERIOD;
}
static void __attribute__((unused)) JJRC345_initialize_txid()
{
calc_fh_channels(JJRC345_NUM_CHANNELS);
#ifdef JJRC345_FORCE_ID
//TX 1
rx_tx_addr[2]=0x1B;
rx_tx_addr[3]=0x12;
hopping_frequency[0] = 0x3f;
hopping_frequency[1] = 0x49;
hopping_frequency[2] = 0x47;
hopping_frequency[3] = 0x47;
//TX 2
rx_tx_addr[2]=0xF1;
rx_tx_addr[3]=0x18;
hopping_frequency[0] = 0x46;
hopping_frequency[1] = 0x4A;
hopping_frequency[2] = 0x41;
hopping_frequency[3] = 0x47;
#endif
}
uint16_t initJJRC345(void)
{
BIND_IN_PROGRESS; // autobind protocol
bind_counter = JJRC345_BIND_COUNT;
JJRC345_initialize_txid();
JJRC345_init();
return JJRC345_INITIAL_WAIT;
}
#endif

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
@@ -11,8 +11,8 @@
11,SLT,SLT_V1,SLT_V2,Q100,Q200,MR100
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
14,Bayang,Bayang,H8S3D,X16_AH,IRDRONE,DHD_D4,QX100
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,14 +52,21 @@
52,ZSX,280
53,Flyzone,FZ-410
54,Scanner
55,Frsky_RX
55,Frsky_RX,RX,CloneTX
56,AFHDS2A_RX
57,HoTT
57,HoTT,Sync,No_Sync
58,FX816,P38
59,Bayang_RX
60,Pelikan
60,Pelikan,Pro,Lite
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
70,DSM_RX
71,JJRC345
72,Q90C

View File

@@ -21,6 +21,7 @@ const char STR_FRSKYD[] ="FrSky D";
const char STR_HISKY[] ="Hisky";
const char STR_V2X2[] ="V2x2";
const char STR_DSM[] ="DSM";
const char STR_DSM_RX[] ="DSM_RX";
const char STR_DEVO[] ="Devo";
const char STR_YD717[] ="YD717";
const char STR_KN[] ="KN";
@@ -29,6 +30,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";
@@ -38,18 +40,21 @@ const char STR_SHENQI[] ="Shenqi";
const char STR_FY326[] ="FY326";
const char STR_SFHSS[] ="SFHSS";
const char STR_J6PRO[] ="J6 Pro";
const char STR_JJRC345[] ="JJRC345";
const char STR_FQ777[] ="FQ777";
const char STR_ASSAN[] ="Assan";
const char STR_FRSKYV[] ="FrSky V";
const char STR_HONTAI[] ="Hontai";
const char STR_AFHDS2A[] ="FSky 2A";
const char STR_AFHDS2A[] ="FlSky2A";
const char STR_Q2X2[] ="Q2x2";
const char STR_WK2x01[] ="Walkera";
const char STR_Q303[] ="Q303";
const char STR_Q90C[] ="Q90C";
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 +66,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 +84,14 @@ 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_TEST[] ="Test";
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";
@@ -93,7 +102,7 @@ const char STR_SUBTYPE_SYMAX[] = "\x03""Std""X5C";
const char STR_SUBTYPE_SLT[] = "\x06""V1_6ch""V2_8ch""Q100\0 ""Q200\0 ""MR100\0";
const char STR_SUBTYPE_CX10[] = "\x07""Green\0 ""Blue\0 ""DM007\0 ""-\0 ""JC3015a""JC3015b""MK33041";
const char STR_SUBTYPE_CG023[] = "\x05""Std\0 ""YD829";
const char STR_SUBTYPE_BAYANG[] = "\x07""Std\0 ""H8S3D\0 ""X16 AH\0""IRDrone""DHD D4";
const char STR_SUBTYPE_BAYANG[] = "\x07""Std\0 ""H8S3D\0 ""X16 AH\0""IRDrone""DHD D4\0""QX100\0 ";
const char STR_SUBTYPE_MT99[] = "\x06""MT99\0 ""H7\0 ""YZ\0 ""LS\0 ""FY805";
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";
@@ -116,11 +125,18 @@ const char STR_SUBTYPE_ZSX[] = "\x07""280JJRC";
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_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";
const char STR_SUBTYPE_HOTT[] = "\x07""Sync\0 ""No_Sync";
const char STR_SUBTYPE_PELIKAN[] = "\x04""Pro\0""Lite";
enum
{
@@ -139,199 +155,223 @@ 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 },
#endif
#if defined(FRSKYX2_CC2500_INO)
{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)
{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)
{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)
{PROTO_FRSKY_R9, STR_FRSKYR9, 4, STR_SUBTYPE_FRSKYR9, OPTION_NONE },
#endif
{0x00, nullptr, 0, nullptr, 0 }
#if defined(ASSAN_NRF24L01_INO)
{PROTO_ASSAN, STR_ASSAN, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(BAYANG_NRF24L01_INO)
{PROTO_BAYANG, STR_BAYANG, 6, 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(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(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(DSM_RX_CYRF6936_INO)
{PROTO_DSM_RX, STR_DSM_RX, 0, NO_SUBTYPE, OPTION_NONE },
#endif
#if defined(E01X_NRF24L01_INO)
{PROTO_E01X, STR_E01X, 3, STR_SUBTYPE_E01X, OPTION_OPTION },
#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
#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, 2, STR_SUBTYPE_HOTT, 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(JJRC345_NRF24L01_INO)
{PROTO_JJRC345, STR_JJRC345, 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 , 2, STR_SUBTYPE_PELIKAN, 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, 1, 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(Q90C_NRF24L01_INO)
{PROTO_Q90C, STR_Q90C, 0, NO_SUBTYPE, OPTION_RFTUNE },
#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(WK2x01_CYRF6936_INO)
{PROTO_WK2x01, STR_WK2x01, 6, STR_SUBTYPE_WK2x01, OPTION_NONE },
#endif
#if defined(WFLY_CYRF6936_INO)
{PROTO_WFLY, STR_WFLY, 1, STR_SUBTYPE_WFLY, 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
#if defined(TEST_CC2500_INO)
{PROTO_TEST, STR_TEST, 0, NO_SUBTYPE, OPTION_RFTUNE },
#endif
{0x00, nullptr, 0, nullptr, 0 }
};
#endif

View File

@@ -18,8 +18,8 @@
//******************
#define VERSION_MAJOR 1
#define VERSION_MINOR 3
#define VERSION_REVISION 0
#define VERSION_PATCH_LEVEL 76
#define VERSION_REVISION 1
#define VERSION_PATCH_LEVEL 9
//******************
// Protocols
@@ -92,6 +92,15 @@ 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
PROTO_DSM_RX = 70, // =>CYRF6936
PROTO_JJRC345 = 71, // =>NRF24L01
PROTO_Q90C = 72, // =>NRF24L01 or CC2500
PROTO_TEST = 127, // =>CC2500
};
enum Flysky
@@ -188,6 +197,7 @@ enum BAYANG
X16_AH = 2,
IRDRONE = 3,
DHD_D4 = 4,
QX100 = 5,
};
enum MT99XX
{
@@ -207,19 +217,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,
};
enum FRSKYX2
{
FRSKYX2_CH_16 = 0,
FRSKYX2_CH_8 = 1,
FRSKYX2_EU_16 = 2,
FRSKYX2_EU_8 = 3,
XCLONE = 4,
};
enum HONTAI
{
@@ -340,6 +349,30 @@ enum ESKY
ESKY_ET4 = 1,
};
enum FRSKY_RX
{
FRSKY_RX = 0,
FRSKY_CLONE = 1,
};
enum FRSKYL
{
LR12 = 0,
LR12_6CH = 1,
};
enum HOTT
{
HOTT_SYNC = 0,
HOTT_NO_SYNC= 1,
};
enum PELIKAN
{
PELIKAN_PRO = 0,
PELIKAN_LITE= 1,
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
@@ -382,8 +415,8 @@ 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 )
#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_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 || protocol==PROTO_FRSKY_R9)
#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 || protocol==PROTO_DSM_RX)
//***************
//*** Flags ***
@@ -473,6 +506,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
@@ -597,6 +635,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
@@ -650,7 +689,11 @@ 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 DSM_RX_EEPROM_OFFSET 877 // (4) TX ID + format, 5 bytes, end is 882
//#define CONFIG_EEPROM_OFFSET 882 // Current configuration of the multimodule
//****************************************
//*** MULTI protocol serial definition ***
@@ -734,6 +777,13 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
XN297DUMP 63
FRSKYX2 64
FRSKY_R9 65
PROPEL 66
FRSKYL 67
SKYARTEC 68
ESKY150V2 69
DSM_RX 70
JJRC345 71
Q90C 72
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
@@ -806,11 +856,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
@@ -892,6 +952,18 @@ 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
sub_protocol==HOTT
HOTT_SYNC 0
HOTT_NO_SYNC 1
sub_protocol==PELIKAN
PELIKAN_PRO 0
PELIKAN_LITE 1
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
@@ -914,6 +986,10 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Disable_Telemetry => 0x02 0=enable, 1=disable
Disable_CH_Mapping => 0x01 0=enable, 1=disable
Stream[27.. 35] = between 0 and 9 bytes for additional protocol data
Protocol specific use:
FrSkyX and FrSkyX2: Stream[27] during bind Telem on=0x00,off=0x01 | CH1-8=0x00,CH9-16=0x02
FrSkyX and FrSkyX2: Stream[27..34] during normal operation unstuffed SPort data to be sent
HoTT: Stream[27] 1 byte for telemetry type
*/
/*
Multimodule Status
@@ -996,7 +1072,8 @@ 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
Type 0x02 Frksy S.port telemetry

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];
@@ -119,7 +123,7 @@ uint8_t num_ch;
#ifdef CC2500_INSTALLED
#ifdef SCANNER_CC2500_INO
uint8_t calData[255];
#elif defined(HOTT_CC2500_INO)
#elif defined(HOTT_CC2500_INO) || defined(ESKY150V2_CC2500_INO)
uint8_t calData[75];
#else
uint8_t calData[50];
@@ -227,7 +231,7 @@ uint8_t packet_in[TELEMETRY_BUFFER_SIZE];//telemetry receiving packets
#endif
//RX protocols
#if defined(AFHDS2A_RX_A7105_INO) || defined(FRSKY_RX_CC2500_INO) || defined(BAYANG_RX_NRF24L01_INO)
#if defined(AFHDS2A_RX_A7105_INO) || defined(FRSKY_RX_CC2500_INO) || defined(BAYANG_RX_NRF24L01_INO) || defined(DSM_RX_CYRF6936_INO)
bool rx_data_started;
bool rx_data_received;
bool rx_disable_lna;
@@ -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
@@ -514,11 +523,6 @@ void setup()
option = FORCE_FRSKYX_TUNING; // Use config-defined tuning value for FrSkyX
else
#endif
#if defined(FORCE_FRSKYX2_TUNING) && defined(FRSKYX2_CC2500_INO)
if(protocol==PROTO_FRSKYX2)
option = FORCE_FRSKYX2_TUNING; // Use config-defined tuning value for FrSkyX2
else
#endif
#if defined(FORCE_SFHSS_TUNING) && defined(SFHSS_CC2500_INO)
if (protocol==PROTO_SFHSS)
option = FORCE_SFHSS_TUNING; // Use config-defined tuning value for SFHSS
@@ -529,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
@@ -742,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) || (protocol==PROTO_DEVO) || (protocol==PROTO_DSM_RX))
#endif
if(IS_DISABLE_TELEM_off)
TelemetryUpdate();
@@ -758,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_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
@@ -1117,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
@@ -1127,20 +1144,13 @@ static void protocol_init()
#endif
#if defined(FRSKYX_CC2500_INO)
case PROTO_FRSKYX:
case PROTO_FRSKYX2:
PE1_off; //antenna RF2
PE2_on;
next_callback = initFrSkyX();
remote_callback = ReadFrSkyX;
break;
#endif
#if defined(FRSKYX2_CC2500_INO)
case PROTO_FRSKYX2:
PE1_off; //antenna RF2
PE2_on;
next_callback = initFrSkyX2();
remote_callback = ReadFrSkyX2;
break;
#endif
#if defined(SFHSS_CC2500_INO)
case PROTO_SFHSS:
PE1_off; //antenna RF2
@@ -1157,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
@@ -1197,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)
@@ -1206,6 +1232,13 @@ static void protocol_init()
remote_callback = ReadDsm;
break;
#endif
#if defined(DSM_RX_CYRF6936_INO)
case PROTO_DSM_RX:
PE2_on; //antenna RF4
next_callback = initDSM_Rx();
remote_callback = DSM_Rx_callback;
break;
#endif
#if defined(WFLY_CYRF6936_INO)
case PROTO_WFLY:
PE2_on; //antenna RF4
@@ -1497,12 +1530,36 @@ 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();
remote_callback = XN297Dump_callback;
break;
#endif
#if defined(JJRC345_NRF24L01_INO)
case PROTO_JJRC345:
next_callback=initJJRC345();
remote_callback = JJRC345_callback;
break;
#endif
#if defined(Q90C_NRF24L01_INO)
case PROTO_Q90C:
next_callback=initQ90C();
remote_callback = Q90C_callback;
break;
#endif
#if defined(TEST_CC2500_INO)
case PROTO_TEST:
next_callback=initTEST();
remote_callback = TEST_callback;
break;
#endif
#endif
#ifdef SX1276_INSTALLED
#if defined(FRSKYR9_SX1276_INO)
@@ -1610,10 +1667,15 @@ void update_serial_data()
//Forced frequency tuning values for CC2500 protocols
#if defined(FORCE_FRSKYD_TUNING) && defined(FRSKYD_CC2500_INO)
if(protocol==PROTO_FRSKYD)
if(protocol==PROTO_FRSKYD)
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
@@ -1624,11 +1686,6 @@ void update_serial_data()
option=FORCE_FRSKYX_TUNING; // Use config-defined tuning value for FrSkyX
else
#endif
#if defined(FORCE_FRSKYX2_TUNING) && defined(FRSKYX2_CC2500_INO)
if(protocol==PROTO_FRSKYX2)
option=FORCE_FRSKYX2_TUNING; // Use config-defined tuning value for FrSkyX2
else
#endif
#if defined(FORCE_SFHSS_TUNING) && defined(SFHSS_CC2500_INO)
if (protocol==PROTO_SFHSS)
option=FORCE_SFHSS_TUNING; // Use config-defined tuning value for SFHSS
@@ -1639,6 +1696,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
@@ -1731,8 +1793,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_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
@@ -1791,7 +1853,7 @@ void update_serial_data()
#endif
if(rx_len>27)
{ // Data available for the current protocol
#if defined FRSKYX_CC2500_INO || defined FRSKYX2_CC2500_INO
#if defined FRSKYX_CC2500_INO
if((protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2) && rx_len==28)
{//Protocol waiting for 1 byte during bind
binding_idx=rx_ok_buff[27];
@@ -1803,33 +1865,41 @@ void update_serial_data()
#define BYTE_STUFF 0x7D
#define STUFF_MASK 0x20
//debug("SPort_in: ");
SportData[SportTail]=0x7E;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
SportData[SportTail]=rx_ok_buff[27]&0x1F;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
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)
{
if(rx_ok_buff[i]==BYTE_STUFF)
{//stuff
SportData[SportTail]=BYTE_STUFF;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
SportData[SportTail]=rx_ok_buff[i]^STUFF_MASK;
}
else
SportData[SportTail]=rx_ok_buff[i];
//debug("%02X ",SportData[SportTail]);
SportData[SportTail]=0x7E;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
}
uint8_t used = SportTail;
if ( SportHead > SportTail )
used += MAX_SPORT_BUFFER - SportHead ;
else
used -= SportHead ;
if ( used >= MAX_SPORT_BUFFER-(MAX_SPORT_BUFFER>>2) )
{
DATA_BUFFER_LOW_on;
SEND_MULTI_STATUS_on; //Send Multi Status ASAP to inform the TX
debugln("Low buf=%d,h=%d,t=%d",used,SportHead,SportTail);
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) || (rx_ok_buff[i]==0x7E) )
{//stuff
SportData[SportTail]=BYTE_STUFF;
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
SportData[SportTail]=rx_ok_buff[i]^STUFF_MASK;
}
else
SportData[SportTail]=rx_ok_buff[i];
//debug("%02X ",SportData[SportTail]);
SportTail = (SportTail+1) & (MAX_SPORT_BUFFER-1);
}
uint8_t used = SportTail;
if ( SportHead > SportTail )
used += MAX_SPORT_BUFFER - SportHead ;
else
used -= SportHead ;
if ( used >= MAX_SPORT_BUFFER-(MAX_SPORT_BUFFER>>2) )
{
DATA_BUFFER_LOW_on;
SEND_MULTI_STATUS_on; //Send Multi Status ASAP to inform the TX
debugln("Low buf=%d,h=%d,t=%d",used,SportHead,SportTail);
}
}
}
#endif //SPORT_SEND
@@ -2084,7 +2154,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
@@ -2150,6 +2220,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

@@ -192,13 +192,6 @@ static void __attribute__((unused)) XN297L_WriteEnhancedPayload(uint8_t* msg, ui
static uint8_t pid=0;
// address
if (xn297_addr_len < 4)
{
// If address length (which is defined by receive address length)
// is less than 4 the TX address can't fit the preamble, so the last
// byte goes here
buf[last++] = 0x55;
}
for (uint8_t i = 0; i < xn297_addr_len; ++i)
{
buf[last] = xn297_tx_addr[xn297_addr_len-i-1];
@@ -235,9 +228,8 @@ static void __attribute__((unused)) XN297L_WriteEnhancedPayload(uint8_t* msg, ui
// crc
//if (xn297_crc)
{
uint8_t offset = xn297_addr_len < 4 ? 1 : 0;
uint16_t crc = 0xb5d2;
for (uint8_t i = offset; i < last; ++i)
for (uint8_t i = 0; i < last; ++i)
crc = crc16_update(crc, buf[i], 8);
crc = crc16_update(crc, buf[last] & 0xc0, 2);
if (xn297_scramble_enabled)
@@ -383,7 +375,11 @@ static void __attribute__((unused)) NRF250K_WritePayload(uint8_t* msg, uint8_t l
}
//CC2500
#ifdef CC2500_INSTALLED
uint8_t buf[35];
#if defined(ESKY150V2_CC2500_INO)
uint8_t buf[158];
#else
uint8_t buf[35];
#endif
uint8_t last = 0;
uint8_t i;
@@ -417,10 +413,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
CC2500_Strobe(CC2500_STX);
// 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

@@ -19,11 +19,14 @@
#include "iface_a7105.h"
//#define PELIKAN_FORCE_ID
//#define PELIKAN_LITE_FORCE_ID
#define PELIKAN_LITE_FORCE_HOP
#define PELIKAN_BIND_COUNT 400
#define PELIKAN_BIND_RF 0x3C
#define PELIKAN_NUM_RF_CHAN 0x1D
#define PELIKAN_PAQUET_PERIOD 7980
#define PELIKAN_PACKET_PERIOD 7980
#define PELIKAN_LITE_PACKET_PERIOD 18000
static void __attribute__((unused)) pelikan_build_packet()
{
@@ -36,7 +39,10 @@ static void __attribute__((unused)) pelikan_build_packet()
packet[3] = rx_tx_addr[1];
packet[4] = rx_tx_addr[2];
packet[5] = rx_tx_addr[3];
packet[6] = 0x05; //??
if(sub_protocol==PELIKAN_PRO)
packet[6] = 0x05; //sub version??
else //PELIKAN_LITE
packet[6] = 0x03; //sub version??
packet[7] = 0x00; //??
packet[8] = 0x55; //??
packet_length = 10;
@@ -72,7 +78,7 @@ static void __attribute__((unused)) pelikan_build_packet()
packet[9]=upper?0xAA:0x00;
upper=!upper;
//Hopping counters
if(++packet_count>4)
if(sub_protocol==PELIKAN_LITE || ++packet_count>4)
{
packet_count=0;
if(++hopping_frequency_no>=PELIKAN_NUM_RF_CHAN)
@@ -106,24 +112,41 @@ static void __attribute__((unused)) pelikan_build_packet()
uint16_t ReadPelikan()
{
#ifndef FORCE_PELIKAN_TUNING
A7105_AdjustLOBaseFreq(1);
#endif
if(IS_BIND_IN_PROGRESS)
if(phase==0)
{
bind_counter--;
if (bind_counter==0)
#ifndef FORCE_PELIKAN_TUNING
A7105_AdjustLOBaseFreq(1);
#endif
if(IS_BIND_IN_PROGRESS)
{
BIND_DONE;
A7105_Strobe(A7105_STANDBY);
A7105_WriteReg(A7105_03_FIFOI,0x28);
bind_counter--;
if (bind_counter==0)
{
BIND_DONE;
A7105_Strobe(A7105_STANDBY);
if(sub_protocol==PELIKAN_PRO)
A7105_WriteReg(A7105_03_FIFOI,0x28);
else//PELIKAN_LITE
A7105_WriteID((rx_tx_addr[0]<<24)|(rx_tx_addr[1]<<16)|(rx_tx_addr[2]<<8)|(rx_tx_addr[3]));
}
}
#ifdef MULTI_SYNC
telemetry_set_input_sync(sub_protocol==PELIKAN_PRO?PELIKAN_PACKET_PERIOD:PELIKAN_LITE_PACKET_PERIOD);
#endif
pelikan_build_packet();
if(sub_protocol==PELIKAN_PRO || IS_BIND_IN_PROGRESS)
return PELIKAN_PACKET_PERIOD;
//PELIKAN_LITE
phase++;
return 942;
}
#ifdef MULTI_SYNC
telemetry_set_input_sync(PELIKAN_PAQUET_PERIOD);
#endif
pelikan_build_packet();
return PELIKAN_PAQUET_PERIOD;
//PELIKAN_LITE
A7105_Strobe(A7105_TX);
phase++;
if(phase==1)
return 942;
phase=0;
return PELIKAN_LITE_PACKET_PERIOD-942-942;
}
static uint8_t pelikan_firstCh(uint8_t u, uint8_t l)
@@ -213,27 +236,57 @@ const uint8_t PROGMEM pelikan_hopp[][PELIKAN_NUM_RF_CHAN] = {
};
#endif
#ifdef PELIKAN_LITE_FORCE_HOP
const uint8_t PROGMEM pelikan_lite_hopp[][PELIKAN_NUM_RF_CHAN] = {
{ 0x46,0x2A,0x3E,0x5A,0x5C,0x24,0x4E,0x32,0x54,0x26,0x2C,0x34,0x56,0x1E,0x3A,0x3C,0x50,0x4A,0x2E,0x42,0x20,0x52,0x28,0x22,0x44,0x58,0x36,0x38,0x4C }
};
#endif
uint16_t initPelikan()
{
A7105_Init();
if(IS_BIND_IN_PROGRESS)
if(IS_BIND_IN_PROGRESS || sub_protocol==PELIKAN_LITE)
A7105_WriteReg(A7105_03_FIFOI,0x10);
pelikan_init_hop();
//ID from dump
#ifdef PELIKAN_FORCE_ID
rx_tx_addr[0]=0x0D; // hopping freq
rx_tx_addr[1]=0xF4; // hopping freq
rx_tx_addr[2]=0x50; // ID
rx_tx_addr[3]=0x18; // ID
// Fill frequency table
for(uint8_t i=0;i<PELIKAN_NUM_RF_CHAN;i++)
hopping_frequency[i]=pgm_read_byte_near(&pelikan_hopp[0][i]);
#else
pelikan_init_hop();
#if defined(PELIKAN_FORCE_ID)
if(sub_protocol==PELIKAN_PRO)
{
rx_tx_addr[0]=0x0D; // hopping freq
rx_tx_addr[1]=0xF4; // hopping freq
rx_tx_addr[2]=0x50; // ID
rx_tx_addr[3]=0x18; // ID
// Fill frequency table
for(uint8_t i=0;i<PELIKAN_NUM_RF_CHAN;i++)
hopping_frequency[i]=pgm_read_byte_near(&pelikan_hopp[0][i]);
}
#endif
#if defined(PELIKAN_LITE_FORCE_ID) || defined(PELIKAN_LITE_FORCE_HOP)
if(sub_protocol==PELIKAN_LITE)
{
#if defined(PELIKAN_LITE_FORCE_ID)
// ID
rx_tx_addr[2]=0x60;
rx_tx_addr[3]=0x18;
#endif
#if defined(PELIKAN_LITE_FORCE_HOP)
// Hop frequency table
rx_tx_addr[0]=0x04; // hopping freq
rx_tx_addr[1]=0x63; // hopping freq
for(uint8_t i=0;i<PELIKAN_NUM_RF_CHAN;i++)
hopping_frequency[i]=pgm_read_byte_near(&pelikan_lite_hopp[0][i]);
#endif
}
#endif
if(sub_protocol==PELIKAN_LITE && IS_BIND_DONE)
A7105_WriteID((rx_tx_addr[0]<<24)|(rx_tx_addr[1]<<16)|(rx_tx_addr[2]<<8)|(rx_tx_addr[3]));
hopping_frequency_no=PELIKAN_NUM_RF_CHAN;
packet_count=5;
phase=0;
return 2400;
}
#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

@@ -0,0 +1,146 @@
/*
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 Q90C quad.
#if defined(Q90C_NRF24L01_INO)
#include "iface_nrf250k.h"
#define FORCE_Q90C_ORIGINAL_ID
#define Q90C_BIND_COUNT 250
#define Q90C_PACKET_PERIOD 7336
#define Q90C_INITIAL_WAIT 500
#define Q90C_PACKET_SIZE 12
#define Q90C_RF_BIND_CHANNEL 0x33
#define Q90C_RF_NUM_CHANNELS 3
#define Q90C_ADDRESS_LENGTH 5
int16_t Q90C_channel(uint8_t num, int16_t in_min,int16_t in_max, int16_t out_min,int16_t out_max)
{
int32_t val=Channel_data[num];
if(val<in_min) val=in_min;
else if(val>in_max) val=in_max;
val=(val-in_min)*(out_max-out_min)/(in_max-in_min)+out_min;
return (uint16_t)val;
}
static void __attribute__((unused)) Q90C_send_packet()
{
if(IS_BIND_IN_PROGRESS)
{
memcpy(packet, rx_tx_addr, 4);
memcpy(&packet[4], hopping_frequency, 3);
packet[7] = 0x1e;
packet[8] = 0;
packet[9] = 0;
packet[10] = rx_tx_addr[4];
}
else
{
XN297L_Hopping(hopping_frequency_no++); // RF Freq
hopping_frequency_no %= Q90C_RF_NUM_CHANNELS;
packet[0]= convert_channel_8b(THROTTLE); // 0..255
// A,E,R have weird scaling, 0x00-0xff range (unsigned) but center isn't 7f or 80
// rudder ff-7a-00
if (Channel_data[RUDDER] <= CHANNEL_MID)
packet[1] = Q90C_channel(RUDDER, CHANNEL_MIN_100, CHANNEL_MID, 0xff, 0x7a );
else
packet[1] = Q90C_channel(RUDDER, CHANNEL_MID, CHANNEL_MAX_100, 0x7a, 0x00 );
// elevator 00-88-ff
if (Channel_data[ELEVATOR] <= CHANNEL_MID)
packet[2] = Q90C_channel(ELEVATOR, CHANNEL_MIN_100, CHANNEL_MID, 0x00, 0x88);
else
packet[2] = Q90C_channel(ELEVATOR, CHANNEL_MID, CHANNEL_MAX_100, 0x88, 0xff);
// aileron ff-88-00
if (Channel_data[AILERON] <= CHANNEL_MID)
packet[3] = Q90C_channel(AILERON, CHANNEL_MIN_100, CHANNEL_MID, 0xff, 0x88);
else
packet[3] = Q90C_channel(AILERON, CHANNEL_MID, CHANNEL_MAX_100, 0x88, 0x00);
// required to "arm" (low throttle + aileron to the right)
if (packet[0] < 5 && packet[3] < 25) {
packet[1] = 0x7a;
packet[2] = 0x88;
}
packet[4] = 0x1e; // T trim 00-1e-3c
packet[5] = 0x1e; // R trim 3c-1e-00
packet[6] = 0x1e; // E trim 00-1e-3c
packet[7] = 0x1e; // A trim 00-1e-3c
packet[8] = 0x00; // flags: 3 position flight mode (Angle - Horizon - Acro), VTX Toggle HIGH = next vTX frequency
packet[9] = 0x00;
packet[10] = packet_count++;
}
uint8_t sum=0;
// checksum
for (uint8_t i = 0; i < Q90C_PACKET_SIZE - 1; i++)
{
sum += packet[i];
debug("%02X ", packet[i]);
}
packet[11] = sum ^ (IS_BIND_IN_PROGRESS? 0xc6 : 0xa4);
debugln("%02X",packet[11]);
XN297L_SetFreqOffset(); // Set frequency offset
XN297L_SetPower(); // Set tx_power
XN297L_WriteEnhancedPayload(packet, Q90C_PACKET_SIZE, 0);
}
static void __attribute__((unused)) Q90C_initialize_txid()
{
calc_fh_channels(Q90C_RF_NUM_CHANNELS);
#ifdef FORCE_Q90C_ORIGINAL_ID
memcpy(rx_tx_addr, (uint8_t*)"\x24\x03\x01\x82\x4B", Q90C_ADDRESS_LENGTH);
memcpy(hopping_frequency, (uint8_t*)"\x18\x26\x37", Q90C_RF_NUM_CHANNELS);
#endif
}
static void __attribute__((unused)) Q90C_init()
{
XN297L_Init();
if(IS_BIND_IN_PROGRESS)
XN297L_SetTXAddr((uint8_t*)"\x4F\x43\x54\x81\x81", Q90C_ADDRESS_LENGTH);
else
XN297L_SetTXAddr(rx_tx_addr, Q90C_ADDRESS_LENGTH);
XN297L_HoppingCalib(Q90C_RF_NUM_CHANNELS); // Calibrate all channels
XN297L_RFChannel(Q90C_RF_BIND_CHANNEL); // Set bind channel
}
uint16_t Q90C_callback()
{
#ifdef MULTI_SYNC
telemetry_set_input_sync(Q90C_PACKET_PERIOD);
#endif
if(IS_BIND_IN_PROGRESS)
if(--bind_counter==0)
{
BIND_DONE;
XN297L_SetTXAddr(rx_tx_addr, Q90C_ADDRESS_LENGTH);
}
Q90C_send_packet();
return Q90C_PACKET_PERIOD;
}
uint16_t initQ90C()
{
Q90C_initialize_txid();
Q90C_init();
hopping_frequency_no = 0;
packet_count = 0;
bind_counter=Q90C_BIND_COUNT;
return Q90C_INITIAL_WAIT;
}
#endif

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)
REDPINE_init(0);
if(bind_counter == REDPINE_BIND/2)
REDPINE_init(1);
if (state == REDPINE_BIND) {
REDPINE_init(0);
}
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},
@@ -181,7 +176,7 @@ static const uint8_t REDPINE_init_data[][3] = {
{CC2500_2C_TEST2, 0x88, 0x88},
{CC2500_2D_TEST1, 0x31, 0x31},
{CC2500_2E_TEST0, 0x0B, 0x0B},
{CC2500_3E_PATABLE, 0xff, 0xff}
{CC2500_3E_PATABLE, 0xff, 0xff}
};
static void REDPINE_init(uint8_t format)
@@ -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))
break;
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

@@ -0,0 +1,63 @@
/*
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(TEST_CC2500_INO)
#include "iface_nrf250k.h"
#define TEST_INITIAL_WAIT 500
#define TEST_PACKET_PERIOD 10000
#define TEST_PAYLOAD_SIZE 10
#define TEST_RF_NUM_CHANNELS 3
uint16_t TEST_callback()
{
option=1;
if(phase)
XN297L_WritePayload(packet, TEST_PAYLOAD_SIZE);
else
{
if(Channel_data[CH5]<CHANNEL_MIN_COMMAND)
hopping_frequency_no=0;
else if(Channel_data[CH5]>CHANNEL_MAX_COMMAND)
hopping_frequency_no=2;
else
hopping_frequency_no=1;
XN297L_Hopping(hopping_frequency_no);
CC2500_WriteReg(CC2500_3E_PATABLE,convert_channel_8b(CH6));
debugln("CH:%d, PWR:%d",hopping_frequency_no,convert_channel_8b(CH6));
}
phase ^= 1;
return TEST_PACKET_PERIOD>>1;
}
uint16_t initTEST()
{
option=1;
hopping_frequency[0]=0;
hopping_frequency[1]=40;
hopping_frequency[2]=80;
XN297L_Init();
XN297L_HoppingCalib(TEST_RF_NUM_CHANNELS); // Calibrate all channels
XN297L_SetTXAddr((uint8_t*)"RADIO", 5);
hopping_frequency_no = 0;
phase=0;
for(uint8_t i=0; i<TEST_PAYLOAD_SIZE; i++)
packet[i]= i;
return TEST_INITIAL_WAIT;
}
#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, 5);
#endif
#else
multi_send_header(MULTI_TELEMETRY_STATUS, 6);
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)
{
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
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
}
// Channels function
//TODO
#endif
}
#endif
@@ -253,7 +267,7 @@ static void multi_send_status()
}
#endif
#if defined (FRSKY_RX_TELEMETRY) || defined (AFHDS2A_RX_TELEMETRY) || defined (BAYANG_RX_TELEMETRY)
#if defined (FRSKY_RX_TELEMETRY) || defined (AFHDS2A_RX_TELEMETRY) || defined (BAYANG_RX_TELEMETRY) || defined (DSM_RX_CYRF6936_INO)
void receiver_channels_frame()
{
uint16_t len = packet_in[3] * 11; // 11 bit per channel
@@ -379,7 +393,7 @@ void frsky_check_telemetry(uint8_t *packet_in,uint8_t len)
#endif
#if defined SPORT_TELEMETRY && defined FRSKYX_CC2500_INO
if (protocol==PROTO_FRSKYX)
if (protocol==PROTO_FRSKYX||protocol==PROTO_FRSKYX2)
{
/*Telemetry frames(RF) SPORT info
15 bytes payload
@@ -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_HUBSAN, PROTO_AFHDS2A, PROTO_BAYANG, PROTO_NCC1701, PROTO_CABELL, PROTO_HITEC, PROTO_BUGS, PROTO_BUGSMINI, PROTO_FRSKYX, PROTO_FRSKYX2, PROTO_PROPEL, PROTO_DEVO
frame[1] = v_lipo1;
frame[2] = v_lipo2;
frame[3] = RX_RSSI;
@@ -856,7 +870,7 @@ void TelemetryUpdate()
#endif
#endif
#if defined SPORT_TELEMETRY
if (protocol==PROTO_FRSKYX && telemetry_link
if ((protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYX2) && telemetry_link
#ifdef TELEMETRY_FRSKYX_TO_FRSKYD
&& mode_select==MODE_SERIAL
#endif
@@ -925,8 +939,8 @@ void TelemetryUpdate()
}
#endif
#if defined (FRSKY_RX_TELEMETRY) || defined(AFHDS2A_RX_TELEMETRY) || defined (BAYANG_RX_TELEMETRY)
if ((telemetry_link & 1) && (protocol == PROTO_FRSKY_RX || protocol == PROTO_AFHDS2A_RX || protocol == PROTO_BAYANG_RX))
#if defined (FRSKY_RX_TELEMETRY) || defined(AFHDS2A_RX_TELEMETRY) || defined (BAYANG_RX_TELEMETRY) || defined (DSM_RX_CYRF6936_INO)
if ((telemetry_link & 1) && (protocol == PROTO_FRSKY_RX || protocol == PROTO_AFHDS2A_RX || protocol == PROTO_BAYANG_RX || protocol == PROTO_DSM_RX) )
{
receiver_channels_frame();
telemetry_link &= ~1;
@@ -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."
@@ -89,16 +94,16 @@
#error "The FrSkyX forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_FRSKYX2_TUNING
#if ( FORCE_FRSKYX2_TUNING < -127 ) || ( FORCE_FRSKYX2_TUNING > 127 )
#error "The FrSkyX2 forced frequency tuning value is outside of the range -127..127."
#endif
#endif
#ifdef FORCE_HITEC_TUNING
#if ( FORCE_HITEC_TUNING < -127 ) || ( FORCE_HITEC_TUNING > 127 )
#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."
@@ -109,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
@@ -188,74 +193,81 @@
//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
#undef DEVO_CYRF6936_INO
#undef DSM_CYRF6936_INO
#undef DSM_RX_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 FRSKYX2_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 JJRC345_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 Q90C_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
@@ -264,6 +276,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
@@ -291,6 +309,8 @@
#undef HOTT_FW_TELEMETRY
#undef BAYANG_RX_TELEMETRY
#undef BAYANG_RX_NRF24L01_INO
#undef DEVO_HUB_TELEMETRY
#undef DSM_RX_CYRF6936_INO
#else
#if defined(MULTI_TELEMETRY) && defined(MULTI_STATUS)
#error You should choose either MULTI_TELEMETRY or MULTI_STATUS but not both.
@@ -314,6 +334,9 @@
#if not defined(BAYANG_NRF24L01_INO)
#undef BAYANG_HUB_TELEMETRY
#endif
#if not defined(DEVO_CYRF6936_INO)
#undef DEVO_HUB_TELEMETRY
#endif
#if not defined(NCC1701_NRF24L01_INO)
#undef NCC1701_HUB_TELEMETRY
#endif
@@ -337,7 +360,7 @@
#if not defined(FRSKYD_CC2500_INO)
#undef HUB_TELEMETRY
#endif
#if not defined(FRSKYX_CC2500_INO) and not defined(FRSKYX2_CC2500_INO)
#if not defined(FRSKYX_CC2500_INO)
#undef SPORT_TELEMETRY
#undef SPORT_SEND
#endif
@@ -350,7 +373,7 @@
#if not defined(HOTT_CC2500_INO)
#undef HOTT_FW_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(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)
#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(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)
#undef TELEMETRY
#undef INVERT_TELEMETRY
#undef MULTI_TELEMETRY

View File

@@ -392,6 +392,9 @@ static uint16_t XN297Dump_callback()
{ // Scan frequencies
hopping_frequency_no++;
bind_counter=0;
if(packet_count && packet_count<=5)
debug("\r\nTrying RF channel: ");
packet_count=0;
if(hopping_frequency_no>XN297DUMP_MAX_RF_CHANNEL)
{
debug("\r\n\r\n%d RF channels identified:",rf_ch_num);
@@ -472,10 +475,9 @@ static uint16_t XN297Dump_callback()
debug(" %02X",packet[i]);
packet_count++;
if(packet_count>5)
{
{//change channel
bind_counter=XN297DUMP_PERIOD_SCAN+1;
debug("\r\nTrying RF channel: ");
packet_count=0;
}
}
}

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
@@ -168,6 +170,7 @@
//The protocols below need a CYRF6936 to be installed
#define DEVO_CYRF6936_INO
#define DSM_CYRF6936_INO
#define DSM_RX_CYRF6936_INO
#define J6PRO_CYRF6936_INO
#define TRAXXAS_CYRF6936_INO
#define WFLY_CYRF6936_INO
@@ -175,6 +178,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 +188,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
@@ -206,13 +212,16 @@
#define HISKY_NRF24L01_INO
#define HONTAI_NRF24L01_INO
#define H8_3D_NRF24L01_INO
#define JJRC345_NRF24L01_INO
#define KF606_NRF24L01_INO
#define KN_NRF24L01_INO
#define MJXQ_NRF24L01_INO
#define MT99XX_NRF24L01_INO
#define NCC1701_NRF24L01_INO
#define POTENSIC_NRF24L01_INO
#define PROPEL_NRF24L01_INO
#define Q303_NRF24L01_INO
#define Q90C_NRF24L01_INO
#define SHENQI_NRF24L01_INO
#define SLT_NRF24L01_INO
#define SYMAX_NRF24L01_INO
@@ -225,18 +234,12 @@
#define ZSX_NRF24L01_INO
//The protocols below need a SX1276 to be installed
//#define FRSKYR9_SX1276_INO
#define FRSKYR9_SX1276_INO
/***************************/
/*** PROTOCOLS SETTINGS ***/
/***************************/
//FrSkyX specific setting
//-----------------------
//EU LBT setting: if commented the TX will not check if a channel is busy before transmitting.
//!!! Work in progress !!! it's currently known to cause telemerty issues. Enable only if you know what you are doing.
//#define FRSKYX_LBT
//DSM specific settings
//---------------------
//The DSM protocol is using by default the Spektrum throw of 1100..1900us @100% and 1000..2000us @125%.
@@ -299,6 +302,7 @@
#define HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define BAYANG_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define BUGS_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define DEVO_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define HUBSAN_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define NCC1701_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
#define CABELL_HUB_TELEMETRY // Use FrSkyD Hub format to send telemetry to TX
@@ -506,6 +510,7 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
X16_AH
IRDRONE
DHD_D4
QX100
PROTO_BAYANG_RX
NONE
PROTO_BUGS
@@ -543,6 +548,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
DSM2_11
DSMX_22
DSMX_11
PROTO_DSM_RX
NONE
PROTO_E01X
E012
E015
@@ -553,6 +560,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
PROTO_ESKY150
ESKY150_4CH
ESKY150_7CH
PROTO_ESKY150V2
NONE
PROTO_FLYSKY
Flysky
V9X9
@@ -563,8 +572,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
@@ -577,13 +593,16 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
CH_8
EU_16
EU_8
XCLONE
PROTO_FRSKYX2
FRSKYX2_CH_16
FRSKYX2_CH_8
FRSKYX2_EU_16
FRSKYX2_EU_8
CH_16
CH_8
EU_16
EU_8
XCLONE
PROTO_FRSKY_RX
NONE
FRSKY_RX
FRSKY_CLONE
PROTO_FX816
NONE
PROTO_FY326
@@ -612,13 +631,16 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
X5C1
FQ777_951
PROTO_HOTT
NONE
HOTT_SYNC
HOTT_NO_SYNC
PROTO_HUBSAN
H107
H301
H501
PROTO_J6PRO
NONE
PROTO_JJRC345
NONE
PROTO_KF606
NONE
PROTO_KN
@@ -641,9 +663,12 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
PROTO_NCC1701
NONE
PROTO_PELIKAN
NONE
PELIKAN_PRO
PELIKAN_LITE
PROTO_POTENSIC
NONE
PROTO_PROPEL
NONE
PROTO_Q2X2
Q222
Q242
@@ -653,6 +678,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
CX35
CX10D
CX10WD
PROTO_Q90C
NONE
PROTO_REDPINE
RED_FAST
RED_SLOW
@@ -662,6 +689,8 @@ const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
NONE
PROTO_SHENQI
NONE
PROTO_SKYARTEC
NONE
PROTO_SLT
SLT_V1
SLT_V2

View File

@@ -67,8 +67,8 @@ You've upgraded the module but the radio does not display the name of the protoc
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|ASSAN||||||||NRF24L01|
[Bayang](Protocols_Details.md#BAYANG---14)|14|Bayang|H8S3D|X16_AH|IRDRONE|DHD_D4||||NRF24L01|XN297
[Bayang RX](Protocols_Details.md#BAYANG-RX---59)|59|||||||||NRF24L01|XN297
[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|RX||||||||NRF24L01|XN297
[Bugs](Protocols_Details.md#BUGS---41)|41|BUGS||||||||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|
@@ -79,19 +79,23 @@ CFlie|38|CFlie||||||||NRF24L01|
[Devo](Protocols_Details.md#DEVO---7)|7|Devo|8CH|10CH|12CH|6CH|7CH|||CYRF6936|
[DM002](Protocols_Details.md#DM002---33)|33|DM002||||||||NRF24L01|XN297
[DSM](Protocols_Details.md#DSM---6)|6|DSM2-22|DSM2-11|DSMX-22|DSMX-11|AUTO||||CYRF6936|
[DSM_RX](Protocols_Details.md#DSM_RX---70)|70|RX||||||||CYRF6936|
[E01X](Protocols_Details.md#E01X---45)|45|E012|E015|E016H||||||NRF24L01|XN297/HS6200
[ESky](Protocols_Details.md#ESKY---16)|16|ESky|Std|ET4||||||NRF24L01|
[ESky](Protocols_Details.md#ESKY---16)|16|ESky|ET4|||||||NRF24L01|
[ESky150](Protocols_Details.md#ESKY150---35)|35|ESKY150||||||||NRF24L01|
[ESky150V2](Protocols_Details.md#ESKY150V2---69)|69|ESky150V2||||||||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|
[Flysky AFHDS2A RX](Protocols_Details.md#FLYSKY-AFHDS2A-RX---56)|56|RX||||||||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|
[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|
[FrskyX_RX](Protocols_Details.md#FRSKYX_RX---55)|55|FCC|EU_LBT|||||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|
@@ -100,32 +104,37 @@ CFlie|38|CFlie||||||||NRF24L01|
[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|||||NRF24L01|XN297
[HoTT](Protocols_Details.md#HoTT---57)|57|||||||||CC2500|
[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|J6PRO||||||||CYRF6936|
[J6Pro](Protocols_Details.md#J6Pro---22)|22|J6Pro||||||||CYRF6936|
[JJRC345](Protocols_Details.md#JJRC345---71)|71|JJRC345||||||||NRF24L01|XN297
[KF606](Protocols_Details.md#KF606---49)|49|KF606*||||||||NRF24L01|XN297
[KN](Protocols_Details.md#KN---9)|9|WLTOYS|FEILUN|||||||NRF24L01|
[MJXq](Protocols_Details.md#MJXQ---18)|18|WLH08|X600|X800|H26D|E010*|H26WH|PHOENIX*||NRF24L01|XN297
[MT99xx](Protocols_Details.md#MT99XX---17)|17|MT|H7|YZ|LS|FY805||||NRF24L01|XN297
[NCC1701](Protocols_Details.md#NCC1701---44)|44|NCC1701||||||||NRF24L01|
[OpenLRS](Protocols_Details.md#OpenLRS---27)|27|||||||||None|
[Pelikan](Protocols_Details.md#Pelikan---60)|60|||||||||A7105|
[Pelikan](Protocols_Details.md#Pelikan---60)|60|Pro|Lite|||||||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
[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
[SLT](Protocols_Details.md#SLT---11)|11|SLT_V1|SLT_V2|Q100|Q200|MR100||||NRF24L01|
[Skyartec](Protocols_Details.md#Skyartec---68)|68|Skyartec||||||||CC2500|CC2500
[SLT](Protocols_Details.md#SLT---11)|11|SLT_V1|SLT_V2|Q100|Q200|MR100||||NRF24L01|CC2500
[SymaX](Protocols_Details.md#Symax---10)|10|SYMAX|SYMAX5C|||||||NRF24L01|
[Tiger](Protocols_Details.md#Tiger---61)|61|Tiger||||||||NRF24L01|XN297
[Traxxas](Protocols_Details.md#Traxxas---43)|43|RX6519||||||||CYRF6936|
[Traxxas](Protocols_Details.md#Traxxas---43)|43|6519 RX||||||||CYRF6936|
[V2x2](Protocols_Details.md#V2X2---5)|5|V2x2|JXD506|||||||NRF24L01|
[V761](Protocols_Details.md#V761---48)|48|V761||||||||NRF24L01|XN297
[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|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.
@@ -259,17 +268,21 @@ A|E|T|R|ARM|ANGLE|FLIP|PICTURE|VIDEO|LED
ANGLE: angle is +100%, acro is -100%
## Pelikan - *60*
Models: TX: CADET PRO V4, RX: RX-602 V4
Extended limits supported
**Only 1 set of frequencies for now**
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be AETR.
RX output will match the Pelikan 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 Pro - *0*
Models: TX: CADET PRO V4, RX: RX-602 V4
### Sub_protocol Lite - *1*
Models: TX: CADET 4 LITE
**Only 1 frequency hopping table**
***
# CC2500 RF Module
@@ -332,8 +345,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 receivers X4R, X6R and X8R. 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
@@ -357,26 +400,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
## FRSKYX_RX - *55*
The FrSkyX receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
### Sub_protocol Cloned - *4*
Use the identifier learnt from another FrSky radio when binding with the FrSkyRX/CloneTX mode.
## FRSKYX2 - *64*
Same as [FrskyX](Protocols_Details.md#FRSKYX---15) but for D16 v2.1.0 FCC/LBT.
## FRSKY_RX - *55*
### 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.
@@ -384,19 +439,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.
@@ -425,18 +486,20 @@ Basic telemetry using FrSky Hub on er9x, erskyTX, OpenTX and any radio with FrSk
**The TX must be close to the RX for the bind negotiation to complete successfully**
### Sub_protocol MINIMA - *2*
MINIMA, MICRO and RED receivers
MINIMA, MICRO and RED receivers. Also used by ARES planes.
## HoTT - *57*
Models: Graupner HoTT receivers (tested on GR-12L and GR-16L).
Models: Graupner HoTT receivers (tested on GR-12, GR-12L, GR-16 and Vector).
Extended limits and failsafe supported
Extended limits, failsafe and LBT supported.
**RX_Num is used to give a number a given RX. You must use a different RX_Num per RX. A maximum of 64 HoTT RXs are supported.**
Full telemetry and full text config mode are available starting from OpenTX 2.3.8N226.
**RX_Num is used to give a number to a given RX. You must use a different RX_Num per RX. A maximum of 64 HoTT RXs are supported.**
**Failsafe MUST be configured once with the desired channel values (hold or position) while the RX is up (wait 10+sec for the RX to learn the config) and then failsafe MUST be set to RX/Receiver otherwise the servos will jitter!!!**
The RX features configuration are done using the OpenTX script "Graupner HoTT.lua" .
The RX and sensors/FC features configuration are done through the OpenTX script "Graupner HoTT.lua".
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.
@@ -445,7 +508,15 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
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.
### Sub_protocol Sync - *0*
Recommended for best telemetry performance.
### Sub_protocol No_Sync - *1*
Telemetry compatibility mode when Sync does not work due to an old firmware on the RX.
You should definitively upgrade your receivers/sensors to the latest firmware versions: https://www.rcgroups.com/forums/showpost.php?p=44668015&postcount=18022
## Scanner - *54*
2.4GHz scanner accessible using the OpenTX 2.3 Spectrum Analyser tool.
## SFHSS - *21*
Models: Futaba RXs and XK models.
@@ -459,8 +530,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
@@ -474,7 +551,9 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
Note that the RX ouput will be EATR.
RX output will match the Devo standard EATR independently of the input configuration AETR, RETA... unless on OpenTX 2.3.3+ you use the "Disable channel mapping" feature on the GUI.
Basic telemetry is available if RX supports it: TX_RSSI, A1 and A2
Bind procedure using serial:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
@@ -604,6 +683,19 @@ The current radio firmware which are able to use the "AUTO" feature are erskyTX
For these firmwares, you must have a telemetry enabled TX and you have to make sure you set the Telemetry "Usr proto" to "DSMx".
Also on er9x you will need to be sure to match the polarity of the telemetry serial (normal or inverted by bitbashing), while on erskyTX you can set "Invert COM1" accordinlgy.
## DSM_RX - *70*
The DSM receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
Notes:
- Automatically detect DSM 2/X 11/22ms 1024/2048res
- Available in OpenTX 2.3.3+, Trainer Mode Master/Multi
- Channels 1..4 are remapped to the module default channel order unless on OpenTX 2.3.3+ you use the "Disable channel mapping" feature on the GUI.
- Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
## J6Pro - *22*
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
@@ -690,6 +782,9 @@ CH12|CH13
----|----
TAKE_OFF|EMG_STOP
### Sub_protocol QX100 - *5*
Model: REVELL QX100
## BAYANG RX - *59*
The Bayang receiver protocol enables master/slave trainning, separate access from 2 different radios to the same model,...
@@ -874,6 +969,19 @@ 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
RATE for the F150 V2 is assigned to channel 5: -100%=low, 100%=high
## FX816 - *58*
Model: FEI XIONG FX816 P38
@@ -1005,6 +1113,13 @@ ARM|
### Sub_protocol FQ777_951 - *3*
## JJRC345 - *71*
Model: JJRC345
CH1|CH2|CH3|CH4|CH5|CH6|CH7
---|---|---|---|---|---|---
A|E|T|R|FLIP|HEADLESS|RTH
## KF606 - *49*
Model: KF606
@@ -1101,7 +1216,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
---|---|---|---|---|---|---|---
@@ -1115,6 +1230,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
@@ -1168,6 +1294,18 @@ ARM|FLIP
ARM is 3 positions: -100%=land / 0%=manual / +100%=take off
## Q90C - *72*
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).
**Only 1 ID available. FMODE and VTX+ are not supported. If you have a TX then contact me on GitHub or RCGroups.**
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|FMODE|VTX+
## Redpine - *50*
[Link to the forum](https://www.rcgroups.com/forums/showthread.php?3236043-Redpine-Lowest-latency-RC-protocol)
@@ -1181,13 +1319,17 @@ Model: Shenqiwei 1/20 Mini Motorcycle
CH1|CH2|CH3|CH4
---|---|---|---
| |T|R
-|-|T|R
Throttle +100%=full forward,0%=stop,-100%=full backward.
## SLT - *11*
Autobind protocol
This protocol is known to be problematic because it's using the NRF24L01 with a transmission speed of 250kbps therefore it doesn't work very well with every modules, this is a hardware issue with the accuracy of the components. (some Jumper models seem to be using a NRF24L01 clone)
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 V1 - *0*
CH1|CH2|CH3|CH4|CH5|CH6
@@ -1326,6 +1468,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
@@ -1347,7 +1507,7 @@ Autobind protocol
CH1|CH2|CH3|CH4|CH5
---|---|---|---|---
||T|R|LIGHT
-|-|T|R|LIGHT
# SX1276 RF Module

View File

@@ -1,14 +1,21 @@
# Flashing from the Transmitter
For radios running erskyTx and OpenTX, there is an option to flash a precompiled firmware file to the multiprotocol module using the transmitter's Bootloader mode.
For radios running erskyTx and OpenTX, there is an option to flash a precompiled firmware file to the multiprotocol module:
- OpenTX: using the SD card browser
- erskyTX : using the transmitter's Bootloader mode.
## Tools required
* A compatible transmitter running an erskyTx bootloader v2.9 or newer. This is true for both OpenTX and erskyTx.
What you need:
* A precompiled multiprotocol firmware file (.hex for Atmega328p or .bin for STM32)
* A **Flash from TX** bootloader installed on an Atmega328p or STM32 multiprotocol module
* A means to get the firmware file onto the transmitter's SD card
## Radio bootloader and apps
## OpenTX 2.3.3 or newer
1. Copy the firmware file to the radio's SD card - it doesn't matter where you put it
1. Switch the radio on normally and use the radio menu to locate the file on the SD card
1. Highlight the file and press the ENTER button
1. Choose Flash internal module or Flash external module as appropriate
## erskyTX
### How to check the bootloader version
1. Push both horizontals trims inwards (close to each others) while powering on the radio
@@ -35,9 +42,7 @@ For radios running erskyTx and OpenTX, there is an option to flash a precompiled
1. Long press it and select `Flash bootloader`
1. Check by rebooting the radio in bootloader mode that everything is [ok](###-How-to-check-the-bootloader-version)
**Note**: For OpenTX radio, this bootloader is an upgraded version of the existing bootloader shipped with OpenTX. It's providing you the exact same level of default features while adding more through apps. You can go back and forth between the 2 bootloaders without an issue.
## Multimodule upgrade procedure
### Multimodule upgrade procedure
1. Either:
1. Connect the transmitter using a USB cable and power it on, or
1. Remove the SD card from the transmitter and mount it using a suitable reader

BIN
docs/images/warning.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 104 KiB