Core and all protocols have been updated

Lot of changes in this new master
ChangeLog:
- Core: LED flashing when an invalid protocol has been selected
- Core: Channels 5 to 12 available as switches for all protocols: code
and size optimization
- Documentation (readme.md): fully updated, all protocols/sub
protocols/channels described, models example, many improvements
- All protocols have been updated in some way, here are some highlights:
* Bayang: added picture, video and inverted channels
* CG023->H8_3D: added light and calibration channels
* CX10: added sub protocols Q282, JC3015_1, JC3015_2, MK33041
* ESky: added new protocol - untested
* Hubsan: added compatibility with the new Hubsan Plus protocol
* KN: fully rewritten protocol: added sub protocols WLTOYS and FEILUN,
11 channels support

New version successfully tested on all my models: Flysky RX/F939/V911
protocol Flysky, Frsky RX protocol Frsky, Hubsan X4 protocol Hubsan,
Hisky HCP100/HCP80 protocol Hisky, HK-3000/HK3100 RX protocol
Hisky/HK310, XINXUN X39 protocol YD717/XINXUN, Symax X5C-1 protocol
SymaX/SYMAX, Cheerson CX-10A protocol CX10/BLUE, Eachine 3D-X4 protocol
CG023.

To access new protocols from er9x/ersky9x, you need to build a version
from this github repository https://github.com/pascallanger/mbtx based
on the latest er9x r820 and ersky9x r218.
This commit is contained in:
pascallanger 2016-01-20 10:50:56 +01:00
parent 481d4c15d6
commit bc42dbf88a
23 changed files with 1199 additions and 798 deletions

View File

@ -140,19 +140,18 @@ void A7105_WriteID(uint32_t ida) {
CS_on;
}
void A7105_SetPower_Value(int power)
{
/*
Power amp is ~+16dBm so:
TXPOWER_100uW = -23dBm == PAC=0 TBG=0
TXPOWER_300uW = -20dBm == PAC=0 TBG=1
TXPOWER_1mW = -16dBm == PAC=0 TBG=2
TXPOWER_3mW = -11dBm == PAC=0 TBG=4
TXPOWER_10mW = -6dBm == PAC=1 TBG=5
TXPOWER_30mW = 0dBm == PAC=2 TBG=7
TXPOWER_100mW = 1dBm == PAC=3 TBG=7
TXPOWER_150mW = 1dBm == PAC=3 TBG=7
*/
static void A7105_SetPower_Value(int power)
{
//Power amp is ~+16dBm so:
//TXPOWER_100uW = -23dBm == PAC=0 TBG=0
//TXPOWER_300uW = -20dBm == PAC=0 TBG=1
//TXPOWER_1mW = -16dBm == PAC=0 TBG=2
//TXPOWER_3mW = -11dBm == PAC=0 TBG=4
//TXPOWER_10mW = -6dBm == PAC=1 TBG=5
//TXPOWER_30mW = 0dBm == PAC=2 TBG=7
//TXPOWER_100mW = 1dBm == PAC=3 TBG=7
//TXPOWER_150mW = 1dBm == PAC=3 TBG=7
uint8_t pac, tbg;
switch(power) {
case 0: pac = 0; tbg = 0; break;
@ -167,6 +166,7 @@ void A7105_SetPower_Value(int power)
};
A7105_WriteReg(0x28, (pac << 3) | tbg);
}
*/
void A7105_SetPower()
{
@ -196,6 +196,8 @@ const uint8_t PROGMEM FLYSKY_A7105_regs[] = {
0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00,
0x01, 0x0f, 0xff
};
#define ID_NORMAL 0x55201041
#define ID_PLUS 0xAA201041
void A7105_Init(uint8_t protocol)
{
void *A7105_Regs;
@ -207,7 +209,7 @@ void A7105_Init(uint8_t protocol)
}
else
{
A7105_WriteID(0x55201041);
A7105_WriteID(ID_NORMAL);
A7105_Regs=(void *)HUBSAN_A7105_regs;
}
for (uint8_t i = 0; i < 0x33; i++){

View File

@ -12,7 +12,8 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with EAchine H8 mini, H10, BayangToys X6/X7/X9, JJRC JJ850 ...
// Compatible with EAchine H8 mini, H10, BayangToys X6/X7/X9, JJRC JJ850 ...
// Last sync with hexfet new_protocols/bayang_nrf24l01.c dated 2015-12-22
#if defined(BAYANG_NRF24L01_INO)
@ -30,15 +31,14 @@ enum BAYANG_FLAGS {
// flags going to packet[2]
BAYANG_FLAG_RTH = 0x01,
BAYANG_FLAG_HEADLESS = 0x02,
BAYANG_FLAG_FLIP = 0x08
BAYANG_FLAG_FLIP = 0x08,
BAYANG_FLAG_VIDEO = 0x10,
BAYANG_FLAG_PICTURE = 0x20,
// flags going to packet[3]
BAYANG_FLAG_INVERTED = 0x80 // inverted flight on Floureon H101
};
enum BAYANG_PHASES {
BAYANG_BIND = 0,
BAYANG_DATA
};
void BAYANG_send_packet(uint8_t bind)
static void BAYANG_send_packet(uint8_t bind)
{
uint8_t i;
if (bind)
@ -48,8 +48,8 @@ void BAYANG_send_packet(uint8_t bind)
packet[i+1]=rx_tx_addr[i];
for(i=0;i<4;i++)
packet[i+6]=hopping_frequency[i];
packet[10] = rx_tx_addr[0];
packet[11] = rx_tx_addr[1];
packet[10] = rx_tx_addr[0]; // txid[0]
packet[11] = rx_tx_addr[1]; // txid[1]
}
else
{
@ -57,16 +57,22 @@ void BAYANG_send_packet(uint8_t bind)
packet[0] = 0xA5;
packet[1] = 0xFA; // normal mode is 0xf7, expert 0xfa
//Flags
//Flags packet[2]
packet[2] = 0x00;
if(Servo_data[AUX1] > PPM_SWITCH)
packet[2] |= BAYANG_FLAG_FLIP;
if(Servo_data[AUX2] > PPM_SWITCH)
packet[2] |= BAYANG_FLAG_HEADLESS;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX1)
packet[2] = BAYANG_FLAG_FLIP;
if(Servo_AUX2)
packet[2] |= BAYANG_FLAG_RTH;
if(Servo_AUX3)
packet[2] |= BAYANG_FLAG_PICTURE;
if(Servo_AUX4)
packet[2] |= BAYANG_FLAG_VIDEO;
if(Servo_AUX5)
packet[2] |= BAYANG_FLAG_HEADLESS;
//Flags packet[3]
packet[3] = 0x00;
if(Servo_AUX6)
packet[3] = BAYANG_FLAG_INVERTED;
//Aileron
val = convert_channel_10b(AILERON);
@ -85,7 +91,7 @@ void BAYANG_send_packet(uint8_t bind)
packet[10] = (val>>8) + (val>>2 & 0xFC);
packet[11] = val & 0xFF;
}
packet[12] = rx_tx_addr[2];
packet[12] = rx_tx_addr[2]; // txid[2]
packet[13] = 0x0A;
packet[14] = 0;
for (uint8_t i=0; i < BAYANG_PACKET_SIZE-1; i++)
@ -95,10 +101,7 @@ void BAYANG_send_packet(uint8_t bind)
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
if (bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, BAYANG_RF_BIND_CHANNEL);
else
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, bind ? BAYANG_RF_BIND_CHANNEL:hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no%=BAYANG_RF_NUM_CHANNELS;
// clear packet status bits and TX FIFO
@ -109,7 +112,7 @@ void BAYANG_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
void BAYANG_init()
static void BAYANG_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@ -118,28 +121,22 @@ void BAYANG_init()
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03);
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x01);
NRF24L01_Activate(0x73);
}
uint16_t BAYANG_callback()
{
switch (phase)
if(IS_BIND_DONE_on)
BAYANG_send_packet(0);
else
{
case BAYANG_BIND:
if (bind_counter == 0)
{
XN297_SetTXAddr(rx_tx_addr, BAYANG_ADDRESS_LENGTH);
phase = BAYANG_DATA;
BIND_DONE;
}
else
@ -147,20 +144,17 @@ uint16_t BAYANG_callback()
BAYANG_send_packet(1);
bind_counter--;
}
break;
case BAYANG_DATA:
BAYANG_send_packet(0);
break;
}
return BAYANG_PACKET_PERIOD;
}
void BAYANG_initialize_txid()
static void BAYANG_initialize_txid()
{
// Strange txid, rx_tx_addr and rf_channels could be anything so I will use on rx_tx_addr for all of them...
// Strange also that there is no check of duplicated rf channels... I think we need to implement that later...
for(uint8_t i=0; i<BAYANG_RF_NUM_CHANNELS; i++)
hopping_frequency[i]=rx_tx_addr[i]%42;
//Could be using txid[0..2] but using rx_tx_addr everywhere instead...
hopping_frequency[0]=0;
hopping_frequency[1]=(rx_tx_addr[0]&0x1F)+0x10;
hopping_frequency[2]=hopping_frequency[1]+0x20;
hopping_frequency[3]=hopping_frequency[2]+0x20;
hopping_frequency_no=0;
}
@ -169,7 +163,6 @@ uint16_t initBAYANG(void)
BIND_IN_PROGRESS; // autobind protocol
bind_counter = BAYANG_BIND_COUNT;
BAYANG_initialize_txid();
phase=BAYANG_BIND;
BAYANG_init();
return BAYANG_INITIAL_WAIT+BAYANG_PACKET_PERIOD;
}

View File

@ -36,7 +36,7 @@ static void ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
//*********************************************
void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
static void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
{
CC25_CSN_off;
cc2500_spi_write(CC2500_WRITE_BURST | address);
@ -53,7 +53,7 @@ void cc2500_writeFifo(uint8_t *dpbuffer, uint8_t len)
}
//--------------------------------------
void cc2500_spi_write(uint8_t command) {
static void cc2500_spi_write(uint8_t command) {
uint8_t n=8;
SCK_off;//SCK start low
@ -81,7 +81,7 @@ void cc2500_writeReg(uint8_t address, uint8_t data) {//same as 7105
CC25_CSN_on;
}
uint8_t cc2500_spi_read(void)
static uint8_t cc2500_spi_read(void)
{
uint8_t result;
uint8_t i;
@ -101,7 +101,7 @@ uint8_t cc2500_spi_read(void)
}
//--------------------------------------------
uint8_t cc2500_readReg(uint8_t address)
static uint8_t cc2500_readReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
@ -119,7 +119,7 @@ void cc2500_strobe(uint8_t address)
CC25_CSN_on;
}
//------------------------
void cc2500_resetChip(void)
/*static void cc2500_resetChip(void)
{
// Toggle chip select signal
CC25_CSN_on;
@ -131,7 +131,7 @@ void cc2500_resetChip(void)
cc2500_strobe(CC2500_SRES);
_delay_ms(100);
}
*/
uint8_t CC2500_Reset()
{
cc2500_strobe(CC2500_SRES);
@ -139,8 +139,8 @@ uint8_t CC2500_Reset()
CC2500_SetTxRxMode(TXRX_OFF);
return cc2500_readReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
}
void CC2500_SetPower_Value(uint8_t power)
/*
static void CC2500_SetPower_Value(uint8_t power)
{
const unsigned char patable[8]= {
0xC5, // -12dbm
@ -156,7 +156,7 @@ void CC2500_SetPower_Value(uint8_t power)
power = 7;
cc2500_writeReg(CC2500_3E_PATABLE, patable[power]);
}
*/
void CC2500_SetPower()
{
uint8_t power=CC2500_BIND_POWER;

View File

@ -12,8 +12,10 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with EAchine 3D X4, CG023/CG031, Attop YD-822/YD-829/YD-829C and H8_3D/JJRC H20/H22
// Merged CG023 and H8_3D protocols
// compatible with EAchine 3D X4, CG023/CG031, Attop YD-822/YD-829/YD-829C and H8_3D/JJRC H20
// Last sync with hexfet new_protocols/cg023_nrf24l01.c dated 2015-10-03
// Last sync with hexfet new_protocols/h8_3d_nrf24l01.c dated 2015-11-18
#if defined(CG023_NRF24L01_INO)
@ -58,8 +60,9 @@ enum H8_3D_FLAGS {
H8_3D_FLAG_FLIP = 0x01,
H8_3D_FLAG_RATE_MID = 0x02,
H8_3D_FLAG_RATE_HIGH = 0x04,
H8_3D_FLAG_HEADLESS = 0x10, // RTH + headless on H8, headless on JJRC H20
H8_3D_FLAG_RTH = 0x40, // 360 flip mode on H8 3D, RTH on JJRC H20
H8_3D_FLAG_LIGTH = 0x08, // Light on H22
H8_3D_FLAG_HEADLESS = 0x10, // RTH + headless on H8, headless on JJRC H20, RTH on H22
H8_3D_FLAG_RTH = 0x20, // 360 flip mode on H8 3D and H22, RTH on JJRC H20
};
enum H8_3D_FLAGS_2 {
@ -67,12 +70,7 @@ enum H8_3D_FLAGS_2 {
H8_3D_FLAG_CALIBRATE = 0x20, // accelerometer calibration
};
enum CG023_PHASES {
CG023_BIND = 0,
CG023_DATA
};
void CG023_send_packet(uint8_t bind)
static void CG023_send_packet(uint8_t bind)
{
// throttle : 0x00 - 0xFF
throttle=convert_channel_8b(THROTTLE);
@ -92,7 +90,7 @@ void CG023_send_packet(uint8_t bind)
packet[0] = 0x13;
packet[3] = rx_tx_addr[2];
packet[4] = rx_tx_addr[3];
packet[8] = (rx_tx_addr[0]+rx_tx_addr[1]+rx_tx_addr[2]+rx_tx_addr[3]) & 0xff; // txid checksum
packet[8] = rx_tx_addr[0]+rx_tx_addr[1]+rx_tx_addr[2]+rx_tx_addr[3]; // txid checksum
memset(&packet[9], 0, 10);
if (bind)
{
@ -115,15 +113,15 @@ void CG023_send_packet(uint8_t bind)
packet[15] = 0x20;
packet[16] = 0x20;
packet[17] = H8_3D_FLAG_RATE_HIGH;
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[17] |= H8_3D_FLAG_FLIP;
if(Servo_data[AUX2] > PPM_SWITCH)
if(Servo_AUX2)
packet[17] |= H8_3D_FLAG_LIGTH; //H22 light
if(Servo_AUX3)
packet[17] |= H8_3D_FLAG_HEADLESS;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX4)
packet[17] |= H8_3D_FLAG_RTH; // 180/360 flip mode on H8 3D
// both sticks bottom left: calibrate acc
if(packet[9] <= 0x05 && packet[10] >= 0xa7 && packet[11] <= 0x57 && packet[12] >= 0xa7)
if(Servo_AUX5)
packet[18] = H8_3D_FLAG_CALIBRATE;
}
uint8_t sum = packet[9];
@ -156,15 +154,15 @@ void CG023_send_packet(uint8_t bind)
// rate
packet[13] = CG023_FLAG_RATE_HIGH;
// flags
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[13] |= CG023_FLAG_FLIP;
if(Servo_data[AUX2] > PPM_SWITCH)
if(Servo_AUX2)
packet[13] |= CG023_FLAG_LED_OFF;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX3)
packet[13] |= CG023_FLAG_STILL;
if(Servo_data[AUX4] > PPM_SWITCH)
if(Servo_AUX4)
packet[13] |= CG023_FLAG_VIDEO;
if(Servo_data[AUX5] > PPM_SWITCH)
if(Servo_AUX5)
packet[13] |= CG023_FLAG_EASY;
}
else
@ -172,13 +170,13 @@ void CG023_send_packet(uint8_t bind)
// rate
packet[13] = YD829_FLAG_RATE_HIGH;
// flags
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[13] |= YD829_FLAG_FLIP;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX3)
packet[13] |= YD829_FLAG_STILL;
if(Servo_data[AUX4] > PPM_SWITCH)
if(Servo_AUX4)
packet[13] |= YD829_FLAG_VIDEO;
if(Servo_data[AUX5] > PPM_SWITCH)
if(Servo_AUX5)
packet[13] |= YD829_FLAG_HEADLESS;
}
packet[14] = 0;
@ -207,7 +205,7 @@ void CG023_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
void CG023_init()
static void CG023_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@ -227,24 +225,19 @@ void CG023_init()
uint16_t CG023_callback()
{
switch (phase)
if(IS_BIND_DONE_on)
CG023_send_packet(0);
else
{
case CG023_BIND:
if (bind_counter == 0)
{
phase = CG023_DATA;
BIND_DONE;
}
else
{
CG023_send_packet(1);
bind_counter--;
}
break;
case CG023_DATA:
CG023_send_packet(0);
break;
}
if(sub_protocol==CG023)
return CG023_PACKET_PERIOD;
else
@ -253,7 +246,7 @@ uint16_t CG023_callback()
return H8_3D_PACKET_PERIOD;
}
void CG023_initialize_txid()
static void CG023_initialize_txid()
{
if(sub_protocol==H8_3D)
{
@ -262,10 +255,10 @@ void CG023_initialize_txid()
rx_tx_addr[2] = rx_tx_addr[2] % 0x20;
rx_tx_addr[3] = rx_tx_addr[3] % 0x11;
hopping_frequency[0] = 0x06 + (((rx_tx_addr[0]>>8) + (rx_tx_addr[0]&0x0f)) % 0x0f);
hopping_frequency[1] = 0x15 + (((rx_tx_addr[1]>>8) + (rx_tx_addr[1]&0x0f)) % 0x0f);
hopping_frequency[2] = 0x24 + (((rx_tx_addr[2]>>8) + (rx_tx_addr[2]&0x0f)) % 0x0f);
hopping_frequency[3] = 0x33 + (((rx_tx_addr[3]>>8) + (rx_tx_addr[3]&0x0f)) % 0x0f);
hopping_frequency[0] = 0x06 + (rx_tx_addr[0]&0x0f);
hopping_frequency[1] = 0x15 + (rx_tx_addr[1]&0x0f);
hopping_frequency[2] = 0x24 + (rx_tx_addr[2]&0x0f);
hopping_frequency[3] = 0x33 + (rx_tx_addr[3]&0x0f);
}
else
{ // CG023 and YD829
@ -282,7 +275,6 @@ uint16_t initCG023(void)
bind_counter = CG023_BIND_COUNT;
CG023_initialize_txid();
CG023_init();
phase=CG023_BIND;
if(sub_protocol==CG023)
return CG023_INITIAL_WAIT+CG023_PACKET_PERIOD;
else

View File

@ -13,6 +13,7 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with Cheerson CX-10 blue & newer red pcb, CX-10A, CX11, CX-10 green pcb, DM007, Floureon FX-10, CX-Stars
// Last sync with hexfet new_protocols/cx10_nrf24l01.c dated 2015-11-26
#if defined(CX10_NRF24L01_INO)
@ -21,6 +22,7 @@
#define CX10_BIND_COUNT 4360 // 6 seconds
#define CX10_PACKET_SIZE 15
#define CX10A_PACKET_SIZE 19 // CX10 blue board packets have 19-byte payload
#define Q282_PACKET_SIZE 21
#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec
#define CX10A_PACKET_PERIOD 6000
@ -39,13 +41,12 @@
#define NUM_RF_CHANNELS 4
enum {
CX10_INIT1 = 0,
CX10_BIND1,
CX10_BIND1 = 0,
CX10_BIND2,
CX10_DATA
};
void CX10_Write_Packet(uint8_t bind)
static void CX10_Write_Packet(uint8_t bind)
{
uint8_t offset = 0;
if(sub_protocol == CX10_BLUE)
@ -66,32 +67,74 @@ void CX10_Write_Packet(uint8_t bind)
packet[12+offset]= highByte(Servo_data[RUDDER]);
// Channel 5 - flip flag
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[12+offset] |= CX10_FLAG_FLIP; // flip flag
// Channel 6 - mode
if(Servo_data[AUX2] > PPM_MAX_COMMAND) // mode 3 / headless on CX-10A
packet[13+offset] = 0x02;
//flags=0; // packet 13
uint8_t flags2=0; // packet 14
// Channel 6 - rate mode is 2 lsb of packet 13
if(Servo_data[AUX2] > PPM_MAX_COMMAND) // rate 3 / headless on CX-10A
flags = 0x02;
else
if(Servo_data[AUX2] < PPM_MIN_COMMAND)
packet[13+offset] = 0x00; // mode 1
flags = 0x00; // rate 1
else
packet[13+offset] = 0x01; // mode 2
flags = 0x01; // rate 2
flags=0;
if(sub_protocol == DM007)
uint8_t video_state=packet[14] & 0x21;
switch(sub_protocol)
{
// Channel 7 - snapshot
if(Servo_data[AUX3] > PPM_SWITCH)
flags |= CX10_FLAG_SNAPSHOT;
// Channel 8 - video
if(Servo_data[AUX4] > PPM_SWITCH)
flags |= CX10_FLAG_VIDEO;
// Channel 9 - headless
if(Servo_data[AUX5] > PPM_SWITCH)
packet[13+offset] |= CX10_FLAG_HEADLESS;
case CX10_BLUE:
if(Servo_AUX3) flags |= 0x10; // Channel 7 - picture
if(Servo_AUX4) flags |= 0x08; // Channel 8 - video
break;
case Q282:
//FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
if(Servo_AUX1) flags2 =0x80; // Channel 5 - FLIP
if(Servo_AUX2) flags2|=0x40; // Channel 6 - LED
if(Servo_AUX3) flags2|=0x10; // Channel 7 - picture
if(Servo_AUX4) // Channel 8 - video
{
if (!(video_state & 0x20)) video_state ^= 0x21;
}
packet[14+offset] = flags;
else
if (video_state & 0x20) video_state &= 0x01;
flags2 |= video_state;
if(Servo_AUX5) flags2|=0x08; // Channel 9 - HEADLESS
flags=3;
if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH
if(Servo_AUX7) flags2|=0x04; // Channel 11 - XCAL
if(Servo_AUX8) flags2|=0x02; // Channel 12 - YCAL
memcpy(&packet[15], "\x10\x10\xaa\xaa\x00\x00", 6);
break;
case DM007:
//FLIP|MODE|PICTURE|VIDEO|HEADLESS
if(Servo_AUX3) flags2 = CX10_FLAG_SNAPSHOT; // Channel 7 - picture
if(Servo_AUX4) flags2|= CX10_FLAG_VIDEO; // Channel 8 - video
if(Servo_AUX5) flags |= CX10_FLAG_HEADLESS; // Channel 9 - headless
break;
case JC3015_1:
//FLIP|MODE|PICTURE|VIDEO
if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - picture
if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - video
break;
case JC3015_2:
//FLIP|MODE|LED|DFLIP
if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - LED
if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - DFLIP
break;
case MK33041:
//FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
if(Servo_AUX3) flags |= _BV(7); // Channel 7 - picture
if(Servo_AUX4) flags2 = _BV(0); // Channel 8 - video
if(Servo_AUX5) flags2|= _BV(5); // Channel 9 - headless
if(Servo_AUX6) flags |= _BV(2); // Channel 10 - rth
break;
}
packet[13+offset]=flags;
packet[14+offset]=flags2;
// Power on, TX mode, 2byte CRC
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
@ -111,7 +154,7 @@ void CX10_Write_Packet(uint8_t bind)
NRF24L01_SetPower();
}
void CX10_init()
static void CX10_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@ -130,9 +173,6 @@ void CX10_init()
uint16_t CX10_callback() {
switch (phase) {
case CX10_INIT1:
phase = bind_phase;
break;
case CX10_BIND1:
if (bind_counter == 0)
{
@ -174,41 +214,51 @@ uint16_t CX10_callback() {
return packet_period;
}
void initialize_txid()
static void initialize_txid()
{
rx_tx_addr[1]%= 0x30;
if(sub_protocol==Q282)
{
hopping_frequency[0] = 0x46;
hopping_frequency[1] = 0x48;
hopping_frequency[2] = 0x4a;
hopping_frequency[3] = 0x4c;
}
else
{
hopping_frequency[0] = 0x03 + (rx_tx_addr[0] & 0x0F);
hopping_frequency[1] = 0x16 + (rx_tx_addr[0] >> 4);
hopping_frequency[2] = 0x2D + (rx_tx_addr[1] & 0x0F);
hopping_frequency[3] = 0x40 + (rx_tx_addr[1] >> 4);
}
}
uint16_t initCX10(void)
{
switch(sub_protocol)
if(sub_protocol==CX10_BLUE)
{
case CX10_GREEN:
case DM007:
packet_length = CX10_PACKET_SIZE;
packet_period = CX10_PACKET_PERIOD;
bind_phase = CX10_BIND1;
bind_counter = CX10_BIND_COUNT;
break;
case CX10_BLUE:
packet_length = CX10A_PACKET_SIZE;
packet_period = CX10A_PACKET_PERIOD;
bind_phase = CX10_BIND2;
phase = CX10_BIND2;
bind_counter=0;
for(uint8_t i=0; i<4; i++)
packet[5+i] = 0xff; // clear aircraft id
packet[9] = 0;
break;
}
else
{
if(sub_protocol==Q282)
packet_length = Q282_PACKET_SIZE;
else
packet_length = CX10_PACKET_SIZE;
packet_period = CX10_PACKET_PERIOD;
phase = CX10_BIND1;
bind_counter = CX10_BIND_COUNT;
}
initialize_txid();
CX10_init();
phase = CX10_INIT1;
BIND_IN_PROGRESS; // autobind protocol
return INITIAL_WAIT;
return INITIAL_WAIT+packet_period;
}
#endif

View File

@ -14,7 +14,7 @@
*/
#include "iface_cyrf6936.h"
void cyrf_spi_write(uint8_t command)
static void cyrf_spi_write(uint8_t command)
{
uint8_t n=8;
SCK_off;//SCK start low
@ -32,7 +32,7 @@ void cyrf_spi_write(uint8_t command)
SDI_on;
}
uint8_t cyrf_spi_read()
static uint8_t cyrf_spi_read()
{
uint8_t result;
uint8_t i;
@ -59,7 +59,7 @@ void CYRF_WriteRegister(uint8_t address, uint8_t data)
CYRF_CSN_on;
}
void CYRF_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
static void CYRF_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
{
uint8_t i;
@ -70,7 +70,7 @@ void CYRF_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t leng
CYRF_CSN_on;
}
void CYRF_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
static void CYRF_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
{
uint8_t i;
@ -149,11 +149,13 @@ void CYRF_ConfigRFChannel(uint8_t ch)
CYRF_WriteRegister(CYRF_00_CHANNEL,ch);
}
void CYRF_SetPower_Value(uint8_t power)
/*
static void CYRF_SetPower_Value(uint8_t power)
{
uint8_t val = CYRF_ReadRegister(CYRF_03_TX_CFG) & 0xF8;
CYRF_WriteRegister(CYRF_03_TX_CFG, val | (power & 0x07));
}
*/
void CYRF_SetPower(uint8_t val)
{
@ -203,22 +205,22 @@ void CYRF_WritePreamble(uint32_t preamble)
/*
*
*/
void CYRF_StartReceive()
static void CYRF_StartReceive()
{
CYRF_WriteRegister(CYRF_05_RX_CTRL,0x87);
}
void CYRF_ReadDataPacket(uint8_t dpbuffer[])
/*static void CYRF_ReadDataPacket(uint8_t dpbuffer[])
{
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, 0x10);
}
void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
*/
/*static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
{
ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
}
void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len)
*/
static void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len)
{
CYRF_WriteRegister(CYRF_01_TX_LENGTH, len);
CYRF_WriteRegister(CYRF_02_TX_CTRL, 0x40);
@ -231,7 +233,7 @@ void CYRF_WriteDataPacket(const uint8_t dpbuffer[])
CYRF_WriteDataPacketLen(dpbuffer, 16);
}
uint8_t CYRF_ReadRSSI(uint8_t dodummyread)
/*static uint8_t CYRF_ReadRSSI(uint8_t dodummyread)
{
uint8_t result;
if(dodummyread)
@ -241,7 +243,7 @@ uint8_t CYRF_ReadRSSI(uint8_t dodummyread)
result = CYRF_ReadRegister(CYRF_13_RSSI);
return (result & 0x0F);
}
*/
//NOTE: This routine will reset the CRC Seed
void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uint8_t min, uint8_t max)
{

View File

@ -121,7 +121,7 @@ const uint8_t cyrfmfg_id[6] = {0xd4, 0x62, 0xd6, 0xad, 0xd3, 0xff}; //dx6i
#endif
*/
void build_bind_packet()
static void build_bind_packet()
{
uint8_t i;
uint16_t sum = 384 - 0x10;//
@ -154,7 +154,7 @@ void build_bind_packet()
packet[15] = sum & 0xff;
}
void build_data_packet(uint8_t upper)//
static void build_data_packet(uint8_t upper)//
{
#if DSM2_NUM_CHANNELS==4
const uint8_t ch_map[] = {0, 1, 2, 3, 0xff, 0xff, 0xff}; //Guess
@ -252,7 +252,7 @@ void build_data_packet(uint8_t upper)//
}
}
uint8_t PROTOCOL_SticksMoved(uint8_t init)
static uint8_t PROTOCOL_SticksMoved(uint8_t init)
{
#define STICK_MOVEMENT 15*(PPM_MAX-PPM_MIN)/100 // defines when the bind dialog should be interrupted (stick movement STICK_MOVEMENT %)
static uint16_t ele_start, ail_start;
@ -268,7 +268,7 @@ uint8_t PROTOCOL_SticksMoved(uint8_t init)
return ((ele_diff + ail_diff) > STICK_MOVEMENT);//
}
uint8_t get_pn_row(uint8_t channel)
static uint8_t get_pn_row(uint8_t channel)
{
return (sub_protocol == DSMX ? (channel - 2) % 5 : channel % 5);
}
@ -300,7 +300,7 @@ const uint8_t init_vals[][2] = {
{CYRF_01_TX_LENGTH, 0x10}, //16byte packet
};
void cyrf_config()
static void cyrf_config()
{
for(uint8_t i = 0; i < sizeof(init_vals) / 2; i++)
CYRF_WriteRegister(init_vals[i][0], init_vals[i][1]);
@ -308,7 +308,7 @@ void cyrf_config()
CYRF_ConfigRFChannel(0x61);
}
void initialize_bind_state()
static void initialize_bind_state()
{
const uint8_t pn_bind[] = { 0xc6,0x94,0x22,0xfe,0x48,0xe6,0x57,0x4e };
uint8_t data_code[32];
@ -342,13 +342,13 @@ const uint8_t data_vals[][2] = {
{CYRF_10_FRAMING_CFG, 0xea},
};
void cyrf_configdata()
static void cyrf_configdata()
{
for(uint8_t i = 0; i < sizeof(data_vals) / 2; i++)
CYRF_WriteRegister(data_vals[i][0], data_vals[i][1]);
}
void set_sop_data_crc()
static void set_sop_data_crc()
{
uint8_t pn_row = get_pn_row(hopping_frequency[chidx]);
//printf("Ch: %d Row: %d SOP: %d Data: %d\n", ch[chidx], pn_row, sop_col, data_col);
@ -363,7 +363,7 @@ void set_sop_data_crc()
crcidx = !crcidx;
}
void calc_dsmx_channel()
static void calc_dsmx_channel()
{
uint8_t idx = 0;
uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0));

View File

@ -66,7 +66,7 @@ uint8_t ch_idx;
uint8_t use_fixed_id;
uint8_t failsafe_pkt;
void scramble_pkt()
static void scramble_pkt()
{
#ifdef NO_SCRAMBLE
return;
@ -77,7 +77,7 @@ void scramble_pkt()
#endif
}
void add_pkt_suffix()
static void add_pkt_suffix()
{
uint8_t bind_state;
if (use_fixed_id)
@ -97,7 +97,7 @@ void add_pkt_suffix()
packet[15] = (fixed_id >> 16) & 0xff;
}
void build_beacon_pkt(uint8_t upper)
static void build_beacon_pkt(uint8_t upper)
{
packet[0] = ((DEVO_NUM_CHANNELS << 4) | 0x07);
// uint8_t enable = 0;
@ -116,7 +116,7 @@ void build_beacon_pkt(uint8_t upper)
add_pkt_suffix();
}
void build_bind_pkt()
static void build_bind_pkt()
{
packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x0a;
packet[1] = bind_counter & 0xff;
@ -136,7 +136,7 @@ void build_bind_pkt()
packet[15] ^= cyrfmfg_id[2];
}
void build_data_pkt()
static void build_data_pkt()
{
uint8_t i;
packet[0] = (DEVO_NUM_CHANNELS << 4) | (0x0b + ch_idx);
@ -161,7 +161,7 @@ void build_data_pkt()
add_pkt_suffix();
}
void cyrf_set_bound_sop_code()
static void cyrf_set_bound_sop_code()
{
/* crc == 0 isn't allowed, so use 1 if the math results in 0 */
uint8_t crc = (cyrfmfg_id[0] + (cyrfmfg_id[1] >> 6) + cyrfmfg_id[2]);
@ -174,7 +174,7 @@ void cyrf_set_bound_sop_code()
CYRF_SetPower(0x08);
}
void cyrf_init()
static void cyrf_init()
{
/* Initialise CYRF chip */
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x39);
@ -201,7 +201,7 @@ void cyrf_init()
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x28);
}
void set_radio_channels()
static void set_radio_channels()
{
//int i;
CYRF_FindBestChannels(hopping_frequency, 3, 4, 4, 80);
@ -217,7 +217,7 @@ void set_radio_channels()
hopping_frequency[4] = hopping_frequency[1];
}
void DEVO_BuildPacket()
static void DEVO_BuildPacket()
{
switch(phase)
{
@ -302,7 +302,7 @@ uint16_t devo_callback()
return 1200;
}
void devo_bind()
/*static void devo_bind()
{
fixed_id = Model_fixed_id;
bind_counter = DEVO_BIND_COUNT;
@ -310,8 +310,8 @@ void devo_bind()
//PROTOCOL_SetBindState(0x1388 * 2400 / 1000); //msecs 12000ms
}
/*
void generate_fixed_id_bind(){
static void generate_fixed_id_bind(){
if(BIND_0){
//randomSeed((uint32_t)analogRead(A6)<<10|analogRead(A7));//seed
uint8_t txid[4];

View File

@ -0,0 +1,171 @@
/*
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/>.
*/
// Last sync with hexfet new_protocols/esky_nrf24l01.c dated 2015-02-13
#if defined(ESKY_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define ESKY_BIND_COUNT 1000
#define ESKY_PACKET_PERIOD 3333
#define ESKY_PAYLOAD_SIZE 13
#define ESKY_PACKET_CHKTIME 100 // Time to wait for packet to be sent (no ACK, so very short)
static void ESKY_set_data_address()
{
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4-byte RX/TX address for regular packets
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 4);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4);
}
static void ESKY_init(uint8_t bind)
{
NRF24L01_Initialize();
// 2-bytes CRC, radio off
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
if (bind)
{
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // 3-byte RX/TX address for bind packets
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t*)"x00x00x00", 3);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"x00x00x00", 3);
}
else
ESKY_set_data_address();
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // No auto retransmission
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 50); // Channel 50 for bind packets
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, ESKY_PAYLOAD_SIZE); // bytes of data payload for pipe 0
NRF24L01_WriteReg(NRF24L01_12_RX_PW_P1, ESKY_PAYLOAD_SIZE);
NRF24L01_WriteReg(NRF24L01_13_RX_PW_P2, ESKY_PAYLOAD_SIZE);
NRF24L01_WriteReg(NRF24L01_14_RX_PW_P3, ESKY_PAYLOAD_SIZE);
NRF24L01_WriteReg(NRF24L01_15_RX_PW_P4, ESKY_PAYLOAD_SIZE);
NRF24L01_WriteReg(NRF24L01_16_RX_PW_P5, ESKY_PAYLOAD_SIZE);
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
}
static void ESKY_init2()
{
NRF24L01_FlushTx();
packet_sent = 0;
hopping_frequency_no = 0;
uint16_t channel_ord = rx_tx_addr[0] % 74;
hopping_frequency[12] = 10 + (uint8_t)channel_ord; //channel_code
uint8_t channel1, channel2;
channel1 = 10 + (uint8_t)((37 + channel_ord*5) % 74);
channel2 = 10 + (uint8_t)(( channel_ord*5) % 74) ;
hopping_frequency[0] = channel1;
hopping_frequency[1] = channel1;
hopping_frequency[2] = channel1;
hopping_frequency[3] = channel2;
hopping_frequency[4] = channel2;
hopping_frequency[5] = channel2;
//end_bytes
hopping_frequency[6] = 6;
hopping_frequency[7] = channel1*2;
hopping_frequency[8] = channel2*2;
hopping_frequency[9] = 6;
hopping_frequency[10] = channel1*2;
hopping_frequency[11] = channel2*2;
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
}
static void ESKY_send_packet(uint8_t bind)
{
uint8_t rf_ch = 50; // bind channel
if (bind)
{
// Bind packet
packet[0] = rx_tx_addr[2];
packet[1] = rx_tx_addr[1];
packet[2] = rx_tx_addr[0];
packet[3] = hopping_frequency[12]; // channel_code encodes pair of channels to transmit on
packet[4] = 0x18;
packet[5] = 0x29;
packet[6] = 0;
packet[7] = 0;
packet[8] = 0;
packet[9] = 0;
packet[10] = 0;
packet[11] = 0;
packet[12] = 0;
}
else
{
// Regular packet
// Each data packet is repeated 3 times on one channel, and 3 times on another channel
// For arithmetic simplicity, channels are repeated in rf_channels array
if (hopping_frequency_no == 0)
{
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2};
for (uint8_t i = 0; i < 6; i++)
{
packet[i*2] = Servo_data[ch[i]]>>8; //high byte of servo timing(1000-2000us)
packet[i*2+1] = Servo_data[ch[i]]&0xFF; //low byte of servo timing(1000-2000us)
}
}
rf_ch = hopping_frequency[hopping_frequency_no];
packet[12] = hopping_frequency[hopping_frequency_no+6]; // end_bytes
hopping_frequency_no++;
if (hopping_frequency_no > 6) hopping_frequency_no = 0;
}
NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch);
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, ESKY_PAYLOAD_SIZE);
packet_sent = 1;
if (! rf_ch_num)
NRF24L01_SetPower(); //Keep transmit power updated
}
uint16_t ESKY_callback()
{
if(IS_BIND_DONE_on)
{
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED)
return ESKY_PACKET_CHKTIME;
ESKY_send_packet(0);
}
else
{
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED)
return ESKY_PACKET_CHKTIME;
ESKY_send_packet(1);
if (--bind_counter == 0)
{
ESKY_set_data_address();
BIND_DONE;
}
}
return ESKY_PACKET_PERIOD;
}
uint16_t initESKY(void)
{
bind_counter = ESKY_BIND_COUNT;
rx_tx_addr[3] = 0xBB;
ESKY_init(IS_AUTOBIND_FLAG_on);
ESKY_init2();
return 50000;
}
#endif

View File

@ -12,6 +12,7 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/flysky_a7105.c dated 2015-09-28
#if defined(FLYSKY_A7105_INO)
@ -72,44 +73,45 @@ uint8_t chanrow;
uint8_t chancol;
uint8_t chanoffset;
void flysky_apply_extension_flags()
static void flysky_apply_extension_flags()
{
const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
0x49, 0x49, 0x49, 0x49, 0x49, };
static uint8_t seq_counter;
switch(sub_protocol) {
switch(sub_protocol)
{
case V9X9:
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[12] |= FLAG_V9X9_UNK;
if(Servo_data[AUX2] > PPM_SWITCH)
if(Servo_AUX2)
packet[12] |= FLAG_V9X9_LED;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX3)
packet[10] |= FLAG_V9X9_CAMERA;
if(Servo_data[AUX4] > PPM_SWITCH)
if(Servo_AUX4)
packet[10] |= FLAG_V9X9_VIDEO;
break;
case V6X6:
packet[13] = 0x03; // 3 = 100% rate (0=40%, 1=60%, 2=80%)
packet[14] = 0x00;
if(Servo_data[AUX1] > PPM_SWITCH)
if(Servo_AUX1)
packet[14] |= FLAG_V6X6_FLIP;
if(Servo_data[AUX2] > PPM_SWITCH)
if(Servo_AUX2)
packet[14] |= FLAG_V6X6_LED;
if(Servo_data[AUX3] > PPM_SWITCH)
if(Servo_AUX3)
packet[14] |= FLAG_V6X6_CAMERA;
if(Servo_data[AUX4] > PPM_SWITCH)
if(Servo_AUX4)
packet[14] |= FLAG_V6X6_VIDEO;
if(Servo_data[AUX5] > PPM_SWITCH)
if(Servo_AUX5)
{
packet[13] |= FLAG_V6X6_HLESS1;
packet[14] |= FLAG_V6X6_HLESS2;
}
if(Servo_data[AUX6] > PPM_SWITCH) //use option to manipulate these bytes
if(Servo_AUX6) //use option to manipulate these bytes
packet[14] |= FLAG_V6X6_RTH;
if(Servo_data[AUX7] > PPM_SWITCH)
if(Servo_AUX7)
packet[14] |= FLAG_V6X6_XCAL;
if(Servo_data[AUX8] > PPM_SWITCH)
if(Servo_AUX8)
packet[14] |= FLAG_V6X6_YCAL;
packet[15] = 0x10; // unknown
packet[16] = 0x10; // unknown
@ -126,9 +128,9 @@ void flysky_apply_extension_flags()
packet[12] |= 0x20; // bit 6 is always set ?
packet[13] = 0x00; // unknown
packet[14] = 0x00;
if(Servo_data[AUX1] > PPM_SWITCH)
packet[14] |= FLAG_V912_BTMBTN;
if(Servo_data[AUX2] > PPM_SWITCH)
if(Servo_AUX1)
packet[14] = FLAG_V912_BTMBTN;
if(Servo_AUX2)
packet[14] |= FLAG_V912_TOPBTN;
packet[15] = 0x27; // [15] and [16] apparently hold an analog channel with a value lower than 1000
packet[16] = 0x03; // maybe it's there for a pitch channel for a CP copter ?
@ -146,7 +148,7 @@ void flysky_apply_extension_flags()
}
}
void flysky_build_packet(uint8_t init)
static void flysky_build_packet(uint8_t init)
{
uint8_t i;
//servodata timing range for flysky.
@ -159,7 +161,7 @@ void flysky_build_packet(uint8_t init)
packet[2] = rx_tx_addr[2];
packet[3] = rx_tx_addr[1];
packet[4] = rx_tx_addr[0];
uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
for(i = 0; i < 8; i++)
{
packet[5+2*i]=lowByte(Servo_data[ch[i]]); //low byte of servo timing(1000-2000us)

View File

@ -111,7 +111,7 @@ uint16_t ReadFrSky_2way()
}
#if defined(TELEMETRY)
void check_telemetry(uint8_t *pkt,uint8_t len)
static void check_telemetry(uint8_t *pkt,uint8_t len)
{
if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3)
{//only packets with the required id and packet length
@ -128,17 +128,16 @@ void check_telemetry(uint8_t *pkt,uint8_t len)
}
void compute_RSSIdbm(){
if(pktt[len-2] >=128){
RSSI_dBm =(((uint16_t)(pktt[len-2])*18)>>5)- 82;
}
else{
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5)+65;
}
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5);
if(pktt[len-2] >=128)
RSSI_dBm -= 82;
else
RSSI_dBm += 65;
}
#endif
void frsky2way_init(uint8_t bind)
static void frsky2way_init(uint8_t bind)
{
// Configure cc2500 for tx mode
CC2500_Reset();
@ -197,7 +196,7 @@ void frsky2way_init(uint8_t bind)
//#######END INIT########
}
uint8_t get_chan_num(uint16_t idx)
static uint8_t get_chan_num(uint16_t idx)
{
uint8_t ret = (idx * 0x1e) % 0xeb;
if(idx == 3 || idx == 23 || idx == 47)
@ -207,7 +206,7 @@ uint8_t get_chan_num(uint16_t idx)
return ret;
}
void frsky2way_build_bind_packet()
static void frsky2way_build_bind_packet()
{
//11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01
//11 03 01 19 3e 00 02 8e 2f bb 5c 00 00 00 00 00 00 01
@ -234,7 +233,7 @@ void frsky2way_build_bind_packet()
uint8_t telemetry_counter=0;
void frsky2way_data_frame()
static void frsky2way_data_frame()
{//pachet[4] is telemetry user frame counter(hub)
//11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88
//11 57 12 00 00 01 f2 f2 f2 f2 06 06 ca ca ca ca 18 18

View File

@ -12,6 +12,7 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/hisky_nrf24l01.c dated 2015-03-27
#if defined(HISKY_NRF24L01_INO)
@ -26,7 +27,7 @@ uint8_t bind_buf_arry[4][10];
// HiSky protocol uses TX id as an address for nRF24L01, and uses frequency hopping sequence
// which does not depend on this id and is passed explicitly in binding sequence. So we are free
// to generate this sequence as we wish. It should be in the range [02..77]
void calc_fh_channels(uint32_t seed)
static void calc_fh_channels(uint32_t seed)
{
uint8_t idx = 0;
uint32_t rnd = seed;
@ -60,7 +61,7 @@ void calc_fh_channels(uint32_t seed)
}
}
void build_binding_packet(void)
static void build_binding_packet(void)
{
uint8_t i;
uint16_t sum=0;
@ -94,7 +95,7 @@ void build_binding_packet(void)
}
}
void hisky_init()
static void hisky_init()
{
NRF24L01_Initialize();
@ -115,11 +116,11 @@ void hisky_init()
// HiSky channel sequence: AILE ELEV THRO RUDD GEAR PITCH, channel data value is from 0 to 1000
// Channel 7 - Gyro mode, 0 - 6 axis, 3 - 3 axis
void build_ch_data()
static void build_ch_data()
{
uint16_t temp;
uint8_t i,j;
uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
for (i = 0; i< 8; i++) {
j=ch[i];
temp=map(limit_channel_100(j),PPM_MIN_100,PPM_MAX_100,0,1000);
@ -213,7 +214,7 @@ uint16_t hisky_cb()
}
// Generate internal id from TX id and manufacturer id (STM32 unique id)
void initialize_tx_id()
static void initialize_tx_id()
{
//Generate frequency hopping table
if(sub_protocol==HK310)

View File

@ -12,19 +12,31 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/hubsan_a7105.c dated 2015-12-11
#if defined(HUBSAN_A7105_INO)
#include "iface_a7105.h"
enum{
// flags going to packet[9] (Normal)
HUBSAN_FLAG_VIDEO= 0x01, // record video
HUBSAN_FLAG_FLIP = 0x08,
HUBSAN_FLAG_LIGHT = 0x04
HUBSAN_FLAG_FLIP = 0x08, // enable flips
HUBSAN_FLAG_LED = 0x04 // enable LEDs
};
uint32_t sessionid;
const uint32_t txid = 0xdb042679;
enum{
// flags going to packet[9] (Plus series)
HUBSAN_FLAG_HEADLESS = 0x08, // headless mode
};
enum{
// flags going to packet[13] (Plus series)
HUBSAN_FLAG_SNAPSHOT = 0x01,
HUBSAN_FLAG_FLIP_PLUS = 0x80,
};
uint32_t sessionid,id_data;
enum {
BIND_1,
@ -43,7 +55,7 @@ enum {
};
#define WAIT_WRITE 0x80
void update_crc()
static void update_crc()
{
uint8_t sum = 0;
for(uint8_t i = 0; i < 15; i++)
@ -51,23 +63,41 @@ void update_crc()
packet[15] = (256 - (sum % 256)) & 0xFF;
}
void hubsan_build_bind_packet(uint8_t state)
static void hubsan_build_bind_packet(uint8_t bind_state)
{
packet[0] = state;
static uint8_t handshake_counter;
if(phase < BIND_7)
handshake_counter = 0;
memset(packet, 0, 16);
packet[0] = bind_state;
packet[1] = channel;
packet[2] = (sessionid >> 24) & 0xFF;
packet[3] = (sessionid >> 16) & 0xFF;
packet[4] = (sessionid >> 8) & 0xFF;
packet[5] = (sessionid >> 0) & 0xFF;
if(id_data == ID_NORMAL)
{
packet[6] = 0x08;
packet[7] = 0xe4;
packet[8] = 0xea;
packet[9] = 0x9e;
packet[10] = 0x50;
packet[11] = (txid >> 24) & 0xFF;
packet[12] = (txid >> 16) & 0xFF;
packet[13] = (txid >> 8) & 0xFF;
packet[14] = (txid >> 0) & 0xFF;
//const uint32_t txid = 0xdb042679;
packet[11] = 0xDB;
packet[12] = 0x04;
packet[13] = 0x26;
packet[14] = 0x79;
}
else
{ //ID_PLUS
if(phase >= BIND_3)
{
packet[7] = 0x62;
packet[8] = 0x16;
}
if(phase == BIND_7)
packet[2] = handshake_counter++;
}
update_crc();
}
@ -75,69 +105,111 @@ void hubsan_build_bind_packet(uint8_t state)
//ee : rudder observed range: 0x34 - 0xcc (smaller is right)52-204-60%
//gg : elevator observed range: 0x3e - 0xbc (smaller is up)62-188 -50%
//ii : aileron observed range: 0x45 - 0xc3 (smaller is right)69-195-50%
void hubsan_build_packet()
static void hubsan_build_packet()
{
static uint8_t vtx_freq = 0;
memset(packet, 0, 16);
if(vtx_freq != option || packet_count==100) // set vTX frequency (H107D)
{
vtx_freq = option;
packet[0] = 0x40;
packet[1] = (option>0xF2)?0x17:0x16;
packet[2] = option+0x0D; // 5645 - 5900 MHz
packet[0] = 0x40; // vtx data packet
packet[1] = (vtx_freq>0xF2)?0x17:0x16;
packet[2] = vtx_freq+0x0D; // 5645 - 5900 MHz
packet[3] = 0x82;
packet_count++;
}
else //20 00 00 00 80 00 7d 00 84 02 64 db 04 26 79 7b
{
packet[0] = 0x20;
packet[2] = convert_channel_8b(THROTTLE);//throtle
packet[0] = 0x20; // normal data packet
packet[2] = convert_channel_8b(THROTTLE); //Throtle
}
packet[4] = 0xFF - convert_channel_8b(RUDDER); //Rudder is reversed
packet[6] = 0xFF - convert_channel_8b(ELEVATOR); //Elevator is reversed
packet[8] = convert_channel_8b(AILERON);//aileron
if( packet_count < 100) {
packet[9] = 0x02 | HUBSAN_FLAG_LIGHT | HUBSAN_FLAG_FLIP;
packet[8] = convert_channel_8b(AILERON); //Aileron
if(id_data == ID_NORMAL)
{
if( packet_count < 100)
{
packet[9] = 0x02 | HUBSAN_FLAG_LED | HUBSAN_FLAG_FLIP; // sends default value for the 100 first packets
packet_count++;
}
else
{
packet[9] = 0x02;
// Channel 5
if( Servo_data[AUX1] >= PPM_SWITCH)
packet[9] |= HUBSAN_FLAG_FLIP;
if(Servo_AUX1) packet[9] |= HUBSAN_FLAG_FLIP;
// Channel 6
if( Servo_data[AUX2] >= PPM_SWITCH)
packet[9] |= HUBSAN_FLAG_LIGHT;
if(Servo_AUX2) packet[9] |= HUBSAN_FLAG_LED;
// Channel 8
if( Servo_data[AUX4] > PPM_SWITCH)
packet[9] |= HUBSAN_FLAG_VIDEO;
if(Servo_AUX4) packet[9] |= HUBSAN_FLAG_VIDEO; // H102D
}
packet[10] = 0x64;
packet[11] = (txid >> 24) & 0xFF;
packet[12] = (txid >> 16) & 0xFF;
packet[13] = (txid >> 8) & 0xFF;
packet[14] = (txid >> 0) & 0xFF;
//const uint32_t txid = 0xdb042679;
packet[11] = 0xDB;
packet[12] = 0x04;
packet[13] = 0x26;
packet[14] = 0x79;
}
else
{ //ID_PLUS
packet[3] = 0x64;
packet[5] = 0x64;
packet[7] = 0x64;
packet[9] = 0x06;
//FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
if(Servo_AUX4) packet[9] |= HUBSAN_FLAG_VIDEO;
if(Servo_AUX5) packet[9] |= HUBSAN_FLAG_HEADLESS;
packet[10]= 0x19;
packet[12]= 0x5C; // ghost channel ?
packet[13] = 0;
if(Servo_AUX3) packet[13] = HUBSAN_FLAG_SNAPSHOT;
if(Servo_AUX1) packet[13] |= HUBSAN_FLAG_FLIP_PLUS;
packet[14]= 0x49; // ghost channel ?
if(packet_count < 100)
{ // set channels to neutral for first 100 packets
packet[2] = 0x80; // throttle neutral is at mid stick on plus series
packet[4] = 0x80;
packet[6] = 0x80;
packet[8] = 0x80;
packet[9] = 0x06;
packet[13]= 0x00;
packet_count++;
}
}
update_crc();
}
uint8_t hubsan_check_integrity()
#if defined(TELEMETRY)
/*static uint8_t hubsan_check_integrity()
{
uint8_t sum = 0;
for(int i = 0; i < 15; i++)
int sum = 0;
for(uint8_t i = 0; i < 15; i++)
sum += packet[i];
return packet[15] == ((256 - (sum % 256)) & 0xFF);
}
*/
#endif
uint16_t ReadHubsan()
{
static uint8_t txState=0;
static uint8_t rfMode=0;
static uint8_t bind_count=0;
uint16_t delay;
uint8_t i;
switch(phase) {
case BIND_1:
bind_count++;
if(bind_count >= 20)
{
if(id_data == ID_NORMAL)
id_data = ID_PLUS;
else
id_data = ID_NORMAL;
A7105_WriteID(id_data);
bind_count = 0;
}
case BIND_3:
case BIND_5:
case BIND_7:
@ -151,13 +223,22 @@ uint16_t ReadHubsan()
case BIND_5 | WAIT_WRITE:
case BIND_7 | WAIT_WRITE:
//wait for completion
for(i = 0; i< 20; i++) {
for(i = 0; i< 20; i++)
if(! (A7105_ReadReg(A7105_00_MODE) & 0x01))
break;
}
A7105_SetTxRxMode(RX_EN);
A7105_Strobe(A7105_RX);
phase &= ~WAIT_WRITE;
if(id_data == ID_PLUS)
{
if(state == BIND_7 && packet[2] == 9)
{
state = DATA_1;
A7105_WriteReg(A7105_1F_CODE_I, 0x0F);
BIND_DONE;
return 4500;
}
}
phase++;
return 4500; //7.5msec elapsed since last write
case BIND_2:
@ -180,7 +261,7 @@ uint16_t ReadHubsan()
return 15000; //22.5msec elapsed since last write
}
A7105_ReadData();
if(packet[1] == 9) {
if(packet[1] == 9 && id_data == ID_NORMAL) {
phase = DATA_1;
A7105_WriteReg(A7105_1F_CODE_I, 0x0F);
BIND_DONE;
@ -200,7 +281,7 @@ uint16_t ReadHubsan()
A7105_SetPower(); //Keep transmit power in sync
hubsan_build_packet();
A7105_Strobe(A7105_STANDBY);
A7105_WriteData(16, phase == DATA_5 ? channel + 0x23 : channel);
A7105_WriteData(16, phase == DATA_5 && id_data == ID_NORMAL ? channel + 0x23 : channel);
if (phase == DATA_5)
phase = DATA_1;
else
@ -249,13 +330,18 @@ uint16_t initHubsan() {
const uint8_t allowed_ch[] = {0x14, 0x1e, 0x28, 0x32, 0x3c, 0x46, 0x50, 0x5a, 0x64, 0x6e, 0x78, 0x82};
A7105_Init(INIT_HUBSAN); //hubsan_init();
randomSeed((uint32_t)analogRead(A0) << 10 | analogRead(A4));
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
sessionid = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16);
channel = allowed_ch[random(0xfefefefe) % sizeof(allowed_ch)];
BIND_IN_PROGRESS; // autobind protocol
phase = BIND_1;
packet_count=0;
id_data=ID_NORMAL;
#if defined(TELEMETRY)
v_lipo=0;
telemetry_link=0;
#endif
return 10000;
}

View File

@ -12,187 +12,215 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/KN_nrf24l01.c dated 2015-11-09
#if defined(KN_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define KN_BIND_COUNT 1000 // for KN 2sec every 2ms - 1000 packets
// Timeout for callback in uSec, 2ms=2000us for KN
#define KN_PACKET_PERIOD 2000
#define KN_PACKET_CHKTIME 100 // Time to wait for packet to be sent (no ACK, so very short)
// Wait for RX chip stable - 10ms
#define KN_INIT_WAIT_MS 10000
//#define PAYLOADSIZE 16
#define NFREQCHANNELS 4
#define KN_TXID_SIZE 4
//Payload(16 bytes) plus overhead(10 bytes) is 208 bits, takes about 0.4ms or 0.2ms
//to send for the rate of 500kb/s and 1Mb/s respectively.
// Callback timeout period for sending bind packets, minimum 250
#define KN_BINDING_PACKET_PERIOD 1000
// Timeout for sending data packets, in uSec, KN protocol requires 2ms
#define KN_WL_SENDING_PACKET_PERIOD 2000
// Timeout for sending data packets, in uSec, KNFX protocol requires 1.2 ms
#define KN_FX_SENDING_PACKET_PERIOD 1200
// packets to be sent during binding, last 0.5 seconds in WL Toys and 0.2 seconds in Feilun
#define KN_WL_BIND_COUNT 500
#define KN_FX_BIND_COUNT 200
#define KN_PAYLOADSIZE 16
//24L01 has 126 RF channels, can we use all of them?
#define KN_MAX_RF_CHANNEL 73
//KN protocol for WL Toys changes RF frequency every 10 ms, repeats with only 4 channels.
//Feilun variant uses only 2 channels, so we will just repeat the hopping channels later
#define KN_RF_CH_COUNT 4
//KN protocol for WL Toys sends 4 data packets every 2ms per frequency, plus a 2ms gap.
#define KN_WL_PACKET_SEND_COUNT 5
//KN protocol for Feilun sends 8 data packets every 1.2ms per frequency, plus a 0.3ms gap.
#define KN_FX_PACKET_SEND_COUNT 8
#define KN_TX_ADDRESS_SIZE 5
enum {
KN_FLAG_DR = 0x01, // Dual Rate
KN_FLAG_TH = 0x02, // Throttle Hold
KN_FLAG_IDLEUP = 0x04, // Idle up
KN_PHASE_PRE_BIND,
KN_PHASE_BINDING,
KN_PHASE_PRE_SEND,
KN_PHASE_SENDING,
};
enum {
KN_FLAG_DR = 0x01, // Dual Rate: 1 - full range
KN_FLAG_TH = 0x02, // Throttle Hold: 1 - hold
KN_FLAG_IDLEUP = 0x04, // Idle up: 1 - 3D
KN_FLAG_RES1 = 0x08,
KN_FLAG_RES2 = 0x10,
KN_FLAG_RES3 = 0x20,
KN_FLAG_GYRO3 = 0x40, // 00 - 6G mode, 01 - 3G mode
KN_FLAG_GYRO3 = 0x40, // 0 - 6G mode, 1 - 3G mode
KN_FLAG_GYROR = 0x80 // Always 0 so far
};
//
enum {
KN_INIT2 = 0,
KN_INIT2_NO_BIND,
KN_BIND,
KN_DATA
};
/*enum {
USE1MBPS_NO = 0,
USE1MBPS_YES = 1,
};*/
// 2-bytes CRC
#define CRC_CONFIG (BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO))
void kn_init()
//================================================================================================
// Private Functions
//================================================================================================
uint16_t initKN()
{
NRF24L01_Initialize();
if(sub_protocol==WLTOYS)
{
packet_period = KN_WL_SENDING_PACKET_PERIOD;
bind_counter = KN_WL_BIND_COUNT;
packet_count = KN_WL_PACKET_SEND_COUNT;
}
else
{
packet_period = KN_FX_SENDING_PACKET_PERIOD;
bind_counter = KN_FX_BIND_COUNT;
packet_count = KN_FX_PACKET_SEND_COUNT;
}
kn_init();
phase = IS_AUTOBIND_FLAG_on ? KN_PHASE_PRE_BIND : KN_PHASE_PRE_SEND;
NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG);
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0
// Enable: Dynamic Payload Length, Payload with ACK , W_TX_PAYLOAD_NOACK
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL) | BV(NRF2401_1D_EN_ACK_PAY) | BV(NRF2401_1D_EN_DYN_ACK));
NRF24L01_Activate(0x73);
return KN_INIT_WAIT_MS;
}
uint16_t kn_init2()
uint16_t kn_callback()
{
NRF24L01_FlushTx();
NRF24L01_FlushRx();
switch (phase)
{
case KN_PHASE_PRE_BIND:
kn_bind_init();
phase=KN_PHASE_BINDING;
//Do once, no break needed
case KN_PHASE_BINDING:
if(bind_counter>0)
{
bind_counter--;
NRF24L01_WritePayload(packet, KN_PAYLOADSIZE);
return KN_BINDING_PACKET_PERIOD;
}
BIND_DONE;
//Continue
case KN_PHASE_PRE_SEND:
packet_sent = 0;
packet_count = 0;
hopping_frequency_no = 0;
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, KN_TX_ADDRESS_SIZE);
phase = KN_PHASE_SENDING;
//Do once, no break needed
case KN_PHASE_SENDING:
if(packet_sent >= packet_count)
{
packet_sent = 0;
hopping_frequency_no++;
if(hopping_frequency_no >= KN_RF_CH_COUNT) hopping_frequency_no = 0;
kn_update_packet_control_data();
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
}
else
{
// Update sending count and RF channel index.
// The protocol sends 4 data packets every 2ms per frequency, plus a 2ms gap.
// Each data packet need a packet number and RF channel index
packet[13] = 0x00;
if(sub_protocol==WLTOYS)
packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2);
}
NRF24L01_WritePayload(packet, KN_PAYLOADSIZE);
packet_sent++;
return packet_period;
} //switch
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG | BV(NRF24L01_00_PWR_UP));
return 150;
//Bad things happened, reset
packet_sent = 0;
phase = KN_PHASE_PRE_SEND;
return packet_period;
}
void set_tx_for_bind()
//-------------------------------------------------------------------------------------------------
// This function init 24L01 regs and packet data for binding
// Send tx address, hopping table (for Wl Toys), and data rate to the KN receiver during binding.
// It seems that KN can remember these parameters, no binding needed after power up.
// Bind uses fixed TX address "KNDZK", 1 Mbps data rate and channel 83
//-------------------------------------------------------------------------------------------------
static void kn_bind_init()
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83);
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps for binding
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"KNDZK", 5);
}
void set_tx_for_data()
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
void kn_calc_fh_channels(uint32_t seed)
{
uint8_t idx = 0;
uint32_t rnd = seed;
while (idx < NFREQCHANNELS) {
uint8_t i;
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
// Use least-significant byte. 73 is prime, so channels 76..77 are unused
uint8_t next_ch = ((rnd >> 8) % 73) + 2;
// Keep the distance 2 between the channels - either odd or even
if (((next_ch ^ seed) & 0x01 )== 0)
continue;
// Check that it's not duplicate and spread uniformly
for (i = 0; i < idx; i++) {
if(hopping_frequency[i] == next_ch)
break;
}
if (i != idx)
continue;
hopping_frequency[idx++] = next_ch;
}
}
void kn_initialize_tx_id()
{
rx_tx_addr[4] = 'K';
kn_calc_fh_channels(MProtocol_id);
}
#define PACKET_COUNT_SHIFT 5
#define RF_CHANNEL_SHIFT 2
void kn_send_packet(uint8_t bind)
{
uint8_t rf_ch;
if (bind) {
rf_ch = 83;
packet[0] = 'K';
packet[1] = 'N';
packet[2] = 'D';
packet[3] = 'Z';
//Use first four bytes of tx_addr
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
packet[7] = rx_tx_addr[3];
if(sub_protocol==WLTOYS)
{
packet[8] = hopping_frequency[0];
packet[9] = hopping_frequency[1];
packet[10] = hopping_frequency[2];
packet[11] = hopping_frequency[3];
}
else
{
packet[8] = 0x00;
packet[9] = 0x00;
packet[10] = 0x00;
packet[11] = 0x00;
}
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x01; //mode_bitrate == USE1MBPS_YES ? 0x01 : 0x00;
} else {
rf_ch = hopping_frequency[hopping_frequency_no];
packet[15] = 0x01; //(USE1MBPS_YES) ? 0x01 : 0x00;
// Each packet is repeated 4 times on the same channel
// We're not strictly repeating them, rather we
// send new packet on the same frequency, so the
// receiver gets the freshest command. As receiver
// hops to a new frequency as soon as valid packet
// received it does not matter that the packet is
// not the same one repeated twice - nobody checks this
//Set RF channel
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83);
}
// NB! packet_count overflow is handled and used in
// callback.
if (++packet_count == 4)
hopping_frequency_no = (hopping_frequency_no + 1) & 0x03;
uint16_t kn_throttle, kn_rudder, kn_elevator, kn_aileron;
kn_throttle = convert_channel_10b(THROTTLE);
kn_aileron = convert_channel_10b(AILERON);
kn_elevator = convert_channel_10b(ELEVATOR);
kn_rudder = convert_channel_10b(RUDDER);
packet[0] = (kn_throttle >> 8) & 0xFF;
packet[1] = kn_throttle & 0xFF;
packet[2] = (kn_aileron >> 8) & 0xFF;
packet[3] = kn_aileron & 0xFF;
packet[4] = (kn_elevator >> 8) & 0xFF;
packet[5] = kn_elevator & 0xFF;
packet[6] = (kn_rudder >> 8) & 0xFF;
packet[7] = kn_rudder & 0xFF;
// Trims, middle is 0x64 (100) 0-200
packet[8] = 0x64; // T
packet[9] = 0x64; // A
packet[10] = 0x64; // E
//-------------------------------------------------------------------------------------------------
// Update control data to be sent
// Do it once per frequency, so the same values will be sent 4 times
// KN uses 4 10-bit data channels plus a 8-bit switch channel
//
// The packet[0] is used for pitch/throttle, the relation is hard coded, not changeable.
// We can change the throttle/pitch range though.
//
// How to use trim? V977 stock controller can trim 6-axis mode to eliminate the drift.
//-------------------------------------------------------------------------------------------------
static void kn_update_packet_control_data()
{
uint16_t value;
value = convert_channel_10b(THROTTLE);
packet[0] = (value >> 8) & 0xFF;
packet[1] = value & 0xFF;
value = convert_channel_10b(AILERON);
packet[2] = (value >> 8) & 0xFF;
packet[3] = value & 0xFF;
value = convert_channel_10b(ELEVATOR);
packet[4] = (value >> 8) & 0xFF;
packet[5] = value & 0xFF;
value = convert_channel_10b(RUDDER);
packet[6] = (value >> 8) & 0xFF;
packet[7] = value & 0xFF;
// Trims, middle is 0x64 (100) range 0-200
packet[8] = convert_channel_8b_scale(AUX5,0,200); // 0x64; // T
packet[9] = convert_channel_8b_scale(AUX6,0,200); // 0x64; // A
packet[10] = convert_channel_8b_scale(AUX7,0,200); // 0x64; // E
packet[11] = 0x64; // R
if (Servo_data[AUX1] > PPM_SWITCH)
flags |= KN_FLAG_DR;
else
flags=0;
if (Servo_data[AUX1] > PPM_SWITCH)
flags = KN_FLAG_DR;
if (Servo_data[AUX2] > PPM_SWITCH)
flags |= KN_FLAG_TH;
if (Servo_data[AUX3] > PPM_SWITCH)
@ -202,73 +230,117 @@ void kn_send_packet(uint8_t bind)
packet[12] = flags;
packet[13] = (packet_count << PACKET_COUNT_SHIFT) | (hopping_frequency_no << RF_CHANNEL_SHIFT);
packet[13] = 0x00;
if(sub_protocol==WLTOYS)
packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2);
packet[14] = 0x00;
packet[15] = 0x00;
}
packet_sent = 0;
NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch);
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, 16);
//++total_packets;
packet_sent = 1;
if (! hopping_frequency_no) {
//Keep transmit power updated
NRF24L01_SetPower();
}
}
uint16_t kn_callback()
//-------------------------------------------------------------------------------------------------
// This function setup 24L01
// V977 uses one way communication, receiving only. 24L01 RX is never enabled.
// V977 needs payload length in the packet. We should configure 24L01 to enable Packet Control Field(PCF)
// Some RX reg settings are actually for enable PCF
//-------------------------------------------------------------------------------------------------
static void kn_init()
{
uint16_t timeout = KN_PACKET_PERIOD;
switch (phase)
kn_calculate_tx_addr();
kn_calculate_freqency_hopping_channels();
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0
NRF24L01_Activate(0x73);
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0
// Enable: Dynamic Payload Length to enable PCF
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL));
NRF24L01_SetPower();
NRF24L01_FlushTx();
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_SetBitrate(NRF24L01_BR_1M); //USE1MBPS_YES ? NRF24L01_BR_1M : NRF24L01_BR_250K;
}
//-------------------------------------------------------------------------------------------------
// This function generate RF TX packet address
// V977 can remember the binding parameters; we do not need rebind when power up.
// This requires the address must be repeatable for a specific RF ID at power up.
//-------------------------------------------------------------------------------------------------
static void kn_calculate_tx_addr()
{
case KN_INIT2:
bind_counter = KN_BIND_COUNT;
timeout = kn_init2();
phase = KN_BIND;
set_tx_for_bind();
break;
case KN_INIT2_NO_BIND:
timeout = kn_init2();
phase = KN_DATA;
set_tx_for_data();
break;
case KN_BIND:
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED)
return KN_PACKET_CHKTIME;
kn_send_packet(1);
if (--bind_counter == 0) {
phase = KN_DATA;
set_tx_for_data();
BIND_DONE;
if(sub_protocol==FEILUN)
{
uint8_t addr2;
// Generate TXID with sum of minimum 256 and maximum 256+MAX_RF_CHANNEL-32
rx_tx_addr[1] = 1 + rx_tx_addr[0] % (KN_MAX_RF_CHANNEL-33);
addr2 = 1 + rx_tx_addr[2] % (KN_MAX_RF_CHANNEL-33);
if ((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1]) < 256)
rx_tx_addr[2] = addr2;
else
rx_tx_addr[2] = 0x00;
rx_tx_addr[3] = 0x00;
while((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]) < 257)
rx_tx_addr[3] += addr2;
}
break;
case KN_DATA:
if (packet_count == 4)
packet_count = 0;
else {
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED)
return KN_PACKET_CHKTIME;
kn_send_packet(0);
}
break;
}
return timeout;
//The 5th byte is a constant, must be 'K'
rx_tx_addr[4] = 'K';
}
uint16_t initKN(){
//total_packets = 0;
//mode_bitrate=USE1MBPS_YES;
kn_init();
phase = IS_AUTOBIND_FLAG_on ? KN_INIT2 : KN_INIT2_NO_BIND;
kn_initialize_tx_id();
//-------------------------------------------------------------------------------------------------
// This function generates "random" RF hopping frequency channel numbers.
// These numbers must be repeatable for a specific seed
// The generated number range is from 0 to MAX_RF_CHANNEL. No repeat or adjacent numbers
//
// For Feilun variant, the channels are calculated from TXID, and since only 2 channels are used
// we copy them to fill up to MAX_RF_CHANNEL
//-------------------------------------------------------------------------------------------------
static void kn_calculate_freqency_hopping_channels()
{
if(sub_protocol==WLTOYS)
{
uint8_t idx = 0;
uint32_t rnd = MProtocol_id;
while (idx < KN_RF_CH_COUNT)
{
uint8_t i;
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
// Call callback in 50ms
return 50000;
// Use least-significant byte. 73 is prime, so channels 76..77 are unused
uint8_t next_ch = ((rnd >> 8) % KN_MAX_RF_CHANNEL) + 2;
// Keep the distance 2 between the channels - either odd or even
if (((next_ch ^ MProtocol_id) & 0x01 )== 0)
continue;
// Check that it's not duplicate and spread uniformly
for (i = 0; i < idx; i++)
if(hopping_frequency[i] == next_ch)
break;
if (i != idx)
continue;
hopping_frequency[idx++] = next_ch;
}
}
else
{//FEILUN
hopping_frequency[0] = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; // - 256; ???
hopping_frequency[1] = hopping_frequency[0] + 32;
hopping_frequency[2] = hopping_frequency[0];
hopping_frequency[3] = hopping_frequency[1];
}
}
#endif

View File

@ -24,14 +24,17 @@
#include <avr/pgmspace.h>
#include <util/delay.h>
#include "multiprotocol.h"
//******************************************************
//******************************************************
// Multiprotocol module configuration starts here
//Uncomment the TX type
#define ER9X
//#define DEVO7
//Uncomment the type of TX
#define TX_ER9X //ER9X AETR (988<->2012µs)
//#define TX_DEVO7 //DEVO7 EATR (1120<->1920µs)
//#define TX_SPEKTRUM //Spektrum TAER (1100<->1900µs)
//#define TX_HISKY //HISKY AETR (1100<->1900µs)
#include "multiprotocol.h"
//Uncomment to enable 8 channels serial protocol, 16 otherwise
//#define NUM_SERIAL_CH_8
@ -39,12 +42,13 @@
//Uncomment to enable telemetry
#define TELEMETRY
//Protocols to include in compilation, comment to exclude
//Comment protocols to exclude from compilation
#define BAYANG_NRF24L01_INO
#define CG023_NRF24L01_INO
#define CX10_NRF24L01_INO
#define DEVO_CYRF6936_INO
#define DSM2_CYRF6936_INO
#define ESKY_NRF24L01_INO
#define FLYSKY_A7105_INO
#define FRSKY_CC2500_INO
#define HISKY_NRF24L01_INO
@ -65,7 +69,7 @@ static const uint8_t PPM_prot[15][2]= { {MODE_FLYSKY , Flysky }, //Dial=1
{MODE_DSM2 , DSM2 }, //Dial=6
{MODE_DEVO , 0 }, //Dial=7
{MODE_YD717 , YD717 }, //Dial=8
{MODE_KN , 0 }, //Dial=9
{MODE_KN , WLTOYS }, //Dial=9
{MODE_SYMAX , SYMAX }, //Dial=10
{MODE_SLT , 0 }, //Dial=11
{MODE_CX10 , CX10_BLUE }, //Dial=12
@ -74,54 +78,6 @@ static const uint8_t PPM_prot[15][2]= { {MODE_FLYSKY , Flysky }, //Dial=1
{MODE_SYMAX , SYMAX5C } //Dial=15
};
//
//TX definitions with timing endpoints and channels order
//
// Turnigy PPM and channels
#if defined(ER9X)
#define PPM_MAX 2140
#define PPM_MIN 860
#define PPM_MAX_100 2012
#define PPM_MIN_100 988
enum chan_order{
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// Devo PPM and channels
#if defined(DEVO7)
#define PPM_MAX 2100
#define PPM_MIN 900
#define PPM_MAX_100 1920
#define PPM_MIN_100 1120
enum chan_order{
ELEVATOR=0,
AILERON,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
//CC2500 RF module frequency adjustment, use in case you cannot bind with Frsky RX
//Note: this is set via Option when serial protocol is used
//values from 0-127 offset increase frequency, values from 255 to 127 decrease base frequency
@ -130,6 +86,7 @@ uint8_t fine = 0xd7; //* 215=-41 *
// Multiprotocol module configuration ends here
//******************************************************
//******************************************************
//Global constants/variables
@ -148,6 +105,7 @@ uint8_t packet[40];
#define NUM_CHN 16
// Servo data
uint16_t Servo_data[NUM_CHN];
uint8_t Servo_AUX;
// PPM variable
volatile uint16_t PPM_data[NUM_CHN];
@ -171,7 +129,7 @@ uint8_t flags;
// Mode_select variables
uint8_t mode_select;
uint8_t protocol_flags;
uint8_t protocol_flags=0,protocol_flags2=0;
// Serial variables
#if defined(NUM_SERIAL_CH_8) //8 channels serial protocol
@ -207,7 +165,7 @@ uint8_t telemetry_link=0;
// Callback
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 CheckTimer(uint16_t (*cb)(void));
static void CheckTimer(uint16_t (*cb)(void));
// Init
void setup()
@ -287,6 +245,7 @@ void loop()
if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received
{
update_serial_data(); // Update protocol and data
update_aux_flags();
if(IS_CHANGE_PROTOCOL_FLAG_on)
{ // Protocol needs to be changed
LED_OFF; //led off during protocol init
@ -302,6 +261,7 @@ void loop()
cli(); // disable global int
Servo_data[i]=PPM_data[i];
sei(); // enable global int
update_aux_flags();
}
PPM_FLAG_off; // wait for next frame before update
}
@ -314,33 +274,41 @@ void loop()
CheckTimer(remote_callback);
}
// Update led status based on binding and serial
void update_led_status(void)
// Update Servo_AUX flags based on servo AUX positions
static void update_aux_flags(void)
{
Servo_AUX=0;
for(uint8_t i=0;i<8;i++)
if(Servo_data[AUX1+i]>PPM_SWITCH)
Servo_AUX|=1<<i;
}
// Update led status based on binding and serial
static void update_led_status(void)
{
if(cur_protocol[0]==0)
{ // serial without valid protocol
if(blink<millis())
{
LED_TOGGLE;
if(cur_protocol[0]==0) // No valid serial received at least once
blink+=BLINK_SERIAL_TIME; //blink slowly while waiting a valid serial input
}
}
else
if(remote_callback == 0)
LED_OFF;
{ // Invalid protocol
if(IS_LED_on) //flash to indicate invalid protocol
blink+=BLINK_BAD_PROTO_TIME_LOW;
else
blink+=BLINK_BAD_PROTO_TIME_HIGH;
}
else
if(IS_BIND_DONE_on)
LED_ON; //bind completed -> led on
LED_OFF; //bind completed -> led on
else
if(blink<millis())
{
LED_TOGGLE;
blink+=BLINK_BIND_TIME; //blink fastly during binding
LED_TOGGLE;
}
}
// Protocol scheduler
void CheckTimer(uint16_t (*cb)(void))
static void CheckTimer(uint16_t (*cb)(void))
{
uint16_t next_callback;
uint32_t prev;
@ -373,13 +341,13 @@ void CheckTimer(uint16_t (*cb)(void))
}
}
void protocol_init(uint8_t protocol)
static void protocol_init(uint8_t protocol)
{
uint16_t next_callback=100; // Default is immediate call back
uint16_t next_callback=0; // Default is immediate call back
remote_callback = 0;
set_rx_tx_addr(MProtocol_id);
blink=millis()+BLINK_BIND_TIME;
blink=millis();
if(IS_BIND_BUTTON_FLAG_on)
AUTOBIND_FLAG_on;
if(IS_AUTOBIND_FLAG_on)
@ -387,8 +355,8 @@ void protocol_init(uint8_t protocol)
else
BIND_DONE;
CTRL1_on; //antenna RF3 by default
CTRL2_off; //antenna RF3 by default
CTRL1_on; //NRF24L01 antenna RF3 by default
CTRL2_off; //NRF24L01 antenna RF3 by default
switch(protocol) // Init the requested protocol
{
@ -491,6 +459,12 @@ void protocol_init(uint8_t protocol)
next_callback=initBAYANG();
remote_callback = BAYANG_callback;
break;
#endif
#if defined(ESKY_NRF24L01_INO)
case MODE_ESKY:
next_callback=initESKY();
remote_callback = ESKY_callback;
break;
#endif
}
@ -506,7 +480,7 @@ void protocol_init(uint8_t protocol)
BIND_BUTTON_FLAG_off; // do not bind/reset id anymore even if protocol change
}
void update_serial_data()
static void update_serial_data()
{
if(rx_ok_buff[0]&0x20) //check range
RANGE_FLAG_on;
@ -567,7 +541,7 @@ void update_serial_data()
RX_FLAG_off; //data has been processed
}
void module_reset()
static void module_reset()
{
remote_callback = 0;
switch(prev_protocol)
@ -580,19 +554,15 @@ void module_reset()
case MODE_FRSKYX:
CC2500_Reset();
break;
case MODE_HISKY:
case MODE_V2X2:
case MODE_YD717:
case MODE_KN:
case MODE_SYMAX:
case MODE_SLT:
case MODE_CX10:
NRF24L01_Reset();
break;
case MODE_DSM2:
case MODE_DEVO:
CYRF_Reset();
break;
default:
// MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY
NRF24L01_Reset();
break;
}
}
@ -648,7 +618,7 @@ uint16_t limit_channel_100(uint8_t ch)
}
// Convert 32b id to rx_tx_addr
void set_rx_tx_addr(uint32_t id)
static void set_rx_tx_addr(uint32_t id)
{ // Used by almost all protocols
rx_tx_addr[0] = (id >> 24) & 0xFF;
rx_tx_addr[1] = (id >> 16) & 0xFF;
@ -669,7 +639,7 @@ void Serial_write(uint8_t data)
}
#endif
void Mprotocol_serial_init()
static void Mprotocol_serial_init()
{
#if defined(NUM_SERIAL_CH_8) //8 channels serial protocol
#define BAUD 125000
@ -742,9 +712,10 @@ ISR(INT1_vect)
else
if(chan!=-1) // need to wait for start of frame
{ //servo values between 500us and 2420us will end up here
PPM_data[chan] = Cur_TCNT1/2;
if(PPM_data[chan]<PPM_MIN) PPM_data[chan]=PPM_MIN;
else if(PPM_data[chan]>PPM_MAX) PPM_data[chan]=PPM_MAX;
uint16_t a = Cur_TCNT1>>2;
if(a<PPM_MIN) a=PPM_MIN;
else if(a>PPM_MAX) a=PPM_MAX;
PPM_data[chan]=a;
if(chan++>=NUM_CHN)
chan=-1; // don't accept any new channels
}

View File

@ -19,7 +19,7 @@
//---------------------------
#include "iface_nrf24l01.h"
void nrf_spi_write(uint8_t command)
static void nrf_spi_write(uint8_t command)
{
uint8_t n=8;
@ -39,7 +39,7 @@ void nrf_spi_write(uint8_t command)
}
//VARIANT 2
uint8_t nrf_spi_read(void)
static uint8_t nrf_spi_read(void)
{
uint8_t result;
uint8_t i;
@ -106,7 +106,7 @@ uint8_t NRF24L01_ReadReg(uint8_t reg)
return data;
}
void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
/*static void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(R_REGISTER | (REGISTER_MASK & reg));
@ -114,8 +114,8 @@ void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
data[i] = nrf_spi_read();
NRF_CSN_on;
}
void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
*/
static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(R_RX_PAYLOAD);
@ -124,7 +124,7 @@ void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
NRF_CSN_on;
}
void NRF24L01_Strobe(uint8_t state)
static void NRF24L01_Strobe(uint8_t state)
{
NRF_CSN_off;
nrf_spi_write(state);
@ -161,7 +161,8 @@ void NRF24L01_SetBitrate(uint8_t bitrate)
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
}
void NRF24L01_SetPower_Value(uint8_t power)
/*
static void NRF24L01_SetPower_Value(uint8_t power)
{
uint8_t nrf_power = 0;
switch(power) {
@ -179,7 +180,7 @@ void NRF24L01_SetPower_Value(uint8_t power)
rf_setup = (rf_setup & 0xF9) | ((nrf_power & 0x03) << 1);
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
}
*/
void NRF24L01_SetPower()
{
uint8_t power=NRF_BIND_POWER;
@ -254,42 +255,6 @@ uint8_t NRF24L01_packet_ack()
return PKT_PENDING;
}
//---------------------------
/*
void NRF24L01_spi_test(void)
{
unsigned long errors = 0;
unsigned long test = 0;
unsigned long time;
uint8_t test_data_r[5];
uint8_t test_data_w[5] = {0x01,0x02,0x03,0x04,0x05};
time = micros();
Serial.println("Testing SPI");
for(test=0; test < 2775600 ; test++) // should run for X mins.
{
NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, test_data_w, 5);
NRF24L01_ReadRegisterMulti(NRF24L01_0B_RX_ADDR_P1, test_data_r, 5);
if(0 != memcmp(test_data_r, test_data_w, sizeof(test_data_r))) errors++;
test_data_w[0] ++;
test_data_w[1] ++;
test_data_w[2] ++;
test_data_w[3] ++;
test_data_w[4] ++;
}
Serial.print("test "); Serial.print(test, HEX); Serial.print("\n");
Serial.print("errors "); Serial.print(errors, HEX); Serial.print("\n");
Serial.print("time "); Serial.print(micros()- time, DEC); Serial.print("\n");
// 124211960
// 90899216
}
*/
//---------------------------
///////////////
// XN297 emulation layer
uint8_t xn297_addr_len;
@ -311,7 +276,7 @@ static const uint16_t xn297_crc_xorout[] = {
0x8B17, 0x2920, 0x8B5F, 0x61B1, 0xD391, 0x7401,
0x2138, 0x129F, 0xB3A0, 0x2988};
uint8_t bit_reverse(uint8_t b_in)
static uint8_t bit_reverse(uint8_t b_in)
{
uint8_t b_out = 0;
for (uint8_t i = 0; i < 8; ++i)
@ -322,7 +287,7 @@ uint8_t bit_reverse(uint8_t b_in)
return b_out;
}
uint16_t crc16_update(uint16_t crc, uint8_t a)
static uint16_t crc16_update(uint16_t crc, uint8_t a)
{
static const uint16_t polynomial = 0x1021;

View File

@ -12,6 +12,7 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/slt_nrf24l01.c dated 2015-02-13
#if defined(SLT_NRF24L01_INO)
@ -30,7 +31,7 @@ enum {
SLT_DATA3
};
void SLT_init()
static void SLT_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); // 2-bytes CRC, radio off
@ -56,7 +57,7 @@ static void SLT_init2()
NRF24L01_SetTxRxMode(TX_EN);
}
void SLT_set_tx_id(void)
static void SLT_set_tx_id(void)
{
// Frequency hopping sequence generation
for (uint8_t i = 0; i < 4; ++i)
@ -89,16 +90,16 @@ void SLT_set_tx_id(void)
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4);
}
void wait_radio()
static void SLT_wait_radio()
{
if (packet_sent)
while (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS))) ;
packet_sent = 0;
}
void send_data(uint8_t *data, uint8_t len)
static void SLT_send_data(uint8_t *data, uint8_t len)
{
wait_radio();
SLT_wait_radio();
NRF24L01_FlushTx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_RX_DR) | BV(NRF24L01_07_MAX_RT));
NRF24L01_WritePayload(data, len);
@ -106,11 +107,11 @@ void send_data(uint8_t *data, uint8_t len)
packet_sent = 1;
}
void SLT_build_packet()
static void SLT_build_packet()
{
// aileron, elevator, throttle, rudder, gear, pitch
uint8_t e = 0; // byte where extension 2 bits for every 10-bit channel are packed
uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER};
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER};
for (uint8_t i = 0; i < 4; ++i) {
uint16_t v = convert_channel_10b(ch[i]);
packet[i] = v;
@ -128,19 +129,20 @@ void SLT_build_packet()
hopping_frequency_no = 0;
}
static void send_bind_packet()
static void SLT_send_bind_packet()
{
wait_radio();
SLT_wait_radio();
BIND_IN_PROGRESS; // autobind protocol
NRF24L01_SetPower();
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x7E\xB8\x63\xA9", 4);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x50);
send_data(rx_tx_addr, 4);
SLT_send_data(rx_tx_addr, 4);
// NB: we should wait until the packet's sent before changing TX address!
wait_radio();
SLT_wait_radio();
BIND_DONE;
NRF24L01_SetPower();
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4);
}
@ -156,24 +158,23 @@ uint16_t SLT_callback()
delay_us = 150;
break;
case SLT_BIND:
send_bind_packet();
SLT_send_bind_packet();
phase = SLT_DATA1;
delay_us = 19000;
BIND_DONE;
break;
case SLT_DATA1:
SLT_build_packet();
send_data(packet, 7);
SLT_send_data(packet, 7);
phase = SLT_DATA2;
delay_us = 1000;
break;
case SLT_DATA2:
send_data(packet, 7);
SLT_send_data(packet, 7);
phase = SLT_DATA3;
delay_us = 1000;
break;
case SLT_DATA3:
send_data(packet, 7);
SLT_send_data(packet, 7);
if (++counter >= 100)
{
counter = 0;
@ -196,7 +197,6 @@ uint16_t initSLT()
SLT_init();
phase = SLT_INIT2;
SLT_set_tx_id();
BIND_IN_PROGRESS; // autobind protocol
return 50000;
}

View File

@ -12,16 +12,13 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with Syma X5C-1, X11, X11C, X12 and for sub protocol X5C Syma X5C (original), X2
// Last sync with hexfet new_protocols/cx10_nrf24l01.c dated 2015-09-28
#if defined(SYMAX_NRF24L01_INO)
#include "iface_nrf24l01.h"
/***
Main protocol compatible with Syma X5C-1, X11, X11C, X12.
SymaX5C protocol option compatible with Syma X5C (original) and X2.
***/
#define SYMAX_BIND_COUNT 345 // 1.5 seconds
#define SYMAX_FIRST_PACKET_DELAY 12000
#define SYMAX_PACKET_PERIOD 4000 // Timeout for callback in uSec
@ -44,16 +41,7 @@ enum {
SYMAX_DATA
};
/*
http://www.deviationtx.com/forum/protocol-development/3768-syma-x5c-1-x11-x12?start=140
TX address Channel Sequence
S1 3B B6 00 00 A2 15 35 1D 3D
D1 9A E9 02 00 A2 14 34 1C 3C
D2 46 18 00 00 A2 11 21 31 41
*/
uint8_t SYMAX_checksum(uint8_t *data)
static uint8_t SYMAX_checksum(uint8_t *data)
{
uint8_t sum = data[0];
@ -66,7 +54,7 @@ uint8_t SYMAX_checksum(uint8_t *data)
return sum + ( sub_protocol==SYMAX5C ? 0 : 0x55 );
}
void SYMAX_read_controls()
static void SYMAX_read_controls()
{
// Protocol is registered AETRF, that is
// Aileron is channel 1, Elevator - 2, Throttle - 3, Rudder - 4, Flip control - 5
@ -75,25 +63,24 @@ void SYMAX_read_controls()
throttle = convert_channel_8b(THROTTLE);
rudder = convert_channel_s8b(RUDDER);
// Channel 5
if (Servo_data[AUX1] > PPM_SWITCH)
flags = SYMAX_FLAG_FLIP;
else
flags=0;
// Channel 5
if (Servo_AUX1)
flags = SYMAX_FLAG_FLIP;
// Channel 7
if (Servo_data[AUX3] > PPM_SWITCH)
if (Servo_AUX3)
flags |= SYMAX_FLAG_PICTURE;
// Channel 8
if (Servo_data[AUX4] > PPM_SWITCH)
if (Servo_AUX4)
flags |= SYMAX_FLAG_VIDEO;
// Channel 9
if (Servo_data[AUX5] > PPM_SWITCH)
if (Servo_AUX5)
flags |= SYMAX_FLAG_HEADLESS;
}
#define X5C_CHAN2TRIM(X) ((((X) & 0x80 ? 0xff - (X) : 0x80 + (X)) >> 2) + 0x20)
void SYMAX_build_packet_x5c(uint8_t bind)
static void SYMAX_build_packet_x5c(uint8_t bind)
{
if (bind)
{
@ -124,12 +111,12 @@ void SYMAX_build_packet_x5c(uint8_t bind)
packet[14] = (flags & SYMAX_FLAG_VIDEO ? 0x10 : 0x00)
| (flags & SYMAX_FLAG_PICTURE ? 0x08 : 0x00)
| (flags & SYMAX_FLAG_FLIP ? 0x01 : 0x00)
| 0x04;// (flags & SYMAX_FLAG_RATES ? 0x04 : 0x00);
| 0x04;// always high rates (bit 3 is rate control)
packet[15] = SYMAX_checksum(packet);
}
}
void SYMAX_build_packet(uint8_t bind)
static void SYMAX_build_packet(uint8_t bind)
{
if (bind)
{
@ -151,7 +138,7 @@ void SYMAX_build_packet(uint8_t bind)
packet[2] = rudder;
packet[3] = aileron;
packet[4] = (flags & SYMAX_FLAG_VIDEO ? 0x80 : 0x00) | (flags & SYMAX_FLAG_PICTURE ? 0x40 : 0x00);
packet[5] = (elevator >> 2) | 0xc0; //always high rates (bit 7 is rate control) (flags & SYMAX_FLAG_RATES ? 0x80 : 0x00) | 0x40; // use trims to extend controls
packet[5] = (elevator >> 2) | 0xc0; //always high rates (bit 7 is rate control)
packet[6] = (rudder >> 2) | (flags & SYMAX_FLAG_FLIP ? 0x40 : 0x00);
packet[7] = (aileron >> 2) | (flags & SYMAX_FLAG_HEADLESS ? 0x80 : 0x00);
packet[8] = 0x00;
@ -159,7 +146,7 @@ void SYMAX_build_packet(uint8_t bind)
packet[9] = SYMAX_checksum(packet);
}
void SYMAX_send_packet(uint8_t bind)
static void SYMAX_send_packet(uint8_t bind)
{
if (sub_protocol==SYMAX5C)
SYMAX_build_packet_x5c(bind);
@ -232,7 +219,7 @@ static void symax_init()
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); // power on
}
void symax_init1()
static void symax_init1()
{
// duplicate stock tx sending strange packet (effect unknown)
uint8_t first_packet[] = {0xf9, 0x96, 0x82, 0x1b, 0x20, 0x08, 0x08, 0xf2, 0x7d, 0xef, 0xff, 0x00, 0x00, 0x00, 0x00};
@ -240,13 +227,6 @@ void symax_init1()
uint8_t chans_bind_x5c[] = {0x27, 0x1b, 0x39, 0x28, 0x24, 0x22, 0x2e, 0x36,
0x19, 0x21, 0x29, 0x14, 0x1e, 0x12, 0x2d, 0x18};
//uint8_t data_rx_tx_addr[] = {0x3b,0xb6,0x00,0x00,0xa2};
//uint8_t data_rx_tx_addr[] = {0x9A,0xe9,0x03,0x00,0xa2};//<<---- is ok
//uint8_t data_rx_tx_addr[] = {0x3b,0xb6,0x00,0x00,0xa2};//<<--- is ok
//uint8_t data_rx_tx_addr[] = {0x9A,0xe9,0x00,0x00,0xa2};
//uint8_t data_rx_tx_addr[] = {0x9A,0xe9,0x03,0x00,0xa2};//<<---- is ok
//uint8_t data_rx_tx_addr[] = {0x46,0x18,0x00,0x00,0xa2};
NRF24L01_FlushTx();
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x08);
NRF24L01_WritePayload(first_packet, 15);
@ -267,14 +247,12 @@ void symax_init1()
}
// channels determined by last byte of tx address
void symax_set_channels(uint8_t address)
static void symax_set_channels(uint8_t address)
{
static const uint8_t start_chans_1[] = {0x0a, 0x1a, 0x2a, 0x3a};
static const uint8_t start_chans_2[] = {0x2a, 0x0a, 0x42, 0x22};
static const uint8_t start_chans_3[] = {0x1a, 0x3a, 0x12, 0x32};
//static const uint8_t start_chans_4[] = {0x15, 0x35, 0x1d, 0x3d};
//static const uint8_t start_chans_5[] = {0x14, 0x34, 0x1c, 0x3c};
//static const uint8_t start_chans_6[] = {0x11, 0x21, 0x31, 0x41};
uint8_t laddress = address & 0x1f;
uint8_t i;
uint32_t *pchans = (uint32_t *)hopping_frequency; // avoid compiler warning
@ -312,7 +290,7 @@ void symax_set_channels(uint8_t address)
*pchans = 0x39194121;
}
void symax_init2()
static void symax_init2()
{
uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24,
0x27, 0x2c, 0x1c, 0x3e, 0x39, 0x2d, 0x22};

View File

@ -12,10 +12,11 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with WLToys V2x2, JXD JD38x, JD39x, JJRC H6C, Yizhan Tarantula X6 ...
// Last sync with hexfet new_protocols/v202_nrf24l01.c dated 2015-03-15
#if defined(V2X2_NRF24L01_INO)
// compatible with WLToys V2x2, JXD JD38x, JD39x, JJRC H6C, Yizhan Tarantula X6 ...
#include "iface_nrf24l01.h"
@ -73,9 +74,8 @@ static const uint8_t freq_hopping[][16] = {
{ 0x22, 0x27, 0x17, 0x39, 0x34, 0x28, 0x2B, 0x1D,
0x18, 0x2A, 0x21, 0x38, 0x10, 0x26, 0x20, 0x1F } // 03
};
//static uint8_t hopping_frequency[16];
void v202_init()
static void v202_init()
{
NRF24L01_Initialize();
@ -103,14 +103,12 @@ void v202_init()
NRF24L01_WriteReg(NRF24L01_15_RX_PW_P4, V2X2_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_16_RX_PW_P5, V2X2_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
uint8_t v2x2_rx_tx_addr[] = {0x66, 0x88, 0x68, 0x68, 0x68};
uint8_t rx_p1_addr[] = {0x88, 0x66, 0x86, 0x86, 0x86};
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, v2x2_rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_p1_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, v2x2_rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x66\x88\x68\x68\x68", 5);
NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, (uint8_t *)"\x88\x66\x86\x86\x86", 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x66\x88\x68\x68\x68", 5);
}
void V202_init2()
static void V202_init2()
{
NRF24L01_FlushTx();
packet_sent = 0;
@ -121,7 +119,7 @@ void V202_init2()
//Done by TX_EN??? => NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
}
void set_tx_id(void)
static void V2X2_set_tx_id(void)
{
uint8_t sum;
sum = rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3];
@ -136,7 +134,7 @@ void set_tx_id(void)
}
}
void add_pkt_checksum()
static void V2X2_add_pkt_checksum()
{
uint8_t sum = 0;
for (uint8_t i = 0; i < 15; ++i)
@ -144,7 +142,7 @@ void add_pkt_checksum()
packet[15] = sum;
}
void send_packet(uint8_t bind)
static void V2X2_send_packet(uint8_t bind)
{
uint8_t flags2=0;
if (bind)
@ -170,18 +168,15 @@ void send_packet(uint8_t bind)
packet[6] = 0x40; // roll
//Flags
flags=0;
// Channel 5
if (Servo_data[AUX1] > PPM_SWITCH)
flags |= V2X2_FLAG_FLIP;
if (Servo_AUX1) flags = V2X2_FLAG_FLIP;
// Channel 6
if (Servo_data[AUX2] > PPM_SWITCH)
flags |= V2X2_FLAG_LIGHT;
if (Servo_AUX2) flags |= V2X2_FLAG_LIGHT;
// Channel 7
if (Servo_data[AUX3] > PPM_SWITCH)
flags |= V2X2_FLAG_CAMERA;
if (Servo_AUX3) flags |= V2X2_FLAG_CAMERA;
// Channel 8
if (Servo_data[AUX4] > PPM_SWITCH)
flags |= V2X2_FLAG_VIDEO;
if (Servo_AUX4) flags |= V2X2_FLAG_VIDEO;
//Flags2
// Channel 9
@ -205,7 +200,7 @@ void send_packet(uint8_t bind)
packet[13] = 0x00;
//
packet[14] = flags;
add_pkt_checksum();
V2X2_add_pkt_checksum();
packet_sent = 0;
uint8_t rf_ch = hopping_frequency[hopping_frequency_no >> 1];
@ -213,7 +208,6 @@ void send_packet(uint8_t bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch);
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, V2X2_PAYLOADSIZE);
++packet_counter;
packet_sent = 1;
if (! hopping_frequency_no)
@ -237,7 +231,7 @@ uint16_t ReadV2x2()
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED) {
return PACKET_CHKTIME;
}
send_packet(1);
V2X2_send_packet(1);
if (--counter == 0) {
phase = V202_DATA;
BIND_DONE;
@ -247,7 +241,7 @@ uint16_t ReadV2x2()
if (packet_sent && NRF24L01_packet_ack() != PKT_ACKED) {
return PACKET_CHKTIME;
}
send_packet(0);
V2X2_send_packet(0);
break;
}
// Packet every 4ms
@ -256,8 +250,6 @@ uint16_t ReadV2x2()
uint16_t initV2x2()
{
flags=0;
packet_counter = 0;
v202_init();
//
if (IS_AUTOBIND_FLAG_on)
@ -267,7 +259,7 @@ uint16_t initV2x2()
}
else
phase = V202_INIT2_NO_BIND;
set_tx_id();
V2X2_set_tx_id();
return 50000;
}

View File

@ -12,6 +12,7 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// Last sync with hexfet new_protocols/yd717_nrf24l01.c dated 2015-09-28
#if defined(YD717_NRF24L01_INO)
@ -23,7 +24,7 @@
#define YD717_PACKET_CHKTIME 500 // Time to wait if packet not yet acknowledged or timed out
// Stock tx fixed frequency is 0x3C. Receiver only binds on this freq.
#define RF_CHANNEL 0x3C
#define YD717_RF_CHANNEL 0x3C
#define YD717_FLAG_FLIP 0x0F
#define YD717_FLAG_LIGHT 0x80
@ -32,7 +33,6 @@
#define YD717_FLAG_HEADLESS 0x10
#define YD717_PAYLOADSIZE 8 // receive data pipes set to this size, but unused
//#define YD717_MAX_PACKET_SIZE 9 // YD717 packets have 8-byte payload, Syma X4 is 9
enum {
YD717_INIT1 = 0,
@ -41,7 +41,7 @@ enum {
YD717_DATA
};
void yd717_send_packet(uint8_t bind)
static void yd717_send_packet(uint8_t bind)
{
uint8_t rudder_trim, elevator_trim, aileron_trim;
if (bind)
@ -93,23 +93,17 @@ void yd717_send_packet(uint8_t bind)
packet[6] = aileron_trim;
}
// Flags
// Channel 5
if (Servo_data[AUX1] > PPM_SWITCH)
flags = YD717_FLAG_FLIP;
else
flags=0;
// Channel 5
if (Servo_AUX1) flags = YD717_FLAG_FLIP;
// Channel 6
if (Servo_data[AUX2] > PPM_SWITCH)
flags |= YD717_FLAG_LIGHT;
if (Servo_AUX2) flags |= YD717_FLAG_LIGHT;
// Channel 7
if (Servo_data[AUX3] > PPM_SWITCH)
flags |= YD717_FLAG_PICTURE;
if (Servo_AUX3) flags |= YD717_FLAG_PICTURE;
// Channel 8
if (Servo_data[AUX4] > PPM_SWITCH)
flags |= YD717_FLAG_VIDEO;
if (Servo_AUX4) flags |= YD717_FLAG_VIDEO;
// Channel 9
if (Servo_data[AUX5] > PPM_SWITCH)
flags |= YD717_FLAG_HEADLESS;
if (Servo_AUX5) flags |= YD717_FLAG_HEADLESS;
packet[7] = flags;
}
@ -131,7 +125,7 @@ void yd717_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
void yd717_init()
static void yd717_init()
{
NRF24L01_Initialize();
@ -142,7 +136,7 @@ void yd717_init()
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3F); // Enable all data pipes
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_05_RF_CH, RF_CHANNEL); // Channel 3C
NRF24L01_WriteReg(NRF24L01_05_RF_CH, YD717_RF_CHANNEL); // Channel 3C
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
@ -168,23 +162,24 @@ void yd717_init()
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
void YD717_init1()
static void YD717_init1()
{
// for bind packets set address to prearranged value known to receiver
uint8_t bind_rx_tx_addr[] = {0x65, 0x65, 0x65, 0x65, 0x65};
if( sub_protocol==SYMAX2 )
for(uint8_t i=0; i < 5; i++)
uint8_t i;
if( sub_protocol==SYMAX4 )
for(i=0; i < 5; i++)
bind_rx_tx_addr[i] = 0x60;
else
if( sub_protocol==NIHUI )
for(uint8_t i=0; i < 5; i++)
for(i=0; i < 5; i++)
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);
}
void YD717_init2()
static void YD717_init2()
{
// set rx/tx address for data phase
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5);
@ -244,7 +239,6 @@ uint16_t yd717_callback()
uint16_t initYD717()
{
rx_tx_addr[4] = 0xC1; // always uses first data port
flags = 0;
yd717_init();
phase = YD717_INIT1;
BIND_IN_PROGRESS; // autobind protocol

View File

@ -83,13 +83,13 @@ void CYRF_SetTxRxMode(enum TXRX_State);
void CYRF_ConfigRFChannel(u8 ch);
void CYRF_SetPower(u8 power);
void CYRF_ConfigCRCSeed(u16 crc);
void CYRF_StartReceive();
static void CYRF_StartReceive();
void CYRF_ConfigSOPCode(const u8 *sopcodes);
void CYRF_ConfigDataCode(const u8 *datacodes, u8 len);
u8 CYRF_ReadRSSI(u32 dodummyread);
void CYRF_ReadDataPacket(u8 dpbuffer[]);
static u8 CYRF_ReadRSSI(u32 dodummyread);
static void CYRF_ReadDataPacket(u8 dpbuffer[]);
void CYRF_WriteDataPacket(const u8 dpbuffer[]);
void CYRF_WriteDataPacketLen(const u8 dpbuffer[], u8 len);
static void CYRF_WriteDataPacketLen(const u8 dpbuffer[], u8 len);
void CYRF_WriteRegister(u8 address, u8 data);
u8 CYRF_ReadRegister(u8 address);
void CYRF_WritePreamble(u32 preamble);

View File

@ -13,6 +13,8 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
//******************
// Protocols
//******************
enum PROTOCOLS
{
@ -32,6 +34,7 @@ enum PROTOCOLS
MODE_CG023 = 13, // =>NRF24L01 / CG023 protocol
MODE_BAYANG = 14, // =>NRF24L01 / BAYANG protocol
MODE_FRSKYX = 15, // =>CC2500 / FRSKYX protocol
MODE_ESKY = 16, // =>NRF24L01 / ESKY protocol
};
enum Flysky
{
@ -53,28 +56,129 @@ enum YD717
{
YD717=0,
SKYWLKR=1,
SYMAX2=2,
SYMAX4=2,
XINXUN=3,
NIHUI=4
};
enum KN
{
WLTOYS=0,
FEILUN=1
};
enum SYMAX
{
SYMAX=0,
SYMAX5C=1,
SYMAX5C=1
};
enum CX10 {
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE, // also compatible with CX10-A, CX12
DM007
CX10_BLUE=1, // also compatible with CX10-A, CX12
DM007=2,
Q282=3,
JC3015_1=4,
JC3015_2=5,
MK33041=6
};
enum CG023 {
enum CG023
{
CG023 = 0,
YD829 = 1,
H8_3D = 2
};
//******************
//TX definitions with timing endpoints and channels order
//******************
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX 2140
#define PPM_MIN 860
#define PPM_MAX_100 2012
#define PPM_MIN_100 988
enum chan_order{
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX 2100
#define PPM_MIN 900
#define PPM_MAX_100 1920
#define PPM_MIN_100 1120
enum chan_order{
ELEVATOR=0,
AILERON,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX 2000
#define PPM_MIN 1000
#define PPM_MAX_100 1900
#define PPM_MIN_100 1100
enum chan_order{
THROTTLE=0,
AILERON,
ELEVATOR,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX 2000
#define PPM_MIN 1000
#define PPM_MAX_100 1900
#define PPM_MIN_100 1100
enum chan_order{
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
#define PPM_MIN_COMMAND 1250
#define PPM_SWITCH 1550
#define PPM_MAX_COMMAND 1750
@ -143,6 +247,7 @@ enum CG023 {
#define LED_OFF PORTB &= ~_BV(5)
#define LED_TOGGLE PORTB ^= _BV(5)
#define LED_SET_OUTPUT DDRB |= _BV(5)
#define IS_LED_on ( (PORTB & _BV(5)) != 0x00 )
// Macros
#define NOP() __asm__ __volatile__("nop")
@ -183,8 +288,24 @@ enum CG023 {
#define BIND_DONE protocol_flags |= _BV(7)
#define IS_BIND_DONE_on ( ( protocol_flags & _BV(7) ) !=0 )
#define BAD_PROTO_off protocol_flags2 &= ~_BV(0)
#define BAD_PROTO_on protocol_flags2 |= _BV(0)
#define IS_BAD_PROTO_on ( ( protocol_flags2 & _BV(0) ) !=0 )
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000
#define BLINK_BAD_PROTO_TIME_HIGH 50
//AUX flags definition
#define Servo_AUX1 Servo_AUX & _BV(0)
#define Servo_AUX2 Servo_AUX & _BV(1)
#define Servo_AUX3 Servo_AUX & _BV(2)
#define Servo_AUX4 Servo_AUX & _BV(3)
#define Servo_AUX5 Servo_AUX & _BV(4)
#define Servo_AUX6 Servo_AUX & _BV(5)
#define Servo_AUX7 Servo_AUX & _BV(6)
#define Servo_AUX8 Servo_AUX & _BV(7)
//************************
//*** Power settings ***
@ -349,6 +470,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
CG023 13
Bayang 14
FrskyX 15
ESky 16
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
@ -369,9 +491,12 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX2 2
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
@ -379,6 +504,10 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
DM007 2
Q282 3
JC3015_1 4
JC3015_2 5
MK33041 6
sub_protocol==CG023
CG023 0
YD829 1
@ -426,6 +555,7 @@ Serial: 125000 Baud 8n1 _ xxxx xxxx - ---
CG023 13
Bayang 14
FrskyX 15
ESky 16
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
@ -446,9 +576,12 @@ Serial: 125000 Baud 8n1 _ xxxx xxxx - ---
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX2 2
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
@ -456,6 +589,10 @@ Serial: 125000 Baud 8n1 _ xxxx xxxx - ---
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
DM007 2
Q282 3
JC3015_1 4
JC3015_2 5
MK33041 6
sub_protocol==CG023
CG023 0
YD829 1

View File

@ -14,9 +14,8 @@
*/
void frskySendStuffed(uint8_t frame[])
static void frskySendStuffed(uint8_t frame[])
{
Serial_write(0x7E);
for (uint8_t i = 0; i < 9; i++) {
if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) {
@ -28,9 +27,7 @@ void frskySendStuffed(uint8_t frame[])
Serial_write(0x7E);
}
void frskySendFrame()
static void frskySendFrame()
{
uint8_t frame[9];
@ -54,16 +51,13 @@ void frskySendFrame()
frame[5] = frame[6] = frame[7] = frame[8] = 0;
}
frskySendStuffed(frame);
}
void frskyUpdate()
{
if(telemetry_link){
if(telemetry_link)
{
frskySendFrame();
telemetry_link=0;
}
}