Compare commits

..

44 Commits

Author SHA1 Message Date
pascallanger
d96ba9fa46 Flysky Flash space optimization 2016-09-04 16:49:00 +02:00
pascallanger
2261d655ea DEVO/J6pro Flash space optimization 2016-09-04 16:49:00 +02:00
pascallanger
8b67049863 Added NRF24L01_ReadPayloadLength 2016-09-04 16:49:00 +02:00
pascallanger
48258dd9dd Renamed FrSky protocols 2016-09-03 11:57:40 +02:00
pascallanger
e04c573726 Renamed FrSky protocols 2016-09-03 11:56:39 +02:00
pascallanger
4daec3794e Renamed FrSky protocols to match with receivers 2016-09-03 11:49:25 +02:00
pascallanger
f0646dde32 FrSky1 Fix 2016-09-03 10:12:30 +02:00
pascallanger
ec2086e0f7 Fixed invert serial compilation 2016-09-01 20:12:17 +02:00
pascallanger
2ac704178c FRSKY1 2016-09-01 18:12:35 +02:00
pascallanger
7c43c38e28 FRSKY1 2016-09-01 18:09:35 +02:00
pascallanger
043a8336e5 Code cleaning (XMEGA) 2016-09-01 17:41:38 +02:00
pascallanger
ee27535b82 Update README.md 2016-09-01 14:42:56 +02:00
pascallanger
89e6ae2475 Update Protocols_Details.md 2016-09-01 14:40:17 +02:00
pascallanger
e51615f520 DSM2 renamed to DSM 2016-09-01 14:00:49 +02:00
pascallanger
6e59897587 Update Protocols_Details.md 2016-09-01 13:53:48 +02:00
pascallanger
bd0644a261 Update Protocols_Details.md 2016-09-01 13:53:10 +02:00
pascallanger
d7825e1bf8 Update README.md 2016-09-01 13:47:42 +02:00
pascallanger
97956b6c5e FrSky1 CRC messed up... 2016-09-01 13:42:33 +02:00
pascallanger
8150504ea0 NRF CE 2016-09-01 13:05:56 +02:00
pascallanger
942dec81c7 Typo 2016-09-01 08:08:00 +02:00
pascallanger
dcbc377c62 FrSky1 optim 2016-08-31 15:54:24 +02:00
pascallanger
7b65233699 FrSky 1way protocol + cosmetic 2016-08-31 15:43:45 +02:00
pascallanger
eabfd8b5c4 Important changes of the scheduler and interrupts 2016-08-31 10:26:27 +02:00
pascallanger
b7b2799611 FrSky option applied live 2016-08-31 10:22:36 +02:00
pascallanger
ece59ac374 FrSky ppm option value default 40 2016-08-31 10:20:56 +02:00
pascallanger
83cc8b772c Merge branch 'master' of https://github.com/pascallanger/DIY-Multiprotocol-TX-Module 2016-08-31 10:19:59 +02:00
pascallanger
8b5bc18142 YD717 4-in-1 V2 compatibility 2016-08-31 10:19:55 +02:00
pascallanger
e1413baa9a Update Protocols_Details.md 2016-08-30 23:30:18 +02:00
pascallanger
03640e6d37 Changed update_serial_data 2016-08-29 17:32:21 +02:00
pascallanger
2588011524 Orange DSM module update 2016-08-29 09:51:34 +02:00
pascallanger
0c16a6804a E010 2016-08-29 08:29:57 +02:00
pascallanger
e2021fdf5d Update README.md 2016-08-29 08:24:52 +02:00
pascallanger
33b5694d35 MJXQ/E010 mod 2016-08-29 08:23:17 +02:00
pascallanger
af7d04fef6 Added E010 2016-08-28 14:05:21 +02:00
pascallanger
14e3419e4c Added MJXQ / E010 2016-08-28 14:03:22 +02:00
pascallanger
f6c5252376 DEVO PPM fixed id mode 2016-08-27 11:38:07 +02:00
pascallanger
78ee77444f Update README.md 2016-08-27 08:26:05 +02:00
pascallanger
fb022970b5 Update Protocols_Details.md 2016-08-26 21:02:50 +02:00
pascallanger
e5d378dc93 Update Protocols_Details.md 2016-08-26 18:46:03 +02:00
pascallanger
5969902263 MJXQ fix 2016-08-26 17:21:21 +02:00
pascallanger
d5894de142 Merge branch 'master' of https://github.com/pascallanger/DIY-Multiprotocol-TX-Module 2016-08-26 16:18:58 +02:00
pascallanger
059c6baa4e FrSkyX/SFHSS rfcal & second channel ASSAN 2016-08-26 16:18:50 +02:00
pascallanger
bbf9331baf Update README.md 2016-08-26 10:56:27 +02:00
pascallanger
a5b084f506 Update README.md 2016-08-26 10:55:13 +02:00
21 changed files with 1161 additions and 914 deletions

View File

@@ -23,12 +23,12 @@
void A7105_WriteData(uint8_t len, uint8_t channel) void A7105_WriteData(uint8_t len, uint8_t channel)
{ {
uint8_t i; uint8_t i;
CS_off; A7105_CS_off;
SPI_Write(A7105_RST_WRPTR); SPI_Write(A7105_RST_WRPTR);
SPI_Write(0x05); SPI_Write(0x05);
for (i = 0; i < len; i++) for (i = 0; i < len; i++)
SPI_Write(packet[i]); SPI_Write(packet[i]);
CS_on; A7105_CS_on;
A7105_WriteReg(0x0F, channel); A7105_WriteReg(0x0F, channel);
A7105_Strobe(A7105_TX); A7105_Strobe(A7105_TX);
} }
@@ -36,27 +36,27 @@ void A7105_WriteData(uint8_t len, uint8_t channel)
void A7105_ReadData() { void A7105_ReadData() {
uint8_t i; uint8_t i;
A7105_Strobe(0xF0); //A7105_RST_RDPTR A7105_Strobe(0xF0); //A7105_RST_RDPTR
CS_off; A7105_CS_off;
SPI_Write(0x45); SPI_Write(0x45);
for (i=0;i<16;i++) for (i=0;i<16;i++)
packet[i]=A7105_Read(); packet[i]=A7105_Read();
CS_on; A7105_CS_on;
} }
void A7105_WriteReg(uint8_t address, uint8_t data) { void A7105_WriteReg(uint8_t address, uint8_t data) {
CS_off; A7105_CS_off;
SPI_Write(address); SPI_Write(address);
NOP(); NOP();
SPI_Write(data); SPI_Write(data);
CS_on; A7105_CS_on;
} }
uint8_t A7105_ReadReg(uint8_t address) { uint8_t A7105_ReadReg(uint8_t address) {
uint8_t result; uint8_t result;
CS_off; A7105_CS_off;
SPI_Write(address |=0x40); //bit 6 =1 for reading SPI_Write(address |=0x40); //bit 6 =1 for reading
result = A7105_Read(); result = A7105_Read();
CS_on; A7105_CS_on;
return(result); return(result);
} }
@@ -110,13 +110,13 @@ uint8_t A7105_Reset()
} }
void A7105_WriteID(uint32_t ida) { void A7105_WriteID(uint32_t ida) {
CS_off; A7105_CS_off;
SPI_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0 SPI_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0
SPI_Write((ida>>24)&0xff);//53 SPI_Write((ida>>24)&0xff);//53
SPI_Write((ida>>16)&0xff);//75 SPI_Write((ida>>16)&0xff);//75
SPI_Write((ida>>8)&0xff);//c5 SPI_Write((ida>>8)&0xff);//c5
SPI_Write((ida>>0)&0xff);//2a SPI_Write((ida>>0)&0xff);//2a
CS_on; A7105_CS_on;
} }
/* /*
@@ -162,9 +162,9 @@ void A7105_SetPower()
} }
void A7105_Strobe(uint8_t address) { void A7105_Strobe(uint8_t address) {
CS_off; A7105_CS_off;
SPI_Write(address); SPI_Write(address);
CS_on; A7105_CS_on;
} }
const uint8_t PROGMEM HUBSAN_A7105_regs[] = { const uint8_t PROGMEM HUBSAN_A7105_regs[] = {

View File

@@ -140,7 +140,7 @@ static void __attribute__((unused)) ASSAN_initialize_txid()
packet[21]=0xFA; packet[21]=0xFA;
packet[20]=0x53; */ packet[20]=0x53; */
// Using packet[20..23] to store the ID1 and packet[24..27] to store the ID2 // Using packet[20..23] to store the ID1 and packet[24..27] to store the ID2
uint8_t freq=0; uint8_t freq=0,freq2;
for(uint8_t i=0;i<4;i++) for(uint8_t i=0;i<4;i++)
{ {
uint8_t temp=rx_tx_addr[0]; uint8_t temp=rx_tx_addr[0];
@@ -153,9 +153,15 @@ static void __attribute__((unused)) ASSAN_initialize_txid()
freq=((freq%25)+2)<<1; freq=((freq%25)+2)<<1;
if(freq&0x02) freq|=0x01; if(freq&0x02) freq|=0x01;
hopping_frequency[0]=freq; hopping_frequency[0]=freq;
// Alternate frequency // Alternate frequency has some random
hopping_frequency[1]=freq*2-6; do
hopping_frequency[1]+=analogRead(A6)%12; // Add some random to the second channel {
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
freq2=random(0xfefefefe)%9;
freq2+=freq*2-5;
}
while( (freq2>118) || (freq2<freq+1) || (freq2==2*freq) );
hopping_frequency[1]=freq2; // Add some random to the second channel
} }
uint16_t initASSAN() uint16_t initASSAN()

View File

@@ -258,3 +258,37 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
} }
CYRF_SetTxRxMode(TX_EN); CYRF_SetTxRxMode(TX_EN);
} }
#if defined(DEVO_CYRF6936_INO) || defined(J6PRO_CYRF6936_INO)
const uint8_t PROGMEM DEVO_j6pro_sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
{0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91},
{0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F},
{0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A},
{0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50},
{0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44},
{0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46},
{0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C},
{0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74},
{0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49},
{0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72},
#if defined(J6PRO_CYRF6936_INO)
{0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17},
{0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table
{0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above,
{0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped
{0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50},
{0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44},
{0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46},
{0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C},
{0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74},
#endif
};
#endif
static void __attribute__((unused)) CYRF_PROGMEM_ConfigSOPCode(const uint8_t *data)
{
uint8_t code[8];
for(uint8_t i=0;i<8;i++)
code[i]=pgm_read_byte_near(&data[i]);
CYRF_ConfigSOPCode(code);
}

View File

@@ -13,7 +13,7 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>. along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/ */
#if defined(DSM2_CYRF6936_INO) #if defined(DSM_CYRF6936_INO)
#include "iface_cyrf6936.h" #include "iface_cyrf6936.h"
@@ -408,7 +408,7 @@ static void __attribute__((unused)) calc_dsmx_channel()
} }
} }
uint16_t ReadDsm2() uint16_t ReadDsm()
{ {
#define DSM_CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2 #define DSM_CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
#define DSM_WRITE_DELAY 1550 // Time after write to verify write complete #define DSM_WRITE_DELAY 1550 // Time after write to verify write complete
@@ -536,7 +536,7 @@ uint16_t ReadDsm2()
return 0; return 0;
} }
uint16_t initDsm2() uint16_t initDsm()
{ {
CYRF_Reset(); CYRF_Reset();
CYRF_GetMfgData(cyrfmfg_id);// CYRF_GetMfgData(cyrfmfg_id);//

View File

@@ -43,28 +43,6 @@ enum {
DEVO_BOUND_10, DEVO_BOUND_10,
}; };
const uint8_t PROGMEM DEVO_sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
/* 0 */ {0x3C,0x37,0xCC,0x91,0xE2,0xF8,0xCC,0x91}, //0x91CCF8E291CC373C
/* 1 */ {0x9B,0xC5,0xA1,0x0F,0xAD,0x39,0xA2,0x0F}, //0x0FA239AD0FA1C59B
/* 2 */ {0xEF,0x64,0xB0,0x2A,0xD2,0x8F,0xB1,0x2A}, //0x2AB18FD22AB064EF
/* 3 */ {0x66,0xCD,0x7C,0x50,0xDD,0x26,0x7C,0x50}, //0x507C26DD507CCD66
/* 4 */ {0x5C,0xE1,0xF6,0x44,0xAD,0x16,0xF6,0x44}, //0x44F616AD44F6E15C
/* 5 */ {0x5A,0xCC,0xAE,0x46,0xB6,0x31,0xAE,0x46}, //0x46AE31B646AECC5A
/* 6 */ {0xA1,0x78,0xDC,0x3C,0x9E,0x82,0xDC,0x3C}, //0x3CDC829E3CDC78A1
/* 7 */ {0xB9,0x8E,0x19,0x74,0x6F,0x65,0x18,0x74}, //0x7418656F74198EB9
/* 8 */ {0xDF,0xB1,0xC0,0x49,0x62,0xDF,0xC1,0x49}, //0x49C1DF6249C0B1DF
/* 9 */ {0x97,0xE5,0x14,0x72,0x7F,0x1A,0x14,0x72}, //0x72141A7F7214E597
};
static void __attribute__((unused)) DEVO_ConfigSOPCode(uint8_t val)
{
uint8_t code[8];
for(uint8_t i=0;i<8;i++)
code[i]=pgm_read_byte_near(&DEVO_sopcodes[val][i]);
CYRF_ConfigSOPCode(code);
}
static void __attribute__((unused)) DEVO_scramble_pkt() static void __attribute__((unused)) DEVO_scramble_pkt()
{ {
#ifdef NO_SCRAMBLE #ifdef NO_SCRAMBLE
@@ -78,7 +56,20 @@ static void __attribute__((unused)) DEVO_scramble_pkt()
static void __attribute__((unused)) DEVO_add_pkt_suffix() static void __attribute__((unused)) DEVO_add_pkt_suffix()
{ {
uint8_t bind_state; uint8_t bind_state;
if(prev_option!=option) #ifdef ENABLE_PPM
if(mode_select && option==0 && IS_BIND_DONE_on) //PPM mode and option not already set and bind is finished
{
BIND_SET_INPUT;
BIND_SET_PULLUP; // set pullup
if(IS_BIND_BUTTON_on)
{
eeprom_write_byte((uint8_t*)(30+mode_select),0x01); // Set fixed id mode for the current model
option=1;
}
BIND_SET_OUTPUT;
}
#endif //ENABLE_PPM
if(prev_option!=option && IS_BIND_DONE_on)
{ {
MProtocol_id = RX_num + MProtocol_id_master; MProtocol_id = RX_num + MProtocol_id_master;
bind_counter=DEVO_BIND_COUNT; bind_counter=DEVO_BIND_COUNT;
@@ -168,7 +159,7 @@ static void __attribute__((unused)) DEVO_cyrf_set_bound_sop_code()
uint8_t sopidx = (0xff &((cyrfmfg_id[0] << 2) + cyrfmfg_id[1] + cyrfmfg_id[2])) % 10; uint8_t sopidx = (0xff &((cyrfmfg_id[0] << 2) + cyrfmfg_id[1] + cyrfmfg_id[2])) % 10;
CYRF_SetTxRxMode(TX_EN); CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed((crc << 8) + crc); CYRF_ConfigCRCSeed((crc << 8) + crc);
DEVO_ConfigSOPCode(sopidx); CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sopidx]);
CYRF_SetPower(0x08); CYRF_SetPower(0x08);
} }
@@ -300,7 +291,7 @@ uint16_t DevoInit()
CYRF_GetMfgData(cyrfmfg_id); CYRF_GetMfgData(cyrfmfg_id);
CYRF_SetTxRxMode(TX_EN); CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed(0x0000); CYRF_ConfigCRCSeed(0x0000);
DEVO_ConfigSOPCode(0); CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[0]);
DEVO_set_radio_channels(); DEVO_set_radio_channels();
hopping_frequency_ptr = hopping_frequency; hopping_frequency_ptr = hopping_frequency;

View File

@@ -50,10 +50,6 @@ enum {
FLAG_V912_BTMBTN= 0x80, FLAG_V912_BTMBTN= 0x80,
}; };
uint8_t chanrow;
uint8_t chancol;
uint8_t chanoffset;
const uint8_t PROGMEM V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ? const uint8_t PROGMEM V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
0x49, 0x49, 0x49, 0x49, 0x49, }; 0x49, 0x49, 0x49, 0x49, 0x49, };
@@ -151,25 +147,6 @@ static void __attribute__((unused)) flysky_build_packet(uint8_t init)
flysky_apply_extension_flags(); flysky_apply_extension_flags();
} }
const uint8_t PROGMEM tx_channels[16][16] = {
{0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0},
{0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a},
{0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82},
{0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a},
{0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96},
{0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28},
{0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64},
{0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50},
{0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64},
{0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50},
{0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46},
{0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82},
{0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46},
{0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46},
};
uint16_t ReadFlySky() uint16_t ReadFlySky()
{ {
if (bind_counter) if (bind_counter)
@@ -183,28 +160,56 @@ uint16_t ReadFlySky()
else else
{ {
flysky_build_packet(0); flysky_build_packet(0);
A7105_WriteData(21, pgm_read_byte_near(&tx_channels[chanrow][chancol])-chanoffset); A7105_WriteData(21, hopping_frequency[hopping_frequency_no]);
chancol = (chancol + 1) % 16; hopping_frequency_no = (hopping_frequency_no + 1) & 0x0F;
if (! chancol) //Keep transmit power updated
A7105_SetPower(); A7105_SetPower();
} }
return 1510; //1460 on deviation but not working with the latest V911 bricks... Turnigy 9X v2 is 1533, Flysky TX for 9XR/9XR Pro is 1510, V911 TX is 1490. return 1510; //1460 on deviation but not working with the latest V911 bricks... Turnigy 9X v2 is 1533, Flysky TX for 9XR/9XR Pro is 1510, V911 TX is 1490.
} }
uint16_t initFlySky() { const uint8_t PROGMEM tx_channels[8][4] = {
{ 0x12, 0x34, 0x56, 0x78},
{ 0x18, 0x27, 0x36, 0x45},
{ 0x41, 0x82, 0x36, 0x57},
{ 0x84, 0x13, 0x65, 0x72},
{ 0x87, 0x64, 0x15, 0x32},
{ 0x76, 0x84, 0x13, 0x52},
{ 0x71, 0x62, 0x84, 0x35},
{ 0x71, 0x86, 0x43, 0x52}
};
uint16_t initFlySky()
{
uint8_t chanrow;
uint8_t chanoffset;
uint8_t temp;
A7105_Init(INIT_FLYSKY); //flysky_init(); A7105_Init(INIT_FLYSKY); //flysky_init();
if ((rx_tx_addr[3]&0xF0) > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912) if ((rx_tx_addr[3]&0xF0) > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912)
rx_tx_addr[3]=rx_tx_addr[3]-0x70; rx_tx_addr[3]=rx_tx_addr[3]-0x70;
chanrow=rx_tx_addr[3] & 0x0F; chanrow=rx_tx_addr[3] & 0x0F;
chancol=0;
chanoffset=rx_tx_addr[3]/16; chanoffset=rx_tx_addr[3]/16;
// Build frequency hop table
for(uint8_t i=0;i<16;i++)
{
temp=pgm_read_byte_near(&tx_channels[chanrow>>1][i>>2]);
if(i&0x01)
temp&=0x0F;
else
temp>>=4;
temp*=0x0A;
if(i&0x02)
temp+=0x50;
hopping_frequency[((chanrow&1)?15-i:i)]=temp-chanoffset;
}
hopping_frequency_no=0;
if(IS_AUTOBIND_FLAG_on) if(IS_AUTOBIND_FLAG_on)
bind_counter = FLYSKY_BIND_COUNT; bind_counter = FLYSKY_BIND_COUNT;
else else
bind_counter = 0; bind_counter = 0;
return 2400; return 2400;
} }
#endif #endif

View File

@@ -13,30 +13,13 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>. along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/ */
#if defined(FRSKY_CC2500_INO) #if defined(FRSKYD_CC2500_INO)
#include "iface_cc2500.h" #include "iface_cc2500.h"
//##########Variables########
//uint32_t state;
//uint8_t len;
/*
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
FRSKY_DATA1,
FRSKY_DATA2,
FRSKY_DATA3,
FRSKY_DATA4,
FRSKY_DATA5
};
*/
static void __attribute__((unused)) frsky2way_init(uint8_t bind) static void __attribute__((unused)) frsky2way_init(uint8_t bind)
{ {
// Configure cc2500 for tx mode // Configure cc2500 for tx mode
CC2500_Reset();
// //
for(uint8_t i=0;i<36;i++) for(uint8_t i=0;i<36;i++)
{ {
@@ -50,6 +33,7 @@ static void __attribute__((unused)) frsky2way_init(uint8_t bind)
val=bind ? 0x43 : 0x03; val=bind ? 0x43 : 0x03;
CC2500_WriteReg(reg,val); CC2500_WriteReg(reg,val);
} }
prev_option = option ;
CC2500_SetTxRxMode(TX_EN); CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower(); CC2500_SetPower();
@@ -143,7 +127,7 @@ uint16_t initFrSky_2way()
if(IS_AUTOBIND_FLAG_on) if(IS_AUTOBIND_FLAG_on)
{ {
frsky2way_init(1); frsky2way_init(1);
state = FRSKY_BIND;// state = FRSKY_BIND;
} }
else else
{ {
@@ -208,6 +192,11 @@ uint16_t ReadFrSky_2way()
} }
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47)); CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ;
}
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89); CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX); CC2500_Strobe(CC2500_SFRX);
frsky2way_data_frame(); frsky2way_data_frame();

View File

@@ -0,0 +1,209 @@
/*
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(FRSKYV_CC2500_INO)
#define FRSKYV_BIND_COUNT 200
enum {
FRSKYV_DATA1=0,
FRSKYV_DATA2,
FRSKYV_DATA3,
FRSKYV_DATA4,
FRSKYV_DATA5
};
#include "iface_cc2500.h"
const PROGMEM uint8_t FRSKYV_cc2500_conf[][2]={
{ CC2500_17_MCSM1, 0x0c },
{ CC2500_18_MCSM0, 0x18 },
{ CC2500_06_PKTLEN, 0xff },
{ CC2500_07_PKTCTRL1, 0x04 },
{ CC2500_08_PKTCTRL0, 0x05 },
{ CC2500_3E_PATABLE, 0xfe },
{ CC2500_0B_FSCTRL1, 0x08 },
{ CC2500_0C_FSCTRL0, 0x00 },
{ CC2500_0D_FREQ2, 0x5c },
{ CC2500_0E_FREQ1, 0x58 },
{ CC2500_0F_FREQ0, 0x9d },
{ CC2500_10_MDMCFG4, 0xaa },
{ CC2500_11_MDMCFG3, 0x10 },
{ CC2500_12_MDMCFG2, 0x93 },
{ CC2500_13_MDMCFG1, 0x23 },
{ CC2500_14_MDMCFG0, 0x7a },
{ CC2500_15_DEVIATN, 0x41 }
};
static void __attribute__((unused)) FRSKYV_init()
{
for(uint8_t i=0;i<17;i++)
{
uint8_t reg=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][1]);
if(reg==CC2500_0C_FSCTRL0)
val=option;
CC2500_WriteReg(reg,val);
}
prev_option = option ;
for(uint8_t i=19;i<36;i++)
{
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
CC2500_WriteReg(reg,val);
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
}
static uint8_t __attribute__((unused)) FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len)
{
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x80)
result = (result << 1) ^ 0x07;
else
result = result << 1;
}
return result;
}
static uint8_t __attribute__((unused)) FRSKYV_crc8_le(uint8_t *data, uint8_t len)
{
uint8_t result = 0xD6;
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x01)
result = (result >> 1) ^ 0x83;
else
result = result >> 1;
}
return result;
}
static void __attribute__((unused)) FRSKYV_build_bind_packet()
{
//0e 03 01 57 12 00 06 0b 10 15 1a 00 00 00 61
packet[0] = 0x0e; //Length
packet[1] = 0x03; //Packet type
packet[2] = 0x01; //Packet type
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
packet[5] = (binding_idx % 10) * 5;
packet[6] = packet[5] * 5 + 6;
packet[7] = packet[5] * 5 + 11;
packet[8] = packet[5] * 5 + 16;
packet[9] = packet[5] * 5 + 21;
packet[10] = packet[5] * 5 + 26;
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = FRSKYV_crc8(0x93, packet, 14);
}
static uint8_t __attribute__((unused)) FRSKYV_calc_channel()
{
uint32_t temp=seed;
temp = (temp * 0xaa) % 0x7673;
seed = temp;
return (seed & 0xff) % 0x32;
}
static void __attribute__((unused)) FRSKYV_build_data_packet()
{
uint8_t idx = 0; // transmit lower channels
packet[0] = 0x0e;
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = seed & 0xff;
packet[4] = seed >> 8;
if (phase == FRSKYV_DATA1 || phase == FRSKYV_DATA3)
packet[5] = 0x0f;
else
if(phase == FRSKYV_DATA2 || phase == FRSKYV_DATA4)
{
packet[5] = 0xf0;
idx=4; // transmit upper channels
}
else
packet[5] = 0x00;
for(uint8_t i = 0; i < 4; i++)
{
uint16_t value = convert_channel_frsky(i+idx);
packet[2*i + 6] = value & 0xff;
packet[2*i + 7] = value >> 8;
}
packet[14] = FRSKYV_crc8(crc8, packet, 14);
}
uint16_t ReadFRSKYV()
{
if(IS_BIND_DONE_on)
{ // Normal operation
uint8_t chan = FRSKYV_calc_channel();
CC2500_Strobe(CC2500_SIDLE);
if (option != prev_option)
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
prev_option=option;
}
CC2500_WriteReg(CC2500_0A_CHANNR, chan * 5 + 6);
FRSKYV_build_data_packet();
if (phase == FRSKYV_DATA5)
{
CC2500_SetPower();
phase = FRSKYV_DATA1;
}
else
phase++;
CC2500_WriteData(packet, packet[0]+1);
return 9006;
}
// Bind mode
FRSKYV_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteData(packet, packet[0]+1);
binding_idx++;
if(binding_idx>=FRSKYV_BIND_COUNT)
BIND_DONE;
return 53460;
}
uint16_t initFRSKYV()
{
//ID is 15 bits. Using rx_tx_addr[2] and rx_tx_addr[3] since we want to use RX_Num for model match
rx_tx_addr[2]&=0x7F;
crc8 = FRSKYV_crc8_le(rx_tx_addr+2, 2);
FRSKYV_init();
seed = 1;
binding_idx=0;
phase = FRSKYV_DATA1;
return 10000;
}
#endif

View File

@@ -21,10 +21,8 @@
#include "iface_cc2500.h" #include "iface_cc2500.h"
uint8_t chanskip; uint8_t chanskip;
uint8_t channr;
uint8_t counter_rst; uint8_t counter_rst;
uint8_t ctr; uint8_t ctr;
uint8_t FS_flag=0;
uint8_t seq_last_sent; uint8_t seq_last_sent;
uint8_t seq_last_rcvd; uint8_t seq_last_rcvd;
@@ -49,16 +47,12 @@ static uint8_t __attribute__((unused)) hop(uint8_t byte)
static void __attribute__((unused)) set_start(uint8_t ch ) static void __attribute__((unused)) set_start(uint8_t ch )
{ {
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_23_FSCAL3, calData[ch][0]); CC2500_WriteReg(CC2500_25_FSCAL1, calData[ch]);
CC2500_WriteReg(CC2500_24_FSCAL2, calData[ch][1]); CC2500_WriteReg(CC2500_0A_CHANNR, ch==47? 0:hop(ch));
CC2500_WriteReg(CC2500_25_FSCAL1, calData[ch][2]);
CC2500_WriteReg(CC2500_0A_CHANNR, ch==47? 0:pgm_read_word(&hop_data[ch]));
} }
static void __attribute__((unused)) frskyX_init() static void __attribute__((unused)) frskyX_init()
{ {
CC2500_Reset();
for(uint8_t i=0;i<36;i++) for(uint8_t i=0;i<36;i++)
{ {
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]); uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
@@ -96,20 +90,16 @@ static void __attribute__((unused)) frskyX_init()
for(uint8_t c=0;c < 47;c++) for(uint8_t c=0;c < 47;c++)
{//calibrate hop channels {//calibrate hop channels
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR,pgm_read_word(&hop_data[c])); CC2500_WriteReg(CC2500_0A_CHANNR,hop(c));
CC2500_Strobe(CC2500_SCAL); CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900);// delayMicroseconds(900);//
calData[c][0] = CC2500_ReadReg(CC2500_23_FSCAL3); calData[c] = CC2500_ReadReg(CC2500_25_FSCAL1);
calData[c][1] = CC2500_ReadReg(CC2500_24_FSCAL2);
calData[c][2] = CC2500_ReadReg(CC2500_25_FSCAL1);
} }
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR,0x00); CC2500_WriteReg(CC2500_0A_CHANNR,0x00);
CC2500_Strobe(CC2500_SCAL); CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900); delayMicroseconds(900);
calData[47][0] = CC2500_ReadReg(CC2500_23_FSCAL3); calData[47] = CC2500_ReadReg(CC2500_25_FSCAL1);
calData[47][1] = CC2500_ReadReg(CC2500_24_FSCAL2);
calData[47][2] = CC2500_ReadReg(CC2500_25_FSCAL1);
//#######END INIT######## //#######END INIT########
} }
@@ -158,11 +148,11 @@ static void __attribute__((unused)) frskyX_build_bind_packet()
packet[4] = rx_tx_addr[2]; packet[4] = rx_tx_addr[2];
int idx = ((state -FRSKY_BIND) % 10) * 5; int idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx; packet[5] = idx;
packet[6] = pgm_read_word(&hop_data[idx++]); packet[6] = hop(idx++);
packet[7] = pgm_read_word(&hop_data[idx++]); packet[7] = hop(idx++);
packet[8] = pgm_read_word(&hop_data[idx++]); packet[8] = hop(idx++);
packet[9] = pgm_read_word(&hop_data[idx++]); packet[9] = hop(idx++);
packet[10] = pgm_read_word(&hop_data[idx++]); packet[10] = hop(idx++);
packet[11] = 0x02; packet[11] = 0x02;
packet[12] = RX_num; packet[12] = RX_num;
// //
@@ -188,13 +178,13 @@ static void __attribute__((unused)) frskyX_data_frame()
packet[2] = rx_tx_addr[2]; packet[2] = rx_tx_addr[2];
packet[3] = 0x02; packet[3] = 0x02;
// //
packet[4] = (ctr<<6)+channr; packet[4] = (ctr<<6)+hopping_frequency_no;
packet[5] = counter_rst; packet[5] = counter_rst;
packet[6] = RX_num; packet[6] = RX_num;
//FLAGS 00 - standard packet //packet[7] = FLAGS 00 - standard packet
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet //10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
//20 - range check packet //20 - range check packet
packet[7] = FS_flag; packet[7] = 0;
packet[8] = 0; packet[8] = 0;
// //
if ( lpass & 1 ) if ( lpass & 1 )
@@ -252,7 +242,7 @@ uint16_t ReadFrSkyX()
return 9000; return 9000;
case FRSKY_BIND_DONE: case FRSKY_BIND_DONE:
initialize_data(0); initialize_data(0);
channr=0; hopping_frequency_no=0;
BIND_DONE; BIND_DONE;
state++; state++;
break; break;
@@ -262,12 +252,11 @@ uint16_t ReadFrSkyX()
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ; prev_option = option ;
} }
LED_ON;
CC2500_SetTxRxMode(TX_EN); CC2500_SetTxRxMode(TX_EN);
set_start(channr); set_start(hopping_frequency_no);
CC2500_SetPower(); CC2500_SetPower();
CC2500_Strobe(CC2500_SFRX); CC2500_Strobe(CC2500_SFRX);
channr = (channr+chanskip)%47; hopping_frequency_no = (hopping_frequency_no+chanskip)%47;
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteData(packet, packet[0]+1); CC2500_WriteData(packet, packet[0]+1);
// //

View File

@@ -35,30 +35,8 @@ enum PktState {
J6PRO_CHAN_4, J6PRO_CHAN_4,
}; };
const uint8_t j6pro_sopcodes[][8] = { const uint8_t PROGMEM j6pro_bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49};
/* Note these are in order transmitted (LSB 1st) */ const uint8_t j6pro_data_code[] = {0x02, 0xf9, 0x93, 0x97, 0x02, 0xfa, 0x5c, 0xe3, 0x01, 0x2b, 0xf1, 0xdb, 0x01, 0x32, 0xbe, 0x6f};
{0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91},
{0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F},
{0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A},
{0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50},
{0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44},
{0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46},
{0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C},
{0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74},
{0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49},
{0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72},
{0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17},
{0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table
{0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above,
{0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped
{0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50},
{0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44},
{0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46},
{0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C},
{0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74},
};
const uint8_t bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49};
const uint8_t data_code[] = {0x02, 0xf9, 0x93, 0x97, 0x02, 0xfa, 0x5c, 0xe3, 0x01, 0x2b, 0xf1, 0xdb, 0x01, 0x32, 0xbe, 0x6f};
static void __attribute__((unused)) j6pro_build_bind_packet() static void __attribute__((unused)) j6pro_build_bind_packet()
{ {
@@ -106,7 +84,7 @@ static void __attribute__((unused)) j6pro_cyrf_init()
CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xee); CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xee);
CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00); CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00);
CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x00); CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x00);
CYRF_ConfigDataCode(data_code, 16); CYRF_ConfigDataCode(j6pro_data_code, 16);
CYRF_WritePreamble(0x023333); CYRF_WritePreamble(0x023333);
CYRF_GetMfgData(cyrfmfg_id); CYRF_GetMfgData(cyrfmfg_id);
@@ -121,7 +99,7 @@ static void __attribute__((unused)) cyrf_bindinit()
CYRF_SetPower(0x28); //Deviation using max power, replaced by bind power... CYRF_SetPower(0x28); //Deviation using max power, replaced by bind power...
CYRF_ConfigRFChannel(0x52); CYRF_ConfigRFChannel(0x52);
CYRF_ConfigSOPCode(bind_sop_code); CYRF_PROGMEM_ConfigSOPCode(j6pro_bind_sop_code);
CYRF_ConfigCRCSeed(0x0000); CYRF_ConfigCRCSeed(0x0000);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a); CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
@@ -144,7 +122,7 @@ static void __attribute__((unused)) cyrf_datainit()
uint16_t crc = (0xff & (cyrfmfg_id[1] - cyrfmfg_id[4] + cyrfmfg_id[5])) | uint16_t crc = (0xff & (cyrfmfg_id[1] - cyrfmfg_id[4] + cyrfmfg_id[5])) |
((0xff & (cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[4] + cyrfmfg_id[5])) << 8); ((0xff & (cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[4] + cyrfmfg_id[5])) << 8);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
CYRF_ConfigSOPCode(j6pro_sopcodes[sop_idx]); CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sop_idx]);
CYRF_ConfigCRCSeed(crc); CYRF_ConfigCRCSeed(crc);
} }

View File

@@ -12,7 +12,7 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>. along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/ */
// compatible with MJX WLH08, X600, X800, H26D // compatible with MJX WLH08, X600, X800, H26D, Eachine E010
// Last sync with hexfet new_protocols/mjxq_nrf24l01.c dated 2016-01-17 // Last sync with hexfet new_protocols/mjxq_nrf24l01.c dated 2016-01-17
#if defined(MJXQ_NRF24L01_INO) #if defined(MJXQ_NRF24L01_INO)
@@ -96,6 +96,7 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
packet[10]=MJXQ_pan_tilt_value(); packet[10]=MJXQ_pan_tilt_value();
// fall through on purpose - no break // fall through on purpose - no break
case WLH08: case WLH08:
case E010:
packet[10] += GET_FLAG(Servo_AUX6, 0x02) //RTH packet[10] += GET_FLAG(Servo_AUX6, 0x02) //RTH
| GET_FLAG(Servo_AUX5, 0x01); //HEADLESS | GET_FLAG(Servo_AUX5, 0x01); //HEADLESS
if (!bind) if (!bind)
@@ -169,12 +170,12 @@ static void __attribute__((unused)) MJXQ_init()
if (sub_protocol == WLH08) if (sub_protocol == WLH08)
memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS); memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS);
else else
if (sub_protocol == H26D) if (sub_protocol == H26D || sub_protocol == E010)
memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS); memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS);
else else
{ {
memcpy(hopping_frequency, "\x0a\x35\x42\x3d", MJXQ_RF_NUM_CHANNELS); memcpy(hopping_frequency, "\x0a\x35\x42\x3d", MJXQ_RF_NUM_CHANNELS);
memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_RF_NUM_CHANNELS); memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_ADDRESS_LENGTH);
} }
@@ -193,6 +194,9 @@ static void __attribute__((unused)) MJXQ_init()
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, MJXQ_PACKET_SIZE); // rx pipe 0 (used only for blue board) NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, MJXQ_PACKET_SIZE); // rx pipe 0 (used only for blue board)
if (sub_protocol == E010)
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250K
else
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower(); NRF24L01_SetPower();
} }
@@ -202,13 +206,20 @@ static void __attribute__((unused)) MJXQ_init2()
if (sub_protocol == H26D) if (sub_protocol == H26D)
memcpy(hopping_frequency, "\x32\x3e\x42\x4e", MJXQ_RF_NUM_CHANNELS); memcpy(hopping_frequency, "\x32\x3e\x42\x4e", MJXQ_RF_NUM_CHANNELS);
else else
if (sub_protocol == WLH08) if (sub_protocol != WLH08 && sub_protocol != E010)
for(uint8_t i=0;i<MJXQ_RF_NUM_CHANNELS;i++) for(uint8_t i=0;i<MJXQ_RF_NUM_CHANNELS;i++)
hopping_frequency[i]=pgm_read_byte_near( &MJXQ_map_rfchan[rx_tx_addr[4]%3][i] ); hopping_frequency[i]=pgm_read_byte_near( &MJXQ_map_rfchan[rx_tx_addr[4]%3][i] );
} }
static void __attribute__((unused)) MJXQ_initialize_txid() static void __attribute__((unused)) MJXQ_initialize_txid()
{ {
if (sub_protocol == E010)
{
rx_tx_addr[0]=0x90;
rx_tx_addr[1]=0x1C;
rx_tx_addr[2]=0x00;
}
else
if (sub_protocol == WLH08) if (sub_protocol == WLH08)
rx_tx_addr[0]&=0xF8; // txid must be multiple of 8 rx_tx_addr[0]&=0xF8; // txid must be multiple of 8
else else

View File

@@ -17,7 +17,8 @@ static void module_reset(void) ;
static void update_led_status(void) ; static void update_led_status(void) ;
static void set_rx_tx_addr(uint32_t id) ; static void set_rx_tx_addr(uint32_t id) ;
uint16_t limit_channel_100(uint8_t ch) ; uint16_t limit_channel_100(uint8_t ch) ;
void initTXSerial( uint8_t speed);
void Serial_write(uint8_t data);
extern void NRF24L01_Reset(void ) ; extern void NRF24L01_Reset(void ) ;
extern void A7105_Reset(void ) ; extern void A7105_Reset(void ) ;

View File

@@ -31,10 +31,10 @@ enum PROTOCOLS
MODE_SERIAL = 0, // Serial commands MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105 MODE_FLYSKY = 1, // =>A7105
MODE_HUBSAN = 2, // =>A7105 MODE_HUBSAN = 2, // =>A7105
MODE_FRSKY = 3, // =>CC2500 MODE_FRSKYD = 3, // =>CC2500
MODE_HISKY = 4, // =>NRF24L01 MODE_HISKY = 4, // =>NRF24L01
MODE_V2X2 = 5, // =>NRF24L01 MODE_V2X2 = 5, // =>NRF24L01
MODE_DSM2 = 6, // =>CYRF6936 MODE_DSM = 6, // =>CYRF6936
MODE_DEVO = 7, // =>CYRF6936 MODE_DEVO = 7, // =>CYRF6936
MODE_YD717 = 8, // =>NRF24L01 MODE_YD717 = 8, // =>NRF24L01
MODE_KN = 9, // =>NRF24L01 MODE_KN = 9, // =>NRF24L01
@@ -52,7 +52,8 @@ enum PROTOCOLS
MODE_SFHSS = 21, // =>CC2500 MODE_SFHSS = 21, // =>CC2500
MODE_J6PRO = 22, // =>CYRF6936 MODE_J6PRO = 22, // =>CYRF6936
MODE_FQ777 = 23, // =>NRF24L01 MODE_FQ777 = 23, // =>NRF24L01
MODE_ASSAN = 24 // =>NRF24L01 MODE_ASSAN = 24, // =>NRF24L01
MODE_FRSKYV = 25 // =>CC2500
}; };
enum Flysky enum Flysky
@@ -67,7 +68,7 @@ enum Hisky
Hisky = 0, Hisky = 0,
HK310 = 1 HK310 = 1
}; };
enum DSM2 enum DSM
{ {
DSM2 = 0, DSM2 = 0,
DSMX = 1 DSMX = 1
@@ -119,7 +120,8 @@ enum MJXQ
WLH08 = 0, WLH08 = 0,
X600 = 1, X600 = 1,
X800 = 2, X800 = 2,
H26D = 3 H26D = 3,
E010 = 4
}; };
enum FRSKYX enum FRSKYX
@@ -144,24 +146,46 @@ struct PPM_Parameters
uint8_t option; uint8_t option;
}; };
//*******************
//*** Timer ***
//*******************
#ifdef XMEGA
#define TIFR1 TCC1.INTFLAGS
#define OCF1A_bm TC1_CCAIF_bm
#define OCR1A TCC1.CCA
#define TCNT1 TCC1.CNT
#define USARTC0.DATA UDR0
#define OCF1B_bm TC1_CCBIF_bm
#define OCR1B TCC1.CCB
#define TCC1.INTCTRLB TIMSK1
#define SET_TIMSK1_OCIE1B TIMSK1 = (TIMSK1 & 0xF3) | 0x04
#define CLR_TIMSK1_OCIE1B TIMSK1 &= 0xF3
#else
#define OCF1A_bm _BV(OCF1A)
#define OCF1B_bm _BV(OCF1B)
#define SET_TIMSK1_OCIE1B TIMSK1 |= _BV(OCIE1B)
#define CLR_TIMSK1_OCIE1B TIMSK1 &=~_BV(OCIE1B)
#endif
//******************* //*******************
//*** Pinouts *** //*** Pinouts ***
//******************* //*******************
#define LED_pin 13 //Promini original led on B5 #define LED_pin 5 //D13 = PB5
#define PPM_pin 3 //PPM-D3 #define BIND_pin 5 //D13 = PB5
#define PPM_pin 3 //D3 = PD3
#ifdef XMEGA #ifdef XMEGA
#define SDI_pin 6 //SDIO-D6 #define SDI_pin 6 //SDIO-D6
#else #else
#define SDI_pin 5 //SDIO-D5 #define SDI_pin 5 //D5 = PD5
#endif #endif
#define SCLK_pin 4 //SCK-D4 #define SCLK_pin 4 //D4 = PD4
#define CS_pin 2 //CS-D2 #define A7105_CS_pin 2 //D2 = PD2
#define SDO_pin 6 //D6 #define SDO_pin 6 //D6 = PD6
#define CC25_CSN_pin 7 #define CC25_CSN_pin 7 //D7 = PD7
#define NRF_CSN_pin 8 #define NRF_CSN_pin 0 //D8 = PB0
#define CYRF_CSN_pin 9 #define CYRF_CSN_pin 1 //D9 = PB1
#define CTRL1 1 //C1 (A1) #define CTRL1_pin 1 //A1 = PC1
#define CTRL2 2 //C2 (A2) #define CTRL2_pin 2 //A2 = PC2
// //
#ifdef XMEGA #ifdef XMEGA
#define CTRL1_on #define CTRL1_on
@@ -176,11 +200,11 @@ struct PPM_Parameters
#endif #endif
// //
#ifdef XMEGA #ifdef XMEGA
#define CS_on PORTD.OUTSET = _BV(4) //D4 #define A7105_CS_on PORTD.OUTSET = _BV(4) //D4
#define CS_off PORTD.OUTCLR = _BV(4) //D4 #define A7105_CS_off PORTD.OUTCLR = _BV(4) //D4
#else #else
#define CS_on PORTD |= _BV(2) //D2 #define A7105_CS_on PORTD |= _BV(2) //D2
#define CS_off PORTD &= ~_BV(2) //D2 #define A7105_CS_off PORTD &= ~_BV(2) //D2
#endif #endif
// //
#ifdef XMEGA #ifdef XMEGA
@@ -200,11 +224,11 @@ struct PPM_Parameters
#endif #endif
// //
#ifdef XMEGA #ifdef XMEGA
#define SDI_1 (PORTD.IN & (1<<SDI_pin)) == (1<<SDI_pin) //D5 #define SDI_1 (PORTD.IN & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (PORTD.IN & (1<<SDI_pin)) == 0x00 //D5 #define SDI_0 (PORTD.IN & _BV(SDI_pin)) == 0x00 //D5
#else #else
#define SDI_1 (PIND & (1<<SDI_pin)) == (1<<SDI_pin) //D5 #define SDI_1 (PIND & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (PIND & (1<<SDI_pin)) == 0x00 //D5 #define SDI_0 (PIND & _BV(SDI_pin)) == 0x00 //D5
#endif #endif
// //
#define SDI_SET_INPUT DDRD &= ~_BV(5) //D5 #define SDI_SET_INPUT DDRD &= ~_BV(5) //D5
@@ -221,9 +245,13 @@ struct PPM_Parameters
#ifdef XMEGA #ifdef XMEGA
#define NRF_CSN_on #define NRF_CSN_on
#define NRF_CSN_off #define NRF_CSN_off
#define NRF_CE_on
#define NRF_CE_off
#else #else
#define NRF_CSN_on PORTB |= _BV(0) //D8 #define NRF_CSN_on PORTB |= _BV(0) //D8
#define NRF_CSN_off PORTB &= ~_BV(0) //D8 #define NRF_CSN_off PORTB &= ~_BV(0) //D8
#define NRF_CE_on
#define NRF_CE_off
#endif #endif
// //
#ifdef XMEGA #ifdef XMEGA
@@ -234,14 +262,15 @@ struct PPM_Parameters
#define CYRF_CSN_off PORTB &= ~_BV(1) //D9 #define CYRF_CSN_off PORTB &= ~_BV(1) //D9
#define CYRF_RST_HI PORTC |= _BV(5) //A5 #define CYRF_RST_HI PORTC |= _BV(5) //A5
#define CYRF_RST_LO PORTC &= ~_BV(5) //A5 #define CYRF_RST_LO PORTC &= ~_BV(5) //A5
#define CYRF_RST_pin 5
#endif #endif
// //
#ifdef XMEGA #ifdef XMEGA
#define SDO_1 (PORTD.IN & (1<<SDO_pin)) == (1<<SDO_pin) //D6 #define SDO_1 (PORTD.IN & _BV(SDO_pin)) == _BV(SDO_pin) //D6
#define SDO_0 (PORTD.IN & (1<<SDO_pin)) == 0x00 //D6 #define SDO_0 (PORTD.IN & _BV(SDO_pin)) == 0x00 //D6
#else #else
#define SDO_1 (PIND & (1<<SDO_pin)) == (1<<SDO_pin) //D6 #define SDO_1 (PIND & _BV(SDO_pin)) == _BV(SDO_pin) //D6
#define SDO_0 (PIND & (1<<SDO_pin)) == 0x00 //D6 #define SDO_0 (PIND & _BV(SDO_pin)) == 0x00 //D6
#endif #endif
// //
// //
@@ -261,11 +290,28 @@ struct PPM_Parameters
#define IS_LED_on ( (PORTB & _BV(5)) != 0x00 ) #define IS_LED_on ( (PORTB & _BV(5)) != 0x00 )
#endif #endif
//BIND
#ifdef XMEGA
#define IS_BIND_BUTTON_on ( (PORTD.IN & _BV(2)) == 0x00 )
#else
#define BIND_SET_INPUT DDRB &= ~_BV(5)
#define BIND_SET_PULLUP PORTB |= _BV(5)
#define IS_BIND_BUTTON_on ( (PINB & _BV(5)) == 0x00 )
#define BIND_SET_OUTPUT DDRB |= _BV(5)
#endif
// TX // TX
#define TX_ON PORTD |= _BV(1) #ifdef DEBUG_TX
#define TX_OFF PORTD &= ~_BV(1) #define TX_ON PORTD |= _BV(1)
#define TX_TOGGLE PORTD ^= _BV(1) #define TX_OFF PORTD &= ~_BV(1)
#define TX_SET_OUTPUT DDRD |= _BV(1) #define TX_TOGGLE PORTD ^= _BV(1)
#define TX_SET_OUTPUT DDRD |= _BV(1)
#else
#define TX_ON
#define TX_OFF
#define TX_TOGGLE
#define TX_SET_OUTPUT
#endif
// Macros // Macros
#define NOP() __asm__ __volatile__("nop") #define NOP() __asm__ __volatile__("nop")
@@ -318,6 +364,16 @@ struct PPM_Parameters
#define RX_MISSED_BUFF_on protocol_flags2 |= _BV(2) #define RX_MISSED_BUFF_on protocol_flags2 |= _BV(2)
#define IS_RX_MISSED_BUFF_on ( ( protocol_flags2 & _BV(2) ) !=0 ) #define IS_RX_MISSED_BUFF_on ( ( protocol_flags2 & _BV(2) ) !=0 )
#define TX_MAIN_PAUSE_off protocol_flags2 &= ~_BV(3)
#define TX_MAIN_PAUSE_on protocol_flags2 |= _BV(3)
#define IS_TX_MAIN_PAUSE_on ( ( protocol_flags2 & _BV(3) ) !=0 )
#define TX_RX_PAUSE_off protocol_flags2 &= ~_BV(4)
#define TX_RX_PAUSE_on protocol_flags2 |= _BV(4)
#define IS_TX_RX_PAUSE_on ( ( protocol_flags2 & _BV(4) ) !=0 )
#define IS_TX_PAUSE_on ( ( protocol_flags2 & (_BV(4)|_BV(3)) ) !=0 )
#define BLINK_BIND_TIME 100 #define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500 #define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000 #define BLINK_BAD_PROTO_TIME_LOW 1000
@@ -425,7 +481,7 @@ enum CYRF_POWER
#define CYRF_HIGH_POWER CYRF_POWER_7 #define CYRF_HIGH_POWER CYRF_POWER_7
#define CYRF_LOW_POWER CYRF_POWER_3 #define CYRF_LOW_POWER CYRF_POWER_3
#define CYRF_RANGE_POWER CYRF_POWER_1 // 1/30 of the full power distance #define CYRF_RANGE_POWER CYRF_POWER_1 // 1/30 of the full power distance
#define CYRF_BIND_POWER CYRF_POWER_1 #define CYRF_BIND_POWER CYRF_POWER_0
enum TXRX_State { enum TXRX_State {
TXRX_OFF, TXRX_OFF,
@@ -460,10 +516,10 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
=> Reserved 0 => Reserved 0
Flysky 1 Flysky 1
Hubsan 2 Hubsan 2
Frsky 3 FrskyD 3
Hisky 4 Hisky 4
V2x2 5 V2x2 5
DSM2 6 DSM 6
Devo 7 Devo 7
YD717 8 YD717 8
KN 9 KN 9
@@ -482,6 +538,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
J6PRO 22 J6PRO 22
FQ777 23 FQ777 23
ASSAN 24 ASSAN 24
FrskyV 25
BindBit=> 0x80 1=Bind/0=No BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No RangeCheck=> 0x20 1=Yes /0=No
@@ -496,7 +553,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
sub_protocol==Hisky sub_protocol==Hisky
Hisky 0 Hisky 0
HK310 1 HK310 1
sub_protocol==DSM2 sub_protocol==DSM
DSM2 0 DSM2 0
DSMX 1 DSMX 1
sub_protocol==YD717 sub_protocol==YD717
@@ -534,6 +591,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
X600 1 X600 1
X800 2 X800 2
H26D 3 H26D 3
E010 4
sub_protocol==FRSKYX sub_protocol==FRSKYX
CH_16 0 CH_16 0
CH_8 1 CH_8 1

View File

@@ -22,14 +22,17 @@
*/ */
#include <avr/eeprom.h> #include <avr/eeprom.h>
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#include "Multiprotocol.h"
//#define DEBUG_TX //#define DEBUG_TX
#include "Multiprotocol.h"
//Multiprotocol module configuration file //Multiprotocol module configuration file
#include "_Config.h" #include "_Config.h"
#include "TX_Def.h" #include "TX_Def.h"
#ifdef XMEGA
#undef ENABLE_PPM // Disable PPM for orange module
#endif
//Global constants/variables //Global constants/variables
uint32_t MProtocol_id;//tx id, uint32_t MProtocol_id;//tx id,
uint32_t MProtocol_id_master; uint32_t MProtocol_id_master;
@@ -65,19 +68,21 @@ uint8_t rf_ch_num;
uint8_t throttle, rudder, elevator, aileron; uint8_t throttle, rudder, elevator, aileron;
uint8_t flags; uint8_t flags;
uint16_t crc; uint16_t crc;
uint8_t crc8;
uint16_t seed;
// //
uint16_t state; uint16_t state;
uint8_t len; uint8_t len;
uint8_t RX_num; uint8_t RX_num;
#if defined(FRSKYX_CC2500_INO) || defined(SFHSS_CC2500_INO) #if defined(FRSKYX_CC2500_INO) || defined(SFHSS_CC2500_INO)
uint8_t calData[48][3]; uint8_t calData[48];
#endif #endif
//Channel mapping for protocols //Channel mapping for protocols
const uint8_t CH_AETR[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; const uint8_t CH_AETR[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
//const uint8_t CH_TAER[]={THROTTLE, AILERON, ELEVATOR, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; const uint8_t CH_TAER[]={THROTTLE, AILERON, ELEVATOR, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
//const uint8_t CH_RETA[]={RUDDER, ELEVATOR, THROTTLE, AILERON, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; const uint8_t CH_RETA[]={RUDDER, ELEVATOR, THROTTLE, AILERON, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
const uint8_t CH_EATR[]={ELEVATOR, AILERON, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8}; const uint8_t CH_EATR[]={ELEVATOR, AILERON, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
// Mode_select variables // Mode_select variables
@@ -99,7 +104,7 @@ volatile uint16_t PPM_data[NUM_CHN];
volatile uint8_t rx_buff[RXBUFFER_SIZE]; volatile uint8_t rx_buff[RXBUFFER_SIZE];
volatile uint8_t rx_ok_buff[RXBUFFER_SIZE]; volatile uint8_t rx_ok_buff[RXBUFFER_SIZE];
#ifndef BASH_SERIAL #ifndef BASH_SERIAL
volatile uint8_t tx_buff[TXBUFFER_SIZE]; volatile uint8_t tx_buff[TXBUFFER_SIZE];
#endif #endif
volatile uint8_t discard_frame = 0; volatile uint8_t discard_frame = 0;
@@ -113,6 +118,7 @@ uint8_t prev_protocol=0;
#define MAX_PKT 27 #define MAX_PKT 27
uint8_t pkt[MAX_PKT];//telemetry receiving packets uint8_t pkt[MAX_PKT];//telemetry receiving packets
#if defined(TELEMETRY) #if defined(TELEMETRY)
uint8_t pass = 0;
uint8_t pktt[MAX_PKT];//telemetry receiving packets uint8_t pktt[MAX_PKT];//telemetry receiving packets
#ifndef BASH_SERIAL #ifndef BASH_SERIAL
volatile uint8_t tx_head=0; volatile uint8_t tx_head=0;
@@ -128,12 +134,12 @@ uint8_t pkt[MAX_PKT];//telemetry receiving packets
// Callback // Callback
typedef uint16_t (*void_function_t) (void);//pointer to a function with no parameters which return an uint16_t integer typedef uint16_t (*void_function_t) (void);//pointer to a function with no parameters which return an uint16_t integer
void_function_t remote_callback = 0; void_function_t remote_callback = 0;
static void CheckTimer(uint16_t (*cb)(void));
// Init // Init
void setup() void setup()
{ {
#ifdef XMEGA #ifdef XMEGA
// General pinout
PORTD.OUTSET = 0x17 ; PORTD.OUTSET = 0x17 ;
PORTD.DIRSET = 0xB2 ; PORTD.DIRSET = 0xB2 ;
PORTD.DIRCLR = 0x4D ; PORTD.DIRCLR = 0x4D ;
@@ -146,18 +152,33 @@ void setup()
for ( uint8_t count = 0 ; count < 20 ; count += 1 ) for ( uint8_t count = 0 ; count < 20 ; count += 1 )
asm("nop") ; asm("nop") ;
PORTE.OUTCLR = 0x01 ; PORTE.OUTCLR = 0x01 ;
#else
// Timer1 config
// TCC1 16-bit timer, clocked at 0.5uS
EVSYS.CH3MUX = 0x80 + 0x04 ; // Prescaler of 16
TCC1.CTRLB = 0; TCC1.CTRLC = 0; TCC1.CTRLD = 0; TCC1.CTRLE = 0;
TCC1.INTCTRLA = 0; TIMSK1 = 0;
TCC1.PER = 0xFFFF ;
TCNT1 = 0 ;
TCC1.CTRLA = 0x0B ; // Event3 (prescale of 16)
#else
// General pinout // General pinout
DDRD = (1<<CS_pin)|(1<<SDI_pin)|(1<<SCLK_pin)|(1<<CS_pin)|(1<< CC25_CSN_pin); DDRD = _BV(A7105_CS_pin)|_BV(SDI_pin)|_BV(SCLK_pin)|_BV( CC25_CSN_pin);//pin output
DDRC = (1<<CTRL1)|(1<<CTRL2); //output DDRC = _BV(CTRL1_pin)|_BV(CTRL2_pin)|_BV(CYRF_RST_pin); //pin output
//DDRC |= (1<<5);//RST pin A5(C5) CYRF output DDRB = _BV(NRF_CSN_pin)|_BV(CYRF_CSN_pin); //pin output
DDRB = _BV(0)|_BV(1); PORTB = _BV(2)|_BV(3)|_BV(4)|_BV(BIND_pin); //pullup on dial (D10=PB2,D11=PB3,D12=PB4) and bind button
PORTB = _BV(2)|_BV(3)|_BV(4)|_BV(5);//pullup 10,11,12 and bind button PORTC = _BV(0); //pullup on dial (A0=PC0)
PORTC = _BV(0);//A0 high pullup #ifdef DEBUG_TX
#endif TX_SET_OUTPUT;
#endif
// Timer1 config
TCCR1A = 0;
TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer
#endif
// Set Chip selects // Set Chip selects
CS_on; A7105_CS_on;
CC25_CSN_on; CC25_CSN_on;
NRF_CSN_on; NRF_CSN_on;
CYRF_CSN_on; CYRF_CSN_on;
@@ -165,52 +186,28 @@ void setup()
SDI_on; SDI_on;
SCK_off; SCK_off;
//#ifdef XMEGA
// // SPI enable, master, prescale of 16
// SPID.CTRL = SPI_ENABLE_bm | SPI_MASTER_bm | SPI_PRESCALER0_bm ;
//#endif
// Timer1 config
#ifdef XMEGA
// TCC1 16-bit timer, clocked at 0.5uS
EVSYS.CH3MUX = 0x80 + 0x04 ; // Prescaler of 16
TCC1.CTRLB = 0; TCC1.CTRLC = 0; TCC1.CTRLD = 0; TCC1.CTRLE = 0;
TCC1.INTCTRLA = 0; TCC1.INTCTRLB = 0;
TCC1.PER = 0xFFFF ;
TCC1.CNT = 0 ;
TCC1.CTRLA = 0x0B ; // Event3 (prescale of 16)
#else
TCCR1A = 0;
TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer
#endif
// Set servos positions // Set servos positions
for(uint8_t i=0;i<NUM_CHN;i++) for(uint8_t i=0;i<NUM_CHN;i++)
Servo_data[i]=1500; Servo_data[i]=1500;
Servo_data[THROTTLE]=servo_min_100; Servo_data[THROTTLE]=servo_min_100;
#ifdef ENABLE_PPM #ifdef ENABLE_PPM
memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data)); memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data));
#endif #endif
//Wait for every component to start //Wait for every component to start
delayMilliseconds(100); delayMilliseconds(100);
// Read status of bind button // Read status of bind button
#ifdef XMEGA if( IS_BIND_BUTTON_on )
if( (PORTD.IN & _BV(2)) == 0x00 )
#else
if( (PINB & _BV(5)) == 0x00 )
#endif
BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan
// Read status of mode select binary switch // Read status of mode select binary switch
// after this mode_select will be one of {0000, 0001, ..., 1111} // after this mode_select will be one of {0000, 0001, ..., 1111}
#ifdef XMEGA #ifndef ENABLE_PPM
mode_select=0x0F - ( PORTA.IN & 0x0F ) ; //encoder dip switches 1,2,4,8=>B2,B3,B4,C0 mode_select = MODE_SERIAL ; // force serial mode
mode_select = MODE_SERIAL ; #else
#else
mode_select=0x0F - ( ( (PINB>>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0 mode_select=0x0F - ( ( (PINB>>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0
#endif #endif
// Update LED // Update LED
LED_OFF; LED_OFF;
@@ -220,18 +217,7 @@ void setup()
MProtocol_id_master=random_id(10,false); MProtocol_id_master=random_id(10,false);
//Init RF modules //Init RF modules
#ifdef CC2500_INSTALLED modules_reset();
CC2500_Reset();
#endif
#ifdef A7105_INSTALLED
A7105_Reset();
#endif
#ifdef CYRF6936_INSTALLED
CYRF_Reset();
#endif
#ifdef NFR24L01_INSTALLED
NRF24L01_Reset();
#endif
#ifdef ENABLE_PPM #ifdef ENABLE_PPM
//Protocol and interrupts initialization //Protocol and interrupts initialization
@@ -251,34 +237,89 @@ void setup()
protocol_init(); protocol_init();
#ifndef XMEGA
//Configure PPM interrupt //Configure PPM interrupt
EICRA |=(1<<ISC11); // The rising edge of INT1 pin D3 generates an interrupt request EICRA |=_BV(ISC11); // The rising edge of INT1 pin D3 generates an interrupt request
EIMSK |= (1<<INT1); // INT1 interrupt enable EIMSK |= _BV(INT1); // INT1 interrupt enable
#endif
#if defined(TELEMETRY) #if defined(TELEMETRY)
PPM_Telemetry_serial_init(); // Configure serial for telemetry PPM_Telemetry_serial_init(); // Configure serial for telemetry
#endif #endif
} }
else else
#endif //ENABLE_PPM #endif //ENABLE_PPM
{ // Serial { // Serial
#ifdef ENABLE_SERIAL #ifdef ENABLE_SERIAL
cur_protocol[0]=0; cur_protocol[0]=0;
cur_protocol[1]=0; cur_protocol[1]=0;
prev_protocol=0; prev_protocol=0;
servo_max_100=SERIAL_MAX_100; servo_min_100=SERIAL_MIN_100; servo_max_100=SERIAL_MAX_100; servo_min_100=SERIAL_MIN_100;
servo_max_125=SERIAL_MAX_125; servo_min_125=SERIAL_MIN_125; servo_max_125=SERIAL_MAX_125; servo_min_125=SERIAL_MIN_125;
Mprotocol_serial_init(); // Configure serial and enable RX interrupt Mprotocol_serial_init(); // Configure serial and enable RX interrupt
#endif //ENABLE_SERIAL #endif //ENABLE_SERIAL
} }
} }
// Main // Main
// Protocol scheduler
void loop() void loop()
{ {
#ifdef ENABLE_SERIAL uint16_t next_callback,diff=0xFFFF;
while(1)
{
if(remote_callback==0 || diff>2*200)
{
do
{
Update_All();
}
while(remote_callback==0);
}
if( (TIFR1 & OCF1A_bm) != 0)
{
cli(); // Disable global int due to RW of 16 bits registers
OCR1A=TCNT1; // Callback should already have been called... Use "now" as new sync point.
sei(); // Enable global int
}
else
while((TIFR1 & OCF1A_bm) == 0); // Wait before callback
do
{
TX_ON;
TX_MAIN_PAUSE_on;
tx_pause();
next_callback=remote_callback();
TX_MAIN_PAUSE_off;
tx_resume();
TX_OFF;
while(next_callback>4000)
{ // start to wait here as much as we can...
next_callback-=2000; // We will wait below for 2ms
cli(); // Disable global int due to RW of 16 bits registers
OCR1A += 2000*2 ; // set compare A for callback
TIFR1=OCF1A_bm; // clear compare A=callback flag
sei(); // enable global int
Update_All();
if(IS_CHANGE_PROTOCOL_FLAG_on)
break; // Protocol has been changed
while((TIFR1 & OCF1A_bm) == 0); // wait 2ms...
}
// at this point we have a maximum of 4ms in next_callback
next_callback *= 2 ;
cli(); // Disable global int due to RW of 16 bits registers
OCR1A+= next_callback ; // set compare A for callback
TIFR1=OCF1A_bm; // clear compare A=callback flag
diff=OCR1A-TCNT1; // compare timer and comparator
sei(); // enable global int
}
while(diff&0x8000); // Callback did not took more than requested time for next callback
// so we can launch Update_All before next callback
}
}
void Update_All()
{
#ifdef ENABLE_SERIAL
if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received
{ {
update_serial_data(); // Update protocol and data update_serial_data(); // Update protocol and data
@@ -286,13 +327,12 @@ void loop()
if(IS_CHANGE_PROTOCOL_FLAG_on) if(IS_CHANGE_PROTOCOL_FLAG_on)
{ // Protocol needs to be changed { // Protocol needs to be changed
LED_OFF; //led off during protocol init LED_OFF; //led off during protocol init
module_reset(); //reset previous module modules_reset(); //reset all modules
protocol_init(); //init new protocol protocol_init(); //init new protocol
CHANGE_PROTOCOL_FLAG_off; //done
} }
} }
#endif //ENABLE_SERIAL #endif //ENABLE_SERIAL
#ifdef ENABLE_PPM #ifdef ENABLE_PPM
if(mode_select!=MODE_SERIAL && IS_PPM_FLAG_on) // PPM mode and a full frame has been received if(mode_select!=MODE_SERIAL && IS_PPM_FLAG_on) // PPM mode and a full frame has been received
{ {
for(uint8_t i=0;i<NUM_CHN;i++) for(uint8_t i=0;i<NUM_CHN;i++)
@@ -308,14 +348,13 @@ void loop()
update_aux_flags(); update_aux_flags();
PPM_FLAG_off; // wait for next frame before update PPM_FLAG_off; // wait for next frame before update
} }
#endif //ENABLE_PPM #endif //ENABLE_PPM
update_led_status(); update_led_status();
#if defined(TELEMETRY) #if defined(TELEMETRY)
if( ((cur_protocol[0]&0x1F)==MODE_FRSKY) || ((cur_protocol[0]&0x1F)==MODE_HUBSAN) || ((cur_protocol[0]&0x1F)==MODE_FRSKYX) || ((cur_protocol[0]&0x1F)==MODE_DSM2) ) uint8_t protocol=cur_protocol[0]&0x1F;
frskyUpdate(); if( (protocol==MODE_FRSKYD) || (protocol==MODE_HUBSAN) || (protocol==MODE_FRSKYX) || (protocol==MODE_DSM) )
TelemetryUpdate();
#endif #endif
if (remote_callback != 0)
CheckTimer(remote_callback);
} }
// Update Servo_AUX flags based on servo AUX positions // Update Servo_AUX flags based on servo AUX positions
@@ -332,7 +371,7 @@ static void update_led_status(void)
{ {
if(blink<millis()) if(blink<millis())
{ {
if(cur_protocol[0]==0) // No valid serial received at least once if(cur_protocol[0]==0) //No valid serial received at least once
blink+=BLINK_SERIAL_TIME; //blink slowly while waiting a valid serial input blink+=BLINK_SERIAL_TIME; //blink slowly while waiting a valid serial input
else else
if(remote_callback == 0) if(remote_callback == 0)
@@ -351,67 +390,33 @@ static void update_led_status(void)
} }
} }
// Protocol scheduler inline void tx_pause()
static void CheckTimer(uint16_t (*cb)(void))
{ {
uint16_t next_callback,diff; #ifdef TELEMETRY
#ifdef XMEGA #ifdef XMEGA
if( (TCC1.INTFLAGS & TC1_CCAIF_bm) != 0) USARTC0.CTRLA &= ~0x03 ; // Pause telemetry by disabling transmitter interrupt
#else
#ifndef BASH_SERIAL
UCSR0B &= ~_BV(UDRIE0); // Pause telemetry by disabling transmitter interrupt
#endif
#endif
#endif
}
inline void tx_resume()
{
#ifdef TELEMETRY
if(!IS_TX_PAUSE_on)
{ {
cli(); // Disable global int due to RW of 16 bits registers #ifdef XMEGA
TCC1.CCA = TCC1.CNT ; // Callback should already have been called... Use "now" as new sync point. USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ; // Resume telemetry by enabling transmitter interrupt
sei(); // Enable global int #else
#ifndef BASH_SERIAL
UCSR0B |= _BV(UDRIE0); // Resume telemetry by enabling transmitter interrupt
#endif
#endif
} }
else #endif
while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait before callback
#else
if( (TIFR1 & (1<<OCF1A)) != 0)
{
cli(); // Disable global int due to RW of 16 bits registers
OCR1A=TCNT1; // Callback should already have been called... Use "now" as new sync point.
sei(); // Enable global int
}
else
while((TIFR1 & (1<<OCF1A)) == 0); // Wait before callback
#endif
do
{
next_callback=cb();
while(next_callback>4000)
{ // start to wait here as much as we can...
next_callback-=2000; // We will wait below for 2ms
#ifdef XMEGA
cli(); // Disable global int due to RW of 16 bits registers
TCC1.CCA +=2000*2; // set compare A for callback
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag
sei(); // enable global int
while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait 2ms...
#else
cli(); // Disable global int due to RW of 16 bits registers
OCR1A = OCR1A + 2000*2 ; // set compare A for callback
TIFR1=(1<<OCF1A); // clear compare A=callback flag
sei(); // enable global int
while((TIFR1 & (1<<OCF1A)) == 0); // wait 2ms...
#endif
}
// at this point we have a maximum of 4ms in next_callback
next_callback *= 2 ;
#ifdef XMEGA
cli(); // Disable global int due to RW of 16 bits registers
TCC1.CCA +=next_callback; // set compare A for callback
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag
diff=TCC1.CCA-TCC1.CNT; // compare timer and comparator
sei(); // enable global int
#else
cli(); // Disable global int due to RW of 16 bits registers
OCR1A+= next_callback ; // set compare A for callback
TIFR1=(1<<OCF1A); // clear compare A=callback flag
diff=OCR1A-TCNT1; // compare timer and comparator
sei(); // enable global int
#endif
}
while(diff&0x8000); // Callback did not took more than requested time for next callback
// so we can let main do its stuff before next callback
} }
// Protocol start // Protocol start
@@ -420,7 +425,19 @@ static void protocol_init()
uint16_t next_callback=0; // Default is immediate call back uint16_t next_callback=0; // Default is immediate call back
remote_callback = 0; remote_callback = 0;
set_rx_tx_addr(MProtocol_id); set_rx_tx_addr(MProtocol_id); // Reset rx_tx_addr
// reset telemetry
#ifdef TELEMETRY
tx_pause();
pass=0;
telemetry_link=0;
#ifndef BASH_SERIAL
tx_tail=0;
tx_head=0;
#endif
#endif
blink=millis(); blink=millis();
if(IS_BIND_BUTTON_FLAG_on) if(IS_BIND_BUTTON_FLAG_on)
AUTOBIND_FLAG_on; AUTOBIND_FLAG_on;
@@ -434,163 +451,186 @@ static void protocol_init()
switch(cur_protocol[0]&0x1F) // Init the requested protocol switch(cur_protocol[0]&0x1F) // Init the requested protocol
{ {
#if defined(FLYSKY_A7105_INO) #if defined(FLYSKY_A7105_INO)
case MODE_FLYSKY: case MODE_FLYSKY:
CTRL1_off; //antenna RF1 CTRL1_off; //antenna RF1
next_callback = initFlySky(); next_callback = initFlySky();
remote_callback = ReadFlySky; remote_callback = ReadFlySky;
break; break;
#endif #endif
#if defined(HUBSAN_A7105_INO) #if defined(HUBSAN_A7105_INO)
case MODE_HUBSAN: case MODE_HUBSAN:
CTRL1_off; //antenna RF1 CTRL1_off; //antenna RF1
if(IS_BIND_BUTTON_FLAG_on) random_id(10,true); // Generate new ID if bind button is pressed. if(IS_BIND_BUTTON_FLAG_on) random_id(10,true); // Generate new ID if bind button is pressed.
next_callback = initHubsan(); next_callback = initHubsan();
remote_callback = ReadHubsan; remote_callback = ReadHubsan;
break; break;
#endif #endif
#if defined(FRSKY_CC2500_INO) #if defined(FRSKYD_CC2500_INO)
case MODE_FRSKY: case MODE_FRSKYD:
CTRL1_off; //antenna RF2 CTRL1_off; //antenna RF2
CTRL2_on; CTRL2_on;
next_callback = initFrSky_2way(); next_callback = initFrSky_2way();
remote_callback = ReadFrSky_2way; remote_callback = ReadFrSky_2way;
break; break;
#endif #endif
#if defined(FRSKYX_CC2500_INO) #if defined(FRSKYV_CC2500_INO)
case MODE_FRSKYV:
CTRL1_off; //antenna RF2
CTRL2_on;
next_callback = initFRSKYV();
remote_callback = ReadFRSKYV;
break;
#endif
#if defined(FRSKYX_CC2500_INO)
case MODE_FRSKYX: case MODE_FRSKYX:
CTRL1_off; //antenna RF2 CTRL1_off; //antenna RF2
CTRL2_on; CTRL2_on;
next_callback = initFrSkyX(); next_callback = initFrSkyX();
remote_callback = ReadFrSkyX; remote_callback = ReadFrSkyX;
break; break;
#endif #endif
#if defined(SFHSS_CC2500_INO) #if defined(SFHSS_CC2500_INO)
case MODE_SFHSS: case MODE_SFHSS:
CTRL1_off; //antenna RF2 CTRL1_off; //antenna RF2
CTRL2_on; CTRL2_on;
next_callback = initSFHSS(); next_callback = initSFHSS();
remote_callback = ReadSFHSS; remote_callback = ReadSFHSS;
break; break;
#endif #endif
#if defined(DSM2_CYRF6936_INO) #if defined(DSM_CYRF6936_INO)
case MODE_DSM2: case MODE_DSM:
CTRL2_on; //antenna RF4 CTRL2_on; //antenna RF4
next_callback = initDsm2(); next_callback = initDsm();
//Servo_data[2]=1500;//before binding //Servo_data[2]=1500;//before binding
remote_callback = ReadDsm2; remote_callback = ReadDsm;
break; break;
#endif #endif
#if defined(DEVO_CYRF6936_INO) #if defined(DEVO_CYRF6936_INO)
case MODE_DEVO: case MODE_DEVO:
#ifdef ENABLE_PPM
if(mode_select) //PPM mode
{
if(IS_BIND_BUTTON_FLAG_on)
{
eeprom_write_byte((uint8_t*)(30+mode_select),0x00); // reset to autobind mode for the current model
option=0;
}
else
{
option=eeprom_read_byte((uint8_t*)(30+mode_select)); // load previous mode: autobind or fixed id
if(option!=1) option=0; // if not fixed id mode then it should be autobind
}
}
#endif //ENABLE_PPM
CTRL2_on; //antenna RF4 CTRL2_on; //antenna RF4
next_callback = DevoInit(); next_callback = DevoInit();
remote_callback = devo_callback; remote_callback = devo_callback;
break; break;
#endif #endif
#if defined(J6PRO_CYRF6936_INO) #if defined(J6PRO_CYRF6936_INO)
case MODE_J6PRO: case MODE_J6PRO:
CTRL2_on; //antenna RF4 CTRL2_on; //antenna RF4
next_callback = initJ6Pro(); next_callback = initJ6Pro();
remote_callback = ReadJ6Pro; remote_callback = ReadJ6Pro;
break; break;
#endif #endif
#if defined(HISKY_NRF24L01_INO) #if defined(HISKY_NRF24L01_INO)
case MODE_HISKY: case MODE_HISKY:
next_callback=initHiSky(); next_callback=initHiSky();
remote_callback = hisky_cb; remote_callback = hisky_cb;
break; break;
#endif #endif
#if defined(V2X2_NRF24L01_INO) #if defined(V2X2_NRF24L01_INO)
case MODE_V2X2: case MODE_V2X2:
next_callback = initV2x2(); next_callback = initV2x2();
remote_callback = ReadV2x2; remote_callback = ReadV2x2;
break; break;
#endif #endif
#if defined(YD717_NRF24L01_INO) #if defined(YD717_NRF24L01_INO)
case MODE_YD717: case MODE_YD717:
next_callback=initYD717(); next_callback=initYD717();
remote_callback = yd717_callback; remote_callback = yd717_callback;
break; break;
#endif #endif
#if defined(KN_NRF24L01_INO) #if defined(KN_NRF24L01_INO)
case MODE_KN: case MODE_KN:
next_callback = initKN(); next_callback = initKN();
remote_callback = kn_callback; remote_callback = kn_callback;
break; break;
#endif #endif
#if defined(SYMAX_NRF24L01_INO) #if defined(SYMAX_NRF24L01_INO)
case MODE_SYMAX: case MODE_SYMAX:
next_callback = initSymax(); next_callback = initSymax();
remote_callback = symax_callback; remote_callback = symax_callback;
break; break;
#endif #endif
#if defined(SLT_NRF24L01_INO) #if defined(SLT_NRF24L01_INO)
case MODE_SLT: case MODE_SLT:
next_callback=initSLT(); next_callback=initSLT();
remote_callback = SLT_callback; remote_callback = SLT_callback;
break; break;
#endif #endif
#if defined(CX10_NRF24L01_INO) #if defined(CX10_NRF24L01_INO)
case MODE_CX10: case MODE_CX10:
next_callback=initCX10(); next_callback=initCX10();
remote_callback = CX10_callback; remote_callback = CX10_callback;
break; break;
#endif #endif
#if defined(CG023_NRF24L01_INO) #if defined(CG023_NRF24L01_INO)
case MODE_CG023: case MODE_CG023:
next_callback=initCG023(); next_callback=initCG023();
remote_callback = CG023_callback; remote_callback = CG023_callback;
break; break;
#endif #endif
#if defined(BAYANG_NRF24L01_INO) #if defined(BAYANG_NRF24L01_INO)
case MODE_BAYANG: case MODE_BAYANG:
next_callback=initBAYANG(); next_callback=initBAYANG();
remote_callback = BAYANG_callback; remote_callback = BAYANG_callback;
break; break;
#endif #endif
#if defined(ESKY_NRF24L01_INO) #if defined(ESKY_NRF24L01_INO)
case MODE_ESKY: case MODE_ESKY:
next_callback=initESKY(); next_callback=initESKY();
remote_callback = ESKY_callback; remote_callback = ESKY_callback;
break; break;
#endif #endif
#if defined(MT99XX_NRF24L01_INO) #if defined(MT99XX_NRF24L01_INO)
case MODE_MT99XX: case MODE_MT99XX:
next_callback=initMT99XX(); next_callback=initMT99XX();
remote_callback = MT99XX_callback; remote_callback = MT99XX_callback;
break; break;
#endif #endif
#if defined(MJXQ_NRF24L01_INO) #if defined(MJXQ_NRF24L01_INO)
case MODE_MJXQ: case MODE_MJXQ:
next_callback=initMJXQ(); next_callback=initMJXQ();
remote_callback = MJXQ_callback; remote_callback = MJXQ_callback;
break; break;
#endif #endif
#if defined(SHENQI_NRF24L01_INO) #if defined(SHENQI_NRF24L01_INO)
case MODE_SHENQI: case MODE_SHENQI:
next_callback=initSHENQI(); next_callback=initSHENQI();
remote_callback = SHENQI_callback; remote_callback = SHENQI_callback;
break; break;
#endif #endif
#if defined(FY326_NRF24L01_INO) #if defined(FY326_NRF24L01_INO)
case MODE_FY326: case MODE_FY326:
next_callback=initFY326(); next_callback=initFY326();
remote_callback = FY326_callback; remote_callback = FY326_callback;
break; break;
#endif #endif
#if defined(FQ777_NRF24L01_INO) #if defined(FQ777_NRF24L01_INO)
case MODE_FQ777: case MODE_FQ777:
next_callback=initFQ777(); next_callback=initFQ777();
remote_callback = FQ777_callback; remote_callback = FQ777_callback;
break; break;
#endif #endif
#if defined(ASSAN_NRF24L01_INO) #if defined(ASSAN_NRF24L01_INO)
case MODE_ASSAN: case MODE_ASSAN:
next_callback=initASSAN(); next_callback=initASSAN();
remote_callback = ASSAN_callback; remote_callback = ASSAN_callback;
break; break;
#endif #endif
} }
if(next_callback>32000) if(next_callback>32000)
@@ -600,29 +640,16 @@ static void protocol_init()
next_callback-=temp<<10; // between 2-3ms left at this stage next_callback-=temp<<10; // between 2-3ms left at this stage
} }
cli(); // disable global int cli(); // disable global int
#ifdef XMEGA OCR1A = TCNT1 + next_callback*2;// set compare A for callback
TCC1.CCA = TCC1.CNT + next_callback*2; // set compare A for callback
sei(); // enable global int sei(); // enable global int
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A flag TIFR1 = OCF1A_bm ; // clear compare A flag
#else
OCR1A=TCNT1+next_callback*2; // set compare A for callback
sei(); // enable global int
TIFR1=(1<<OCF1A); // clear compare A flag
#endif
BIND_BUTTON_FLAG_off; // do not bind/reset id anymore even if protocol change BIND_BUTTON_FLAG_off; // do not bind/reset id anymore even if protocol change
} }
void update_serial_data() void update_serial_data()
{ {
RX_FLAG_off; //data has been processed
do
{
cli();
if(IS_RX_MISSED_BUFF_on) // If the buffer is still valid
memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
sei();
RX_MISSED_BUFF_off;
RX_DONOTUPDTAE_on; RX_DONOTUPDTAE_on;
RX_FLAG_off; //data is being processed
if(rx_ok_buff[0]&0x20) //check range if(rx_ok_buff[0]&0x20) //check range
RANGE_FLAG_on; RANGE_FLAG_on;
else else
@@ -650,6 +677,8 @@ void update_serial_data()
else else
if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set
CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind
else
CHANGE_PROTOCOL_FLAG_off; //no need to restart
cur_protocol[0] = rx_ok_buff[0]; //store current protocol cur_protocol[0] = rx_ok_buff[0]; //store current protocol
// decode channel values // decode channel values
@@ -667,36 +696,40 @@ void update_serial_data()
Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125% Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125%
} }
RX_DONOTUPDTAE_off; RX_DONOTUPDTAE_off;
#ifdef XMEGA
cli();
#else
UCSR0B &= ~_BV(RXCIE0); // RX interrupt disable
#endif
if(IS_RX_MISSED_BUFF_on) // If the buffer is still valid
{ memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
RX_FLAG_on; // data to be processed next time...
RX_MISSED_BUFF_off;
} }
while(IS_RX_MISSED_BUFF_on); // We've just processed an old frame... #ifdef XMEGA
sei();
#else
UCSR0B |= _BV(RXCIE0) ; // RX interrupt enable
#endif
} }
void module_reset() void modules_reset()
{ {
if(remote_callback) #ifdef CC2500_INSTALLED
{ // previous protocol loaded
remote_callback = 0;
switch(prev_protocol)
{
case MODE_FLYSKY:
case MODE_HUBSAN:
A7105_Reset();
break;
case MODE_FRSKY:
case MODE_FRSKYX:
case MODE_SFHSS:
CC2500_Reset(); CC2500_Reset();
break; #endif
case MODE_DSM2: #ifdef A7105_INSTALLED
case MODE_DEVO: A7105_Reset();
case MODE_J6PRO: #endif
#ifdef CYRF6936_INSTALLED
CYRF_Reset(); CYRF_Reset();
break; #endif
default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI, MODE_FY326, MODE_FQ777, MODE_ASSAN #ifdef NFR24L01_INSTALLED
NRF24L01_Reset(); NRF24L01_Reset();
break; #endif
}
} //Wait for every component to reset
delayMilliseconds(100);
prev_power=0xFD; // unused power value prev_power=0xFD; // unused power value
} }
@@ -764,8 +797,7 @@ uint16_t limit_channel_100(uint8_t ch)
void Mprotocol_serial_init() void Mprotocol_serial_init()
{ {
#ifdef XMEGA #ifdef XMEGA
PORTC.OUTSET = 0x08 ; PORTC.OUTSET = 0x08 ;
PORTC.DIRSET = 0x08 ; PORTC.DIRSET = 0x08 ;
@@ -775,26 +807,27 @@ void Mprotocol_serial_init()
USARTC0.CTRLB = 0x18 ; USARTC0.CTRLB = 0x18 ;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ; USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
USARTC0.CTRLC = 0x2B ; USARTC0.CTRLC = 0x2B ;
USARTC0.DATA ; UDR0 ;
#else #ifdef INVERT_TELEMETRY
PORTC.PIN3CTRL |= 0x40 ;
#endif
#else
#include <util/setbaud.h> #include <util/setbaud.h>
UBRR0H = UBRRH_VALUE; UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE; UBRR0L = UBRRL_VALUE;
UCSR0A = 0 ; // Clear X2 bit UCSR0A = 0 ; // Clear X2 bit
//Set frame format to 8 data bits, even parity, 2 stop bits //Set frame format to 8 data bits, even parity, 2 stop bits
UCSR0C = (1<<UPM01)|(1<<USBS0)|(1<<UCSZ01)|(1<<UCSZ00); UCSR0C = _BV(UPM01)|_BV(USBS0)|_BV(UCSZ01)|_BV(UCSZ00);
while ( UCSR0A & (1 << RXC0) )//flush receive buffer while ( UCSR0A & (1 << RXC0) )//flush receive buffer
UDR0; UDR0;
//enable reception and RC complete interrupt //enable reception and RC complete interrupt
UCSR0B = (1<<RXEN0)|(1<<RXCIE0);//rx enable and interrupt UCSR0B = _BV(RXEN0)|_BV(RXCIE0);//rx enable and interrupt
#ifdef DEBUG_TX #ifndef DEBUG_TX
TX_SET_OUTPUT;
#else
#if defined(TELEMETRY) #if defined(TELEMETRY)
initTXSerial( SPEED_100K ) ; initTXSerial( SPEED_100K ) ;
#endif //TELEMETRY #endif //TELEMETRY
#endif //DEBUG_TX #endif //DEBUG_TX
#endif //XMEGA #endif //XMEGA
} }
#if defined(TELEMETRY) #if defined(TELEMETRY)
@@ -854,12 +887,9 @@ void SPI_Write(uint8_t command)
SDI_on; SDI_on;
else else
SDI_off; SDI_off;
NOP();
SCK_on; SCK_on;
NOP();
command = command << 1; command = command << 1;
SCK_off; SCK_off;
NOP();
} }
while(--n) ; while(--n) ;
SDI_on; SDI_on;
@@ -876,7 +906,6 @@ uint8_t SPI_Read(void)
SCK_on; SCK_on;
NOP(); NOP();
SCK_off; SCK_off;
NOP();
} }
return result; return result;
} }
@@ -887,6 +916,7 @@ uint8_t SPI_Read(void)
// replacement millis() and micros() // replacement millis() and micros()
// These work polled, no interrupts // These work polled, no interrupts
// micros() MUST be called at least once every 32 milliseconds // micros() MUST be called at least once every 32 milliseconds
#ifndef XMEGA
uint16_t MillisPrecount ; uint16_t MillisPrecount ;
uint16_t lastTimerValue ; uint16_t lastTimerValue ;
uint32_t TotalMicros ; uint32_t TotalMicros ;
@@ -986,6 +1016,7 @@ void init()
// this needs to be called before setup() or some functions won't work there // this needs to be called before setup() or some functions won't work there
sei(); sei();
} }
#endif //XMEGA
/**************************/ /**************************/
/**************************/ /**************************/
@@ -1005,11 +1036,7 @@ ISR(INT1_vect, ISR_NOBLOCK)
static uint16_t Prev_TCNT1=0; static uint16_t Prev_TCNT1=0;
uint16_t Cur_TCNT1; uint16_t Cur_TCNT1;
#ifdef XMEGA Cur_TCNT1 = TCNT1 - Prev_TCNT1 ; // Capture current Timer1 value
Cur_TCNT1 = TCC1.CNT - Prev_TCNT1 ; // Capture current Timer1 value
#else
Cur_TCNT1=TCNT1-Prev_TCNT1; // Capture current Timer1 value
#endif
if(Cur_TCNT1<1000) if(Cur_TCNT1<1000)
chan=-1; // bad frame chan=-1; // bad frame
else else
@@ -1038,52 +1065,33 @@ ISR(USART_RX_vect)
#endif #endif
{ // RX interrupt { // RX interrupt
static uint8_t idx=0; static uint8_t idx=0;
#ifdef XMEGA #ifdef XMEGA
if((USARTC0.STATUS & 0x1C)==0) // Check frame error, data overrun and parity error if((USARTC0.STATUS & 0x1C)==0) // Check frame error, data overrun and parity error
#else #else
UCSR0B &= ~_BV(RXCIE0) ; // RX interrupt disable
UCSR0B &= ~(1<<RXCIE0) ; //rx interrupt disable
sei() ; sei() ;
if((UCSR0A&0x1C)==0) // Check frame error, data overrun and parity error if((UCSR0A&0x1C)==0) // Check frame error, data overrun and parity error
#endif #endif
{ // received byte is ok to process { // received byte is ok to process
if(idx==0||discard_frame==1) if(idx==0||discard_frame==1)
{ // Let's try to sync at this point { // Let's try to sync at this point
idx=0;discard_frame=0; idx=0;discard_frame=0;
#ifdef XMEGA
if(USARTC0.DATA==0x55) // If 1st byte is 0x55 it looks ok
#else
if(UDR0==0x55) // If 1st byte is 0x55 it looks ok if(UDR0==0x55) // If 1st byte is 0x55 it looks ok
#endif
{ {
#ifdef XMEGA TX_RX_PAUSE_on;
TCC1.CCB = TCC1.CNT+(6500L) ; // Full message should be received within timer of 3250us tx_pause();
TCC1.INTFLAGS = TC1_CCBIF_bm ; // clear OCR1B match flag OCR1B = TCNT1+(6500L) ; // Full message should be received within timer of 3250us
TCC1.INTCTRLB = (TCC1.INTCTRLB & 0xF3) | 0x04 ; // enable interrupt on compare B match TIFR1 = OCF1B_bm ; // clear OCR1B match flag
#else SET_TIMSK1_OCIE1B ; // enable interrupt on compare B match
OCR1B=TCNT1+6500L; // Full message should be received within timer of 3250us
TIFR1=(1<<OCF1B); // clear OCR1B match flag
TIMSK1 |=(1<<OCIE1B); // enable interrupt on compare B match
#endif
idx++; idx++;
} }
} }
else else
{ {
RX_MISSED_BUFF_off; // if rx_buff was good it's not anymore... RX_MISSED_BUFF_off; // if rx_buff was good it's not anymore...
#ifdef XMEGA
rx_buff[(idx++)-1]=USARTC0.DATA; // Store received byte
#else
rx_buff[(idx++)-1]=UDR0; // Store received byte rx_buff[(idx++)-1]=UDR0; // Store received byte
#endif
if(idx>RXBUFFER_SIZE) if(idx>RXBUFFER_SIZE)
{ // A full frame has been received { // A full frame has been received
#ifdef XMEGA
TCC1.INTCTRLB &=0xF3; // disable interrupt on compare B match
#else
TIMSK1 &=~(1<<OCIE1B); // disable interrupt on compare B match
#endif
if(!IS_RX_DONOTUPDTAE_on) if(!IS_RX_DONOTUPDTAE_on)
{ //Good frame received and main is not working on the buffer { //Good frame received and main is not working on the buffer
memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
@@ -1091,34 +1099,36 @@ ISR(USART_RX_vect)
} }
else else
RX_MISSED_BUFF_on; // notify that rx_buff is good RX_MISSED_BUFF_on; // notify that rx_buff is good
idx=0; // start again discard_frame=1; // start again
} }
} }
} }
else else
{ {
#ifdef XMEGA
idx = USARTC0.DATA; // Dummy read
#else
idx=UDR0; // Dummy read idx=UDR0; // Dummy read
#endif
discard_frame=1; // Error encountered discard full frame... discard_frame=1; // Error encountered discard full frame...
} }
if(discard_frame==1)
#ifndef XMEGA {
CLR_TIMSK1_OCIE1B; // Disable interrupt on compare B match
TX_RX_PAUSE_off;
tx_resume();
}
#ifndef XMEGA
cli() ; cli() ;
UCSR0B |= (1<<RXCIE0) ; // RX enable interrupt UCSR0B |= _BV(RXCIE0) ; // RX interrupt enable
#endif #endif
} }
//Serial timer //Serial timer
#ifdef XMEGA #ifdef XMEGA
ISR(TCC1_CCB_vect) ISR(TCC1_CCB_vect)
#else #else
//ISR(TIMER1_COMPB_vect)
ISR(TIMER1_COMPB_vect, ISR_NOBLOCK ) ISR(TIMER1_COMPB_vect, ISR_NOBLOCK )
#endif #endif
{ // Timer1 compare B interrupt { // Timer1 compare B interrupt
discard_frame=1; discard_frame=1;
CLR_TIMSK1_OCIE1B; // Disable interrupt on compare B match
tx_resume();
} }
#endif //ENABLE_SERIAL #endif //ENABLE_SERIAL

View File

@@ -76,6 +76,16 @@ uint8_t NRF24L01_ReadReg(uint8_t reg)
NRF_CSN_on; NRF_CSN_on;
} }
*/ */
static uint8_t __attribute__((unused)) NRF24L01_ReadPayloadLength()
{
NRF_CSN_off;
SPI_Write(R_RX_PL_WID);
uint8_t len = SPI_Read();
NRF_CSN_on;
return len;
}
static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length) static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
{ {
NRF_CSN_off; NRF_CSN_off;
@@ -160,7 +170,7 @@ void NRF24L01_SetPower()
void NRF24L01_SetTxRxMode(enum TXRX_State mode) void NRF24L01_SetTxRxMode(enum TXRX_State mode)
{ {
if(mode == TX_EN) { if(mode == TX_EN) {
NRF_CSN_off; NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s) NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
| (1 << NRF24L01_07_TX_DS) | (1 << NRF24L01_07_TX_DS)
| (1 << NRF24L01_07_MAX_RT)); | (1 << NRF24L01_07_MAX_RT));
@@ -168,11 +178,11 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
| (1 << NRF24L01_00_CRCO) | (1 << NRF24L01_00_CRCO)
| (1 << NRF24L01_00_PWR_UP)); | (1 << NRF24L01_00_PWR_UP));
delayMicroseconds(130); delayMicroseconds(130);
NRF_CSN_on; NRF_CE_on;
} }
else else
if (mode == RX_EN) { if (mode == RX_EN) {
NRF_CSN_off; NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // reset the flag(s) NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // reset the flag(s)
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // switch to RX mode NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // switch to RX mode
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s) NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
@@ -183,12 +193,12 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
| (1 << NRF24L01_00_PWR_UP) | (1 << NRF24L01_00_PWR_UP)
| (1 << NRF24L01_00_PRIM_RX)); | (1 << NRF24L01_00_PRIM_RX));
delayMicroseconds(130); delayMicroseconds(130);
NRF_CSN_on; NRF_CE_on;
} }
else else
{ {
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC)); //PowerDown NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC)); //PowerDown
NRF_CSN_off; NRF_CE_off;
} }
} }
@@ -204,7 +214,7 @@ void NRF24L01_Reset()
NRF24L01_FlushTx(); NRF24L01_FlushTx();
NRF24L01_FlushRx(); NRF24L01_FlushRx();
NRF24L01_Strobe(0xff); // NOP NRF24L01_Strobe(0xff); // NOP
NRF24L01_ReadReg(0x07); NRF24L01_ReadReg(NRF24L01_07_STATUS);
NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TXRX_OFF);
delayMicroseconds(100); delayMicroseconds(100);
} }
@@ -221,6 +231,7 @@ uint8_t NRF24L01_packet_ack()
return PKT_PENDING; return PKT_PENDING;
} }
/////////////// ///////////////
// XN297 emulation layer // XN297 emulation layer
uint8_t xn297_scramble_enabled=XN297_SCRAMBLED; //enabled by default uint8_t xn297_scramble_enabled=XN297_SCRAMBLED; //enabled by default

View File

@@ -98,7 +98,7 @@ static void __attribute__((unused)) SFHSS_tune_chan_fast()
{ {
CC2500_Strobe(CC2500_SIDLE); CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16); CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16);
CC2500_WriteRegisterMulti(CC2500_23_FSCAL3, calData[rf_ch_num], 3); CC2500_WriteReg(CC2500_25_FSCAL1, calData[rf_ch_num]);
} }
static void __attribute__((unused)) SFHSS_tune_freq() static void __attribute__((unused)) SFHSS_tune_freq()
@@ -170,7 +170,7 @@ uint16_t ReadSFHSS()
phase = SFHSS_CAL; phase = SFHSS_CAL;
return 2000; return 2000;
case SFHSS_CAL: case SFHSS_CAL:
CC2500_ReadRegisterMulti(CC2500_23_FSCAL3, calData[rf_ch_num], 3); calData[rf_ch_num]=CC2500_ReadReg(CC2500_25_FSCAL1);
if (++rf_ch_num < 30) if (++rf_ch_num < 30)
SFHSS_tune_chan(); SFHSS_tune_chan();
else else

View File

@@ -1,7 +1,7 @@
//************************************* //**************************
// FrSky Telemetry serial code * // Telemetry serial code *
// By Midelic on RCGroups * // By Midelic on RCGroups *
//************************************* //**************************
#if defined TELEMETRY #if defined TELEMETRY
@@ -26,24 +26,22 @@
uint8_t pktx[MAX_PKTX]; uint8_t pktx[MAX_PKTX];
uint8_t pktx1[MAX_PKTX]; uint8_t pktx1[MAX_PKTX];
uint8_t index; uint8_t index;
uint8_t pass = 0;
uint8_t frame[18]; uint8_t frame[18];
#ifdef BASH_SERIAL #ifdef BASH_SERIAL
// For bit-bashed serial output // For bit-bashed serial output
struct t_serial_bash
struct t_serial_bash {
{
uint8_t head ; uint8_t head ;
uint8_t tail ; uint8_t tail ;
uint8_t data[64] ; uint8_t data[64] ;
uint8_t busy ; uint8_t busy ;
uint8_t speed ; uint8_t speed ;
} SerialControl ; } SerialControl ;
#endif #endif
#if defined DSM_TELEMETRY #if defined DSM_TELEMETRY
void DSM2_frame() void DSM_frame()
{ {
Serial_write(0xAA); // Start Serial_write(0xAA); // Start
for (uint8_t i = 0; i < 17; i++) // RSSI value followed by 16 bytes of telemetry data for (uint8_t i = 0; i < 17; i++) // RSSI value followed by 16 bytes of telemetry data
@@ -110,7 +108,7 @@ void frsky_check_telemetry(uint8_t *pkt,uint8_t len)
void frsky_link_frame() void frsky_link_frame()
{ {
frame[0] = 0xFE; frame[0] = 0xFE;
if ((cur_protocol[0]&0x1F)==MODE_FRSKY) if ((cur_protocol[0]&0x1F)==MODE_FRSKYD)
{ {
compute_RSSIdbm(); compute_RSSIdbm();
frame[1] = pktt[3]; frame[1] = pktt[3];
@@ -395,7 +393,7 @@ void proces_sport_data(uint8_t data)
#endif #endif
void frskyUpdate() void TelemetryUpdate()
{ {
#if defined SPORT_TELEMETRY #if defined SPORT_TELEMETRY
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX) if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
@@ -453,9 +451,9 @@ void frskyUpdate()
#endif #endif
#if defined DSM_TELEMETRY #if defined DSM_TELEMETRY
if(telemetry_link && (cur_protocol[0]&0x1F) == MODE_DSM2 ) if(telemetry_link && (cur_protocol[0]&0x1F) == MODE_DSM )
{ // DSM2 { // DSM
DSM2_frame(); DSM_frame();
telemetry_link=0; telemetry_link=0;
return; return;
} }
@@ -467,7 +465,7 @@ void frskyUpdate()
return; return;
} }
#if defined HUB_TELEMETRY #if defined HUB_TELEMETRY
if(!telemetry_link && (cur_protocol[0]&0x1F) == MODE_FRSKY) if(!telemetry_link && (cur_protocol[0]&0x1F) == MODE_FRSKYD)
{ // FrSky { // FrSky
frsky_user_frame(); frsky_user_frame();
return; return;
@@ -497,16 +495,13 @@ void frskyUpdate()
// Routines for normal serial output // Routines for normal serial output
void Serial_write(uint8_t data) void Serial_write(uint8_t data)
{ {
cli(); // disable global int uint8_t nextHead ;
if(++tx_head>=TXBUFFER_SIZE) nextHead = tx_head + 1 ;
tx_head=0; if ( nextHead >= TXBUFFER_SIZE )
tx_buff[tx_head]=data; nextHead = 0 ;
#ifdef XMEGA tx_buff[nextHead]=data;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ; tx_head = nextHead ;
#else tx_resume();
UCSR0B |= (1<<UDRIE0);//enable UDRE interrupt
#endif
sei(); // enable global int
} }
// Speed is 0 for 100K and 1 for 9600 // Speed is 0 for 100K and 1 for 9600
@@ -521,6 +516,7 @@ void initTXSerial( uint8_t speed)
USARTC0.CTRLB = 0x18 ; USARTC0.CTRLB = 0x18 ;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ; USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
USARTC0.CTRLC = 0x03 ; USARTC0.CTRLC = 0x03 ;
}
#else #else
//9600 bauds //9600 bauds
UBRR0H = 0x00; UBRR0H = 0x00;
@@ -528,11 +524,9 @@ void initTXSerial( uint8_t speed)
UCSR0A = 0 ; // Clear X2 bit UCSR0A = 0 ; // Clear X2 bit
//Set frame format to 8 data bits, none, 1 stop bit //Set frame format to 8 data bits, none, 1 stop bit
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00); UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
UCSR0B = (1<<TXEN0);//tx enable
#endif
} }
else
UCSR0B |= (1<<TXEN0);//tx enable UCSR0B |= (1<<TXEN0);//tx enable
#endif
} }
#ifdef XMEGA #ifdef XMEGA
@@ -545,18 +539,10 @@ ISR(USART_UDRE_vect)
{ {
if(++tx_tail>=TXBUFFER_SIZE)//head if(++tx_tail>=TXBUFFER_SIZE)//head
tx_tail=0; tx_tail=0;
#ifdef XMEGA
USARTC0.DATA = tx_buff[tx_tail] ;
#else
UDR0=tx_buff[tx_tail]; UDR0=tx_buff[tx_tail];
#endif
} }
if (tx_tail == tx_head) if (tx_tail == tx_head)
#ifdef XMEGA tx_pause(); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
USARTC0.CTRLA &= ~0x03 ;
#else
UCSR0B &= ~(1<<UDRIE0); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
#endif
} }
#else //BASH_SERIAL #else //BASH_SERIAL
@@ -566,11 +552,11 @@ ISR(USART_UDRE_vect)
void initTXSerial( uint8_t speed) void initTXSerial( uint8_t speed)
{ {
TIMSK0 = 0 ; // Stop all timer 0 interrupts TIMSK0 = 0 ; // Stop all timer 0 interrupts
#ifdef INVERT_SERIAL #ifdef INVERT_SERIAL
PORTD &= ~2 ; PORTD &= ~2 ;
#else #else
PORTD |= 2 ; PORTD |= 2 ;
#endif #endif
DDRD |= 2 ; // TxD pin is an output DDRD |= 2 ; // TxD pin is an output
UCSR0B &= ~(1<<TXEN0) ; UCSR0B &= ~(1<<TXEN0) ;

View File

@@ -34,13 +34,6 @@
#define YD717_PAYLOADSIZE 8 // receive data pipes set to this size, but unused #define YD717_PAYLOADSIZE 8 // receive data pipes set to this size, but unused
enum {
YD717_INIT1 = 0,
YD717_BIND2,
YD717_BIND3,
YD717_DATA
};
static void __attribute__((unused)) yd717_send_packet(uint8_t bind) static void __attribute__((unused)) yd717_send_packet(uint8_t bind)
{ {
uint8_t rudder_trim, elevator_trim, aileron_trim; uint8_t rudder_trim, elevator_trim, aileron_trim;
@@ -132,116 +125,61 @@ static void __attribute__((unused)) yd717_init()
// CRC, radio on // CRC, radio on
NRF24L01_SetTxRxMode(TX_EN); NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_PWR_UP)); NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x3F); // Auto Acknoledgement on all data pipes NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // Disable Acknoledgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3F); // Enable all data pipes NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x00); // Disable all data pipes
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x1A); // 500uS retransmit t/o, 10 tries NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // No retransmit
NRF24L01_WriteReg(NRF24L01_05_RF_CH, YD717_RF_CHANNEL); // Channel 3C NRF24L01_WriteReg(NRF24L01_05_RF_CH, YD717_RF_CHANNEL); // Channel 3C
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower(); NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_0C_RX_ADDR_P2, 0xC3); // LSB byte of pipe 2 receive address
NRF24L01_WriteReg(NRF24L01_0D_RX_ADDR_P3, 0xC4);
NRF24L01_WriteReg(NRF24L01_0E_RX_ADDR_P4, 0xC5);
NRF24L01_WriteReg(NRF24L01_0F_RX_ADDR_P5, 0xC6);
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, YD717_PAYLOADSIZE); // bytes of data payload for pipe 1
NRF24L01_WriteReg(NRF24L01_12_RX_PW_P1, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_13_RX_PW_P2, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_14_RX_PW_P3, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_15_RX_PW_P4, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_16_RX_PW_P5, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
NRF24L01_Activate(0x73); // Activate feature register NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); // Enable dynamic payload length on all pipes NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); // Enable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); // Set feature bits on NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); // Set feature bits on
NRF24L01_Activate(0x73); NRF24L01_Activate(0x73);
// set tx id
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
static void __attribute__((unused)) YD717_init1()
{
// for bind packets set address to prearranged value known to receiver // for bind packets set address to prearranged value known to receiver
uint8_t bind_rx_tx_addr[] = {0x65, 0x65, 0x65, 0x65, 0x65}; uint8_t bind_rx_tx_addr[] = {0x65, 0x65, 0x65, 0x65, 0x65};
uint8_t i;
if( sub_protocol==SYMAX4 ) if( sub_protocol==SYMAX4 )
for(i=0; i < 5; i++) for(uint8_t i=0; i < 5; i++)
bind_rx_tx_addr[i] = 0x60; bind_rx_tx_addr[i] = 0x60;
else else
if( sub_protocol==NIHUI ) if( sub_protocol==NIHUI )
for(i=0; i < 5; i++) for(uint8_t i=0; i < 5; i++)
bind_rx_tx_addr[i] = 0x64; bind_rx_tx_addr[i] = 0x64;
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_rx_tx_addr, 5); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_rx_tx_addr, 5);
} }
static void __attribute__((unused)) YD717_init2()
{
// set rx/tx address for data phase
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
uint16_t yd717_callback() uint16_t yd717_callback()
{ {
switch (phase) if(IS_BIND_DONE_on)
{
case YD717_INIT1:
yd717_send_packet(0); // receiver doesn't re-enter bind mode if connection lost...check if already bound
phase = YD717_BIND3;
break;
case YD717_BIND2:
if (counter == 0)
{
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete
YD717_init2(); // change to data phase rx/tx address
yd717_send_packet(0); yd717_send_packet(0);
phase = YD717_BIND3; else
{
if (bind_counter == 0)
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); // set address
yd717_send_packet(0);
BIND_DONE; // bind complete
} }
else else
{ {
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete;
yd717_send_packet(1); yd717_send_packet(1);
counter--; bind_counter--;
} }
break;
case YD717_BIND3:
switch (NRF24L01_packet_ack())
{
case PKT_PENDING:
return YD717_PACKET_CHKTIME; // packet send not yet complete
case PKT_ACKED:
phase = YD717_DATA;
BIND_DONE; // bind complete
break;
case PKT_TIMEOUT:
YD717_init1(); // change to bind rx/tx address
counter = YD717_BIND_COUNT;
phase = YD717_BIND2;
yd717_send_packet(1);
}
break;
case YD717_DATA:
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete
yd717_send_packet(0);
break;
} }
return YD717_PACKET_PERIOD; // Packet every 8ms return YD717_PACKET_PERIOD; // Packet every 8ms
} }
uint16_t initYD717() uint16_t initYD717()
{ {
BIND_IN_PROGRESS; // autobind protocol
rx_tx_addr[4] = 0xC1; // always uses first data port rx_tx_addr[4] = 0xC1; // always uses first data port
yd717_init(); yd717_init();
phase = YD717_INIT1; bind_counter = YD717_BIND_COUNT;
BIND_IN_PROGRESS; // autobind protocol
// Call callback in 50ms // Call callback in 50ms
return YD717_INITIAL_WAIT; return YD717_INITIAL_WAIT;

View File

@@ -45,11 +45,12 @@
#endif #endif
#ifdef CYRF6936_INSTALLED #ifdef CYRF6936_INSTALLED
#define DEVO_CYRF6936_INO #define DEVO_CYRF6936_INO
#define DSM2_CYRF6936_INO #define DSM_CYRF6936_INO
#define J6PRO_CYRF6936_INO #define J6PRO_CYRF6936_INO
#endif #endif
#ifdef CC2500_INSTALLED #ifdef CC2500_INSTALLED
#define FRSKY_CC2500_INO #define FRSKYD_CC2500_INO
#define FRSKYV_CC2500_INO
#define FRSKYX_CC2500_INO #define FRSKYX_CC2500_INO
#define SFHSS_CC2500_INO #define SFHSS_CC2500_INO
#endif #endif
@@ -87,13 +88,13 @@
//Comment a line to disable a protocol telemetry //Comment a line to disable a protocol telemetry
#if defined(TELEMETRY) #if defined(TELEMETRY)
#if defined DSM2_CYRF6936_INO #if defined DSM_CYRF6936_INO
#define DSM_TELEMETRY #define DSM_TELEMETRY
#endif #endif
#if defined FRSKYX_CC2500_INO #if defined FRSKYX_CC2500_INO
#define SPORT_TELEMETRY #define SPORT_TELEMETRY
#endif #endif
#if defined FRSKY_CC2500_INO #if defined FRSKYD_CC2500_INO
#define HUB_TELEMETRY #define HUB_TELEMETRY
#endif #endif
#endif #endif
@@ -147,10 +148,10 @@ const PPM_Parameters PPM_prot[15]= {
// Dial Protocol Sub protocol RX_Num Power Auto Bind Option // Dial Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 3 */ {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, // option=fine freq tuning /* 3 */ {MODE_FRSKYD, 0 , 0 , P_HIGH , NO_AUTOBIND , 40 }, // option=fine freq tuning
/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 6 */ {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 2 }, // option=2=6 channels @ 22ms /* 6 */ {MODE_DSM , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 2 }, // option=2=6 channels @ 22ms
/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 },
@@ -169,14 +170,14 @@ const PPM_Parameters PPM_prot[15]= {
V912 V912
MODE_HUBSAN MODE_HUBSAN
NONE NONE
MODE_FRSKY MODE_FRSKYD
NONE NONE
MODE_HISKY MODE_HISKY
Hisky Hisky
HK310 HK310
MODE_V2X2 MODE_V2X2
NONE NONE
MODE_DSM2 MODE_DSM
DSM2 DSM2
DSMX DSMX
MODE_DEVO MODE_DEVO
@@ -225,6 +226,7 @@ const PPM_Parameters PPM_prot[15]= {
X600 X600
X800 X800
H26D H26D
E010
MODE_SHENQI MODE_SHENQI
NONE NONE
MODE_FY326 MODE_FY326
@@ -237,6 +239,8 @@ const PPM_Parameters PPM_prot[15]= {
NONE NONE
MODE_ASSAN MODE_ASSAN
NONE NONE
MODE_FRSKYV
NONE
*/ */
// RX_Num is used for model match. Using RX_Num values different for each receiver will prevent starting a model with the false config loaded... // RX_Num is used for model match. Using RX_Num values different for each receiver will prevent starting a model with the false config loaded...

View File

@@ -50,12 +50,25 @@ A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
*** ***
#CC2500 RF Module #CC2500 RF Module
##FRSKY ##FRSKYV = FrSky 1 way
Models: FrSky receivers V8R4, V8R7 and V8FR.
Extended limits supported
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4
---|---|---|---
CH1|CH2|CH3|CH4
##FRSKYD
Models: FrSky receivers D4R and D8R. DIY RX-F801 and RX-F802 receivers.
Extended limits supported Extended limits supported
Telemetry enabled for A0, A1, RSSI, TSSI and Hub Telemetry enabled for A0, A1, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|--- ---|---|---|---|---|---|---|---
@@ -68,7 +81,7 @@ Extended limits supported
Telemetry enabled for A1 (RxBatt), A2, RSSI, TSSI and Hub Telemetry enabled for A1 (RxBatt), A2, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
###Sub_protocol CH_16 ###Sub_protocol CH_16
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
@@ -83,7 +96,7 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
##SFHSS ##SFHSS
Models: Futaba RXs and XK models. Models: Futaba RXs and XK models.
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|--- ---|---|---|---|---|---|---|---
@@ -99,10 +112,12 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|--- ---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8 A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be EATR.
Bind procedure using serial: 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. - 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.
- Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode). - Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode).
- Tun on RX (RX LED fast blink). - Turn on RX (RX LED fast blink).
- Turn on TX (RX LED solid, TX LED fast blink). - Turn on TX (RX LED solid, TX LED fast blink).
- Wait for bind on the TX to complete (TX LED solid). - Wait for bind on the TX to complete (TX LED solid).
- Make sure to set the RX_Num value for model match. - Make sure to set the RX_Num value for model match.
@@ -111,14 +126,17 @@ Bind procedure using serial:
Bind procedure using PPM: Bind procedure using PPM:
- 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. - 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.
- Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode). - Turn on RX (RX LED fast blink).
- Tun on RX (RX LED fast blink). - Turn the dial to the model number running protocol DEVO on the module.
- Turn on TX (RX LED solid, TX LED fast blink). - Press the bind button and turn on the TX. TX is now in autobind mode.
Fixed ID is not supported yet. - Release bind button after 1 second: RX LED solid, TX LED fast blink.
- Wait for bind on the TX to complete (TX LED solid).
- Press the bind button for 1 second. TX/RX is now in fixed ID mode.
- To verify that the TX is in fixed mode: power cycle the TX, the module LED should be solid ON (no blink).
- Note: Autobind/fixed ID mode is linked to the dial number. Which means that you can have multiple dial numbers set to the same protocol DEVO with different RX_Num and have different bind modes at the same time. It enables PPM users to get model match under DEVO.
Note that the RX ouput will be EATR. ##DSM
###Sub_protocol DSM2
##DSM2
Extended limits supported Extended limits supported
Telemetry enabled for TSSI and plugins Telemetry enabled for TSSI and plugins
@@ -319,8 +337,12 @@ A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|AUTOFLIP|PAN|TILT
###Sub_protocol WLH08 ###Sub_protocol WLH08
###Sub_protocol X600 ###Sub_protocol X600
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol X800 ###Sub_protocol X800
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol H26D ###Sub_protocol H26D
###Sub_protocol E010
Only 1 TX ID available
##MT99XX ##MT99XX
Autobind protocol Autobind protocol

View File

@@ -1,4 +1,5 @@
# DIY-Multiprotocol-TX-Module # DIY-Multiprotocol-TX-Module
Multiprotocol is a 2.4GHz transmitter which enables any TX to control lot of different models available on the market. Multiprotocol is a 2.4GHz transmitter which enables any TX to control lot of different models available on the market.
The source code is partly based on the Deviation TX project, thanks to all the developpers for their great job on protocols. The source code is partly based on the Deviation TX project, thanks to all the developpers for their great job on protocols.
@@ -66,19 +67,19 @@ Notes:
###Telemetry ###Telemetry
There are 4 protocols supporting telemetry: Hubsan, DSM, FrSky and FrSkyX. There are 4 protocols supporting telemetry: Hubsan, DSM, FrSkyD and FrSkyX.
Hubsan displays the battery voltage and TX RSSI. Hubsan displays the battery voltage and TX RSSI.
DSM displays TX RSSI and full telemetry. DSM displays TX RSSI and full telemetry.
FrSky displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub). FrSkyD displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub).
FrSkyX displays full telemetry (A1, A2, RX RSSI, TX RSSI and Hub). FrSkyX displays full telemetry (A1, A2, RX RSSI, TX RSSI and Hub).
### If used in PPM mode ### If used in PPM mode
Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FRSky hub format for Hubsan, FrSky, FrSkyX and DSM format for DSM2/X. Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FrSky hub format for Hubsan, FrSkyD, FrSkyX and DSM format for DSM2/X.
You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter (HC05/HC06) along with an app on your phone/tablet ([app example](https://play.google.com/store/apps/details?id=biz.onomato.frskydash&hl=fr)) to display telemetry information and setup alerts. You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter (HC05/HC06) along with an app on your phone/tablet ([app example](https://play.google.com/store/apps/details?id=biz.onomato.frskydash&hl=fr)) to display telemetry information and setup alerts.
@@ -127,10 +128,10 @@ Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module
0|Select serial|||||| 0|Select serial||||||
1|FLYSKY|Flysky|0|High|No|0|A7105 1|FLYSKY|Flysky|0|High|No|0|A7105
2|HUBSAN|-|0|High|No|0|A7105 2|HUBSAN|-|0|High|No|0|A7105
3|FRSKY|-|0|High|No|-41|CC2500 3|FRSKYD|-|0|High|No|-41|CC2500
4|HISKY|Hisky|0|High|No|0|NRF24L01 4|HISKY|Hisky|0|High|No|0|NRF24L01
5|V2X2|-|0|High|No|0|NRF24L01 5|V2X2|-|0|High|No|0|NRF24L01
6|DSM2|DSM2|0|High|No|6|CYRF6936 6|DSM|DSM2|0|High|No|6|CYRF6936
7|DEVO|-|0|High|No|0|CYRF6936 7|DEVO|-|0|High|No|0|CYRF6936
8|YD717|YD717|0|High|No|0|NRF24L01 8|YD717|YD717|0|High|No|0|NRF24L01
9|KN|WLTOYS|0|High|No|0|NRF24L01 9|KN|WLTOYS|0|High|No|0|NRF24L01
@@ -160,7 +161,8 @@ Hubsan|
#####CC2500 RF module #####CC2500 RF module
Protocol|Sub_protocol Protocol|Sub_protocol
--------|------------ --------|------------
FrSky| FrSkyV|
FrSkyD|
FrSkyX| FrSkyX|
|CH_16 |CH_16
|CH_8 |CH_8
@@ -169,7 +171,7 @@ SFHSS|
#####CYRF6936 RF module #####CYRF6936 RF module
Protocol|Sub_protocol Protocol|Sub_protocol
--------|------------ --------|------------
DSM2| DSM|
|DSM2 |DSM2
|DSMX |DSMX
Devo| Devo|
@@ -220,6 +222,7 @@ MJXQ|
|X600 |X600
|X800 |X800
|H26D |H26D
|E010
Shenqi| Shenqi|
FY326| FY326|
FQ777| FQ777|
@@ -236,8 +239,8 @@ Note:
###RF modules ###RF modules
Up to 4 RF modules can be installed: Up to 4 RF modules can be installed:
- [A7105](http://www.banggood.com/XL7105-D03-A7105-Modification-Module-Support-Deviation-Galee-Flysky-p-922603.html) for Flysky, Hubsan - [A7105](http://www.banggood.com/XL7105-D03-A7105-Modification-Module-Support-Deviation-Galee-Flysky-p-922603.html) for Flysky, Hubsan
- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for FrSky, FrSkyX and SFHSS - [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for FrSkyV, FrSkyD, FrSkyX and SFHSS
- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM2, DSMX, DEVO, Walkera - [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM, DEVO, J6Pro
- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols - [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols
RF modules can be installed for protocols need only. Example: if you only need the Hubsan protocol then install only a A7105 on your board. RF modules can be installed for protocols need only. Example: if you only need the Hubsan protocol then install only a A7105 on your board.
@@ -378,7 +381,9 @@ This will make sure your ATMEGA328 is well configured and the global TX ID is no
Make sure to follow this procedure: press the bind button, apply power and then release it after 1sec. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328. Make sure to follow this procedure: press the bind button, apply power and then release it after 1sec. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328.
For serial, the preffered method is to bind via the GUI protocol page. For serial, the preffered method is to bind via the GUI protocol page.
It migth happen that your module is always binding at power up. If this is the case, there is a big chance that you are using an Arduino Pro Mini with an external status LED. To work around this issue connect a 10K resistor between D13 and 3.3V. If your module is always/sometime binding at power up without pressing the button:
- Arduino Pro Mini with an external status LED: to work around this issue connect a 10K resistor between D13 and 3.3V.
- 4in1 module V1 (check 4in1 pictures): to solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
###Report issues ###Report issues
You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question. You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question.