mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-07-01 01:57:52 +00:00
New protocols and optimizations
New protocols: - FQ777 for FQ777-124 - MT99xx -> "LS" for 114/124
This commit is contained in:
parent
8dc5ae4f86
commit
6d546094ef
@ -24,10 +24,10 @@ void A7105_WriteData(uint8_t len, uint8_t channel)
|
||||
{
|
||||
uint8_t i;
|
||||
CS_off;
|
||||
A7105_Write(A7105_RST_WRPTR);
|
||||
A7105_Write(0x05);
|
||||
SPI_Write(A7105_RST_WRPTR);
|
||||
SPI_Write(0x05);
|
||||
for (i = 0; i < len; i++)
|
||||
A7105_Write(packet[i]);
|
||||
SPI_Write(packet[i]);
|
||||
CS_on;
|
||||
A7105_WriteReg(0x0F, channel);
|
||||
A7105_Strobe(A7105_TX);
|
||||
@ -37,7 +37,7 @@ void A7105_ReadData() {
|
||||
uint8_t i;
|
||||
A7105_Strobe(0xF0); //A7105_RST_RDPTR
|
||||
CS_off;
|
||||
A7105_Write(0x45);
|
||||
SPI_Write(0x45);
|
||||
for (i=0;i<16;i++)
|
||||
packet[i]=A7105_Read();
|
||||
CS_on;
|
||||
@ -45,53 +45,34 @@ void A7105_ReadData() {
|
||||
|
||||
void A7105_WriteReg(uint8_t address, uint8_t data) {
|
||||
CS_off;
|
||||
A7105_Write(address);
|
||||
SPI_Write(address);
|
||||
NOP();
|
||||
A7105_Write(data);
|
||||
SPI_Write(data);
|
||||
CS_on;
|
||||
}
|
||||
|
||||
uint8_t A7105_ReadReg(uint8_t address) {
|
||||
uint8_t result;
|
||||
CS_off;
|
||||
A7105_Write(address |=0x40); //bit 6 =1 for reading
|
||||
SPI_Write(address |=0x40); //bit 6 =1 for reading
|
||||
result = A7105_Read();
|
||||
CS_on;
|
||||
return(result);
|
||||
}
|
||||
|
||||
void A7105_Write(uint8_t command) {
|
||||
uint8_t n=8;
|
||||
|
||||
SCK_off;//SCK start low
|
||||
SDI_off;
|
||||
while(n--) {
|
||||
if(command&0x80)
|
||||
SDI_on;
|
||||
else
|
||||
SDI_off;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
command = command << 1;
|
||||
}
|
||||
SDI_on;
|
||||
}
|
||||
|
||||
uint8_t A7105_Read(void) {
|
||||
uint8_t result=0;
|
||||
uint8_t A7105_Read(void)
|
||||
{
|
||||
uint8_t result;
|
||||
uint8_t i;
|
||||
|
||||
SDI_SET_INPUT;
|
||||
for(i=0;i<8;i++) {
|
||||
for(i=0;i<8;i++)
|
||||
{
|
||||
result=result<<1;
|
||||
if(SDI_1) ///if SDIO =1
|
||||
result=(result<<1)|0x01;
|
||||
else
|
||||
result=result<<1;
|
||||
result |= 0x01;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
NOP();
|
||||
}
|
||||
SDI_SET_OUTPUT;
|
||||
return result;
|
||||
@ -122,7 +103,7 @@ uint8_t A7105_Reset()
|
||||
uint8_t result;
|
||||
|
||||
A7105_WriteReg(0x00, 0x00);
|
||||
_delay_us(1000);
|
||||
delayMicroseconds(1000);
|
||||
A7105_SetTxRxMode(TXRX_OFF); //Set both GPIO as output and low
|
||||
result=A7105_ReadReg(0x10) == 0x9E; //check if is reset.
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
@ -131,11 +112,11 @@ uint8_t A7105_Reset()
|
||||
|
||||
void A7105_WriteID(uint32_t ida) {
|
||||
CS_off;
|
||||
A7105_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0
|
||||
A7105_Write((ida>>24)&0xff);//53
|
||||
A7105_Write((ida>>16)&0xff);//75
|
||||
A7105_Write((ida>>8)&0xff);//c5
|
||||
A7105_Write((ida>>0)&0xff);//2a
|
||||
SPI_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0
|
||||
SPI_Write((ida>>24)&0xff);//53
|
||||
SPI_Write((ida>>16)&0xff);//75
|
||||
SPI_Write((ida>>8)&0xff);//c5
|
||||
SPI_Write((ida>>0)&0xff);//2a
|
||||
CS_on;
|
||||
}
|
||||
|
||||
@ -179,7 +160,7 @@ void A7105_SetPower()
|
||||
|
||||
void A7105_Strobe(uint8_t address) {
|
||||
CS_off;
|
||||
A7105_Write(address);
|
||||
SPI_Write(address);
|
||||
CS_on;
|
||||
}
|
||||
|
||||
|
@ -28,9 +28,9 @@ void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len)
|
||||
static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
|
||||
{
|
||||
CC25_CSN_off;
|
||||
CC2500_SPI_Write(address);
|
||||
SPI_Write(address);
|
||||
for(uint8_t i = 0; i < length; i++)
|
||||
data[i] = CC2500_SPI_Read();
|
||||
data[i] = SPI_Read();
|
||||
CC25_CSN_on;
|
||||
}
|
||||
|
||||
@ -39,9 +39,9 @@ static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t le
|
||||
static void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
|
||||
{
|
||||
CC25_CSN_off;
|
||||
CC2500_SPI_Write(CC2500_WRITE_BURST | address);
|
||||
SPI_Write(CC2500_WRITE_BURST | address);
|
||||
for(uint8_t i = 0; i < length; i++)
|
||||
CC2500_SPI_Write(data[i]);
|
||||
SPI_Write(data[i]);
|
||||
CC25_CSN_on;
|
||||
}
|
||||
|
||||
@ -52,62 +52,23 @@ void CC2500_WriteData(uint8_t *dpbuffer, uint8_t len)
|
||||
CC2500_Strobe(CC2500_STX);//0x35
|
||||
}
|
||||
|
||||
//--------------------------------------
|
||||
static void CC2500_SPI_Write(uint8_t command) {
|
||||
uint8_t n=8;
|
||||
|
||||
SCK_off;//SCK start low
|
||||
SDI_off;
|
||||
while(n--)
|
||||
{
|
||||
if(command&0x80)
|
||||
SDI_on;
|
||||
else
|
||||
SDI_off;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
command = command << 1;
|
||||
}
|
||||
SDI_on;
|
||||
}
|
||||
|
||||
//----------------------------
|
||||
void CC2500_WriteReg(uint8_t address, uint8_t data) {//same as 7105
|
||||
CC25_CSN_off;
|
||||
CC2500_SPI_Write(address);
|
||||
SPI_Write(address);
|
||||
NOP();
|
||||
CC2500_SPI_Write(data);
|
||||
SPI_Write(data);
|
||||
CC25_CSN_on;
|
||||
}
|
||||
|
||||
static uint8_t CC2500_SPI_Read(void)
|
||||
{
|
||||
uint8_t result;
|
||||
uint8_t i;
|
||||
result=0;
|
||||
for(i=0;i<8;i++)
|
||||
{
|
||||
if(SDO_1) ///
|
||||
result=(result<<1)|0x01;
|
||||
else
|
||||
result=result<<1;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
NOP();
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
//--------------------------------------------
|
||||
static uint8_t CC2500_ReadReg(uint8_t address)
|
||||
{
|
||||
uint8_t result;
|
||||
CC25_CSN_off;
|
||||
address |=0x80; //bit 7 =1 for reading
|
||||
CC2500_SPI_Write(address);
|
||||
result = CC2500_SPI_Read();
|
||||
SPI_Write(address);
|
||||
result = SPI_Read();
|
||||
CC25_CSN_on;
|
||||
return(result);
|
||||
}
|
||||
@ -115,7 +76,7 @@ static uint8_t CC2500_ReadReg(uint8_t address)
|
||||
void CC2500_Strobe(uint8_t address)
|
||||
{
|
||||
CC25_CSN_off;
|
||||
CC2500_SPI_Write(address);
|
||||
SPI_Write(address);
|
||||
CC25_CSN_on;
|
||||
}
|
||||
//------------------------
|
||||
@ -123,11 +84,11 @@ void CC2500_Strobe(uint8_t address)
|
||||
{
|
||||
// Toggle chip select signal
|
||||
CC25_CSN_on;
|
||||
_delay_us(30);
|
||||
delayMicroseconds(30);
|
||||
CC25_CSN_off;
|
||||
_delay_us(30);
|
||||
delayMicroseconds(30);
|
||||
CC25_CSN_on;
|
||||
_delay_us(45);
|
||||
delayMicroseconds(45);
|
||||
CC2500_Strobe(CC2500_SRES);
|
||||
_delay_ms(100);
|
||||
}
|
||||
@ -135,7 +96,7 @@ void CC2500_Strobe(uint8_t address)
|
||||
uint8_t CC2500_Reset()
|
||||
{
|
||||
CC2500_Strobe(CC2500_SRES);
|
||||
_delay_us(1000);
|
||||
delayMicroseconds(1000);
|
||||
CC2500_SetTxRxMode(TXRX_OFF);
|
||||
return CC2500_ReadReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
|
||||
}
|
||||
|
@ -215,7 +215,7 @@ uint16_t CX10_callback()
|
||||
NRF24L01_FlushTx();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
CX10_Write_Packet(1);
|
||||
_delay_us(400);
|
||||
delayMicroseconds(400);
|
||||
// switch to RX mode
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_FlushRx();
|
||||
|
@ -14,63 +14,12 @@
|
||||
*/
|
||||
#include "iface_cyrf6936.h"
|
||||
|
||||
#ifdef XMEGA
|
||||
#define XNOP() NOP()
|
||||
#else
|
||||
#define XNOP()
|
||||
#endif
|
||||
|
||||
static void cyrf_spi_write(uint8_t command)
|
||||
{
|
||||
uint8_t n=8;
|
||||
SCK_off;//SCK start low
|
||||
XNOP() ;
|
||||
SDI_off;
|
||||
XNOP() ;
|
||||
while(n--) {
|
||||
if(command&0x80)
|
||||
SDI_on;
|
||||
else
|
||||
SDI_off;
|
||||
XNOP() ;
|
||||
SCK_on;
|
||||
NOP();
|
||||
XNOP() ;
|
||||
XNOP() ;
|
||||
SCK_off;
|
||||
command = command << 1;
|
||||
XNOP() ;
|
||||
}
|
||||
SDI_on;
|
||||
}
|
||||
|
||||
static uint8_t cyrf_spi_read()
|
||||
{
|
||||
uint8_t result;
|
||||
uint8_t i;
|
||||
result=0;
|
||||
for(i=0;i<8;i++)
|
||||
{
|
||||
result<<=1;
|
||||
if(SDO_1) ///
|
||||
result|=0x01;
|
||||
SCK_on;
|
||||
XNOP() ;
|
||||
XNOP() ;
|
||||
NOP();
|
||||
SCK_off;
|
||||
XNOP() ;
|
||||
XNOP() ;
|
||||
NOP();
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void CYRF_WriteRegister(uint8_t address, uint8_t data)
|
||||
{
|
||||
CYRF_CSN_off;
|
||||
cyrf_spi_write(0x80 | address);
|
||||
cyrf_spi_write(data);
|
||||
SPI_Write(0x80 | address);
|
||||
SPI_Write(data);
|
||||
CYRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -79,9 +28,9 @@ static void CYRF_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8
|
||||
uint8_t i;
|
||||
|
||||
CYRF_CSN_off;
|
||||
cyrf_spi_write(0x80 | address);
|
||||
SPI_Write(0x80 | address);
|
||||
for(i = 0; i < length; i++)
|
||||
cyrf_spi_write(data[i]);
|
||||
SPI_Write(data[i]);
|
||||
CYRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -90,9 +39,9 @@ static void CYRF_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t leng
|
||||
uint8_t i;
|
||||
|
||||
CYRF_CSN_off;
|
||||
cyrf_spi_write(address);
|
||||
SPI_Write(address);
|
||||
for(i = 0; i < length; i++)
|
||||
data[i] = cyrf_spi_read();
|
||||
data[i] = SPI_Read();
|
||||
CYRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -100,8 +49,8 @@ uint8_t CYRF_ReadRegister(uint8_t address)
|
||||
{
|
||||
uint8_t data;
|
||||
CYRF_CSN_off;
|
||||
cyrf_spi_write(address);
|
||||
data = cyrf_spi_read();
|
||||
SPI_Write(address);
|
||||
data = SPI_Read();
|
||||
CYRF_CSN_on;
|
||||
return data;
|
||||
}
|
||||
@ -110,11 +59,11 @@ uint8_t CYRF_ReadRegister(uint8_t address)
|
||||
uint8_t CYRF_Reset()
|
||||
{
|
||||
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x01);//software reset
|
||||
_delay_us(200);//
|
||||
delayMicroseconds(200);//
|
||||
// RS_HI;
|
||||
// _delay_us(100);
|
||||
// delayMicroseconds(100);
|
||||
// RS_LO;
|
||||
// _delay_us(100);
|
||||
// delayMicroseconds(100);
|
||||
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0); //Enable XOUT as GPIO
|
||||
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04); //Enable PACTL as GPIO
|
||||
CYRF_SetTxRxMode(TXRX_OFF);
|
||||
@ -211,10 +160,10 @@ void CYRF_ConfigDataCode(const uint8_t *datacodes, uint8_t len)
|
||||
void CYRF_WritePreamble(uint32_t preamble)
|
||||
{
|
||||
CYRF_CSN_off;
|
||||
cyrf_spi_write(0x80 | 0x24);
|
||||
cyrf_spi_write(preamble & 0xff);
|
||||
cyrf_spi_write((preamble >> 8) & 0xff);
|
||||
cyrf_spi_write((preamble >> 16) & 0xff);
|
||||
SPI_Write(0x80 | 0x24);
|
||||
SPI_Write(preamble & 0xff);
|
||||
SPI_Write((preamble >> 8) & 0xff);
|
||||
SPI_Write((preamble >> 16) & 0xff);
|
||||
CYRF_CSN_on;
|
||||
}
|
||||
/*
|
||||
@ -277,13 +226,13 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
|
||||
CYRF_ConfigCRCSeed(0x0000);
|
||||
CYRF_SetTxRxMode(RX_EN);
|
||||
//Wait for pre-amp to switch from send to receive
|
||||
_delay_us(1000);
|
||||
delayMicroseconds(1000);
|
||||
for(i = 0; i < NUM_FREQ; i++)
|
||||
{
|
||||
CYRF_ConfigRFChannel(i);
|
||||
CYRF_ReadRegister(CYRF_13_RSSI);
|
||||
CYRF_StartReceive();
|
||||
_delay_us(10);
|
||||
delayMicroseconds(10);
|
||||
rssi[i] = CYRF_ReadRegister(CYRF_13_RSSI);
|
||||
}
|
||||
|
||||
|
205
Multiprotocol/FQ777_nrf24l01.ino
Normal file
205
Multiprotocol/FQ777_nrf24l01.ino
Normal file
@ -0,0 +1,205 @@
|
||||
/*
|
||||
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 bikemike FQ777-124.ino
|
||||
|
||||
#if defined(FQ777_NRF24L01_INO)
|
||||
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
#define FQ777_INITIAL_WAIT 500
|
||||
#define FQ777_PACKET_PERIOD 1500
|
||||
#define FQ777_PACKET_SIZE 8
|
||||
#define FQ777_BIND_COUNT 1000
|
||||
#define FQ777_NUM_RF_CHANNELS 4
|
||||
|
||||
enum {
|
||||
FQ777_FLAG_RETURN = 0x40, // 0x40 when not off, !0x40 when one key return
|
||||
FQ777_FLAG_HEADLESS = 0x04,
|
||||
FQ777_FLAG_EXPERT = 0x01,
|
||||
FQ777_FLAG_FLIP = 0x80,
|
||||
};
|
||||
|
||||
const uint8_t ssv_xor[] = {0x80,0x44,0x64,0x75,0x6C,0x71,0x2A,0x36,0x7C,0xF1,0x6E,0x52,0x9,0x9D,0x1F,0x78,0x3F,0xE1,0xEE,0x16,0x6D,0xE8,0x73,0x9,0x15,0xD7,0x92,0xE7,0x3,0xBA};
|
||||
uint8_t FQ777_bind_addr [] = {0xe7,0xe7,0xe7,0xe7,0x67};
|
||||
|
||||
static void __attribute__((unused)) ssv_pack_dpl(uint8_t addr[], uint8_t pid, uint8_t* len, uint8_t* payload, uint8_t* packed_payload)
|
||||
{
|
||||
uint8_t i = 0;
|
||||
|
||||
uint16_t pcf = (*len & 0x3f) << 3;
|
||||
pcf |= (pid & 0x3) << 1;
|
||||
pcf |= 0x00; // noack field
|
||||
|
||||
uint8_t header[7] = {0};
|
||||
header[6] = pcf;
|
||||
header[5] = (pcf >> 7) | (addr[0] << 1);
|
||||
header[4] = (addr[0] >> 7) | (addr[1] << 1);
|
||||
header[3] = (addr[1] >> 7) | (addr[2] << 1);
|
||||
header[2] = (addr[2] >> 7) | (addr[3] << 1);
|
||||
header[1] = (addr[3] >> 7) | (addr[4] << 1);
|
||||
header[0] = (addr[4] >> 7);
|
||||
|
||||
// calculate the crc
|
||||
union
|
||||
{
|
||||
uint8_t bytes[2];
|
||||
uint16_t val;
|
||||
} crc;
|
||||
|
||||
for (i = 0; i < 7; ++i)
|
||||
crc.val=crc16_update(0x3c18,header[i]);
|
||||
for (i = 0; i < *len; ++i)
|
||||
crc.val=crc16_update(crc.val,payload[i]);
|
||||
|
||||
// encode payload and crc
|
||||
// xor with this:
|
||||
for (i = 0; i < *len; ++i)
|
||||
payload[i] ^= ssv_xor[i];
|
||||
crc.bytes[1] ^= ssv_xor[i++];
|
||||
crc.bytes[0] ^= ssv_xor[i++];
|
||||
|
||||
// pack the pcf, payload, and crc into packed_payload
|
||||
packed_payload[0] = pcf >> 1;
|
||||
packed_payload[1] = (pcf << 7) | (payload[0] >> 1);
|
||||
|
||||
for (i = 0; i < *len - 1; ++i)
|
||||
packed_payload[i+2] = (payload[i] << 7) | (payload[i+1] >> 1);
|
||||
|
||||
packed_payload[i+2] = (payload[i] << 7) | (crc.val >> 9);
|
||||
++i;
|
||||
packed_payload[i+2] = (crc.val >> 1 & 0x80 ) | (crc.val >> 1 & 0x7F);
|
||||
++i;
|
||||
packed_payload[i+2] = (crc.val << 7);
|
||||
|
||||
*len += 4;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) FQ777_send_packet(uint8_t bind)
|
||||
{
|
||||
uint8_t packet_len = FQ777_PACKET_SIZE;
|
||||
uint8_t packet_ori[8];
|
||||
if (bind)
|
||||
{
|
||||
// 4,5,6 = address fields
|
||||
// last field is checksum of address fields
|
||||
packet_ori[0] = 0x20;
|
||||
packet_ori[1] = 0x15;
|
||||
packet_ori[2] = 0x05;
|
||||
packet_ori[3] = 0x06;
|
||||
packet_ori[4] = rx_tx_addr[0];
|
||||
packet_ori[5] = rx_tx_addr[1];
|
||||
packet_ori[6] = rx_tx_addr[2];
|
||||
packet_ori[7] = packet[4] + packet[5] + packet[6];
|
||||
}
|
||||
else
|
||||
{
|
||||
// throt, yaw, pitch, roll, trims, flags/left button,00,right button
|
||||
//0-3 0x00-0x64
|
||||
//4 roll/pitch/yaw trims. cycles through one trim at a time - 0-40 trim1, 40-80 trim2, 80-C0 trim3 (center: A0 20 60)
|
||||
//5 flags for throttle button, two buttons above throttle - def: 0x40
|
||||
//6 00 ??
|
||||
//7 checksum - add values in other fields
|
||||
|
||||
/*
|
||||
// Trims are usually done through the radio configuration but leaving the code here just in case...
|
||||
uint8_t trim_mod = packet_count % 144;
|
||||
uint8_t trim_val = 0;
|
||||
if (36 <= trim_mod && trim_mod < 72) // yaw
|
||||
trim_val = 0x20; // don't modify yaw trim
|
||||
else
|
||||
if (108 < trim_mod && trim_mod) // pitch
|
||||
trim_val = map(ppm[FQ777124_TRIM_CHAN_PITCH], PPM_MIN, PPM_MAX, 0x01, 0x3E) + 0xA0 - 0x1F;
|
||||
else // roll
|
||||
trim_val = map(ppm[FQ777124_TRIM_CHAN_ROLL], PPM_MIN, PPM_MAX, 0x01, 0x3E) + 0x60 - 0x1F;*/
|
||||
|
||||
packet_ori[0] = convert_channel_8b_scale(THROTTLE,0,0x64);
|
||||
packet_ori[1] = convert_channel_8b_scale(RUDDER,0,0x64);
|
||||
packet_ori[2] = convert_channel_8b_scale(ELEVATOR,0,0x64);
|
||||
packet_ori[3] = convert_channel_8b_scale(AILERON,0,0x64);
|
||||
packet_ori[4] = 0x20; //trim_val; // calculated above
|
||||
packet_ori[5] = GET_FLAG(Servo_AUX1, FQ777_FLAG_FLIP)
|
||||
| GET_FLAG(Servo_AUX3, FQ777_FLAG_HEADLESS)
|
||||
| GET_FLAG(!Servo_AUX2, FQ777_FLAG_RETURN)
|
||||
| GET_FLAG(Servo_AUX4,FQ777_FLAG_EXPERT);
|
||||
|
||||
packet_ori[6] = 0x00;
|
||||
// calculate checksum
|
||||
uint8_t checksum = 0;
|
||||
for (int i = 0; i < 7; ++i)
|
||||
checksum += packet_ori[i];
|
||||
packet_ori[7] = checksum;
|
||||
|
||||
//packet_count++;
|
||||
}
|
||||
|
||||
ssv_pack_dpl( (0 == bind) ? rx_tx_addr : FQ777_bind_addr, hopping_frequency_no, &packet_len, packet_ori, packet);
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG,_BV(NRF24L01_00_PWR_UP));
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
|
||||
hopping_frequency_no %= FQ777_NUM_RF_CHANNELS;
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
NRF24L01_WritePayload(packet, packet_len);
|
||||
NRF24L01_WritePayload(packet, packet_len);
|
||||
NRF24L01_WritePayload(packet, packet_len);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) FQ777_init()
|
||||
{
|
||||
NRF24L01_Initialize();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, FQ777_bind_addr, 5);
|
||||
NRF24L01_FlushTx();
|
||||
NRF24L01_FlushRx();
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement on all data pipes
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x00);
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03);
|
||||
NRF24L01_SetBitrate(NRF24L01_BR_250K);
|
||||
NRF24L01_SetPower();
|
||||
}
|
||||
|
||||
uint16_t FQ777_callback()
|
||||
{
|
||||
if(bind_counter!=0)
|
||||
{
|
||||
FQ777_send_packet(1);
|
||||
if (bind_counter-- == 0)
|
||||
{
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
|
||||
BIND_DONE;
|
||||
}
|
||||
}
|
||||
else
|
||||
FQ777_send_packet(0);
|
||||
return FQ777_PACKET_PERIOD;
|
||||
}
|
||||
|
||||
uint16_t initFQ777(void)
|
||||
{
|
||||
BIND_IN_PROGRESS; // autobind protocol
|
||||
bind_counter = FQ777_BIND_COUNT;
|
||||
hopping_frequency[0] = 0x4D;
|
||||
hopping_frequency[1] = 0x43;
|
||||
hopping_frequency[2] = 0x27;
|
||||
hopping_frequency[3] = 0x07;
|
||||
hopping_frequency_no=0;
|
||||
rx_tx_addr[2] = 0x00;
|
||||
rx_tx_addr[3] = 0xe7;
|
||||
rx_tx_addr[4] = 0x67;
|
||||
FQ777_init();
|
||||
return FQ777_INITIAL_WAIT;
|
||||
}
|
||||
|
||||
#endif
|
@ -235,9 +235,9 @@ uint16_t ReadHubsan()
|
||||
phase &= ~WAIT_WRITE;
|
||||
if(id_data == ID_PLUS)
|
||||
{
|
||||
if(state == BIND_7 && packet[2] == 9)
|
||||
if(phase == BIND_7 && packet[2] == 9)
|
||||
{
|
||||
state = DATA_1;
|
||||
phase = DATA_1;
|
||||
A7105_WriteReg(A7105_1F_CODE_I, 0x0F);
|
||||
BIND_DONE;
|
||||
return 4500;
|
||||
|
@ -12,7 +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/>.
|
||||
*/
|
||||
// compatible with MT99xx, Eachine H7, Yi Zhan i6S
|
||||
// compatible with MT99xx, Eachine H7, Yi Zhan i6S and LS114/124
|
||||
// Last sync with Goebish mt99xx_nrf24l01.c dated 2016-01-29
|
||||
|
||||
#if defined(MT99XX_NRF24L01_INO)
|
||||
@ -43,34 +43,54 @@ enum {
|
||||
MT99XX_DATA
|
||||
};
|
||||
|
||||
const uint8_t h7_mys_byte[] = {
|
||||
0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14,
|
||||
0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10
|
||||
};
|
||||
|
||||
static const u8 ls_mys_byte[] = {
|
||||
0x05, 0x15, 0x25, 0x06, 0x16, 0x26,
|
||||
0x07, 0x17, 0x27, 0x00, 0x10, 0x20,
|
||||
0x01, 0x11, 0x21, 0x02, 0x12, 0x22,
|
||||
0x03, 0x13, 0x23, 0x04, 0x14, 0x24
|
||||
};
|
||||
|
||||
static void __attribute__((unused)) MT99XX_send_packet()
|
||||
{
|
||||
const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60};
|
||||
const uint8_t mys_byte[] = {
|
||||
0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14,
|
||||
0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10
|
||||
};
|
||||
static uint8_t yz_seq_num=0;
|
||||
static uint8_t ls_counter=0;
|
||||
|
||||
if(sub_protocol != YZ)
|
||||
{ // MT99XX & H7
|
||||
{ // MT99XX & H7 & LS
|
||||
packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0xE1); // throttle
|
||||
packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0xE1); // rudder
|
||||
packet[2] = convert_channel_8b_scale(AILERON ,0x00,0xE1); // aileron
|
||||
packet[3] = convert_channel_8b_scale(ELEVATOR,0x00,0xE1); // elevator
|
||||
packet[4] = 0x20; // pitch trim (0x3f-0x20-0x00)
|
||||
packet[5] = 0x20; // roll trim (0x00-0x20-0x3f)
|
||||
packet[6] = GET_FLAG( Servo_AUX1, FLAG_MT_FLIP )
|
||||
| GET_FLAG( Servo_AUX3, FLAG_MT_SNAPSHOT )
|
||||
| GET_FLAG( Servo_AUX4, FLAG_MT_VIDEO );
|
||||
if(sub_protocol==MT99)
|
||||
packet[6] |= 0x40 | FLAG_MT_RATE2;
|
||||
packet[6] = GET_FLAG( Servo_AUX1, FLAG_MT_FLIP );
|
||||
packet[7] = h7_mys_byte[hopping_frequency_no]; // next rf channel index ?
|
||||
|
||||
if(sub_protocol==H7)
|
||||
packet[6]|=FLAG_MT_RATE1; // max rate on H7
|
||||
else
|
||||
packet[6] |= FLAG_MT_RATE1; // max rate on H7
|
||||
// todo: mys_byte = next channel index ?
|
||||
// low nibble: index in chan list ?
|
||||
// high nibble: 0->start from start of list, 1->start from end of list ?
|
||||
packet[7] = mys_byte[hopping_frequency_no];
|
||||
if(sub_protocol==MT99)
|
||||
packet[6] |= 0x40 | FLAG_MT_RATE2
|
||||
| GET_FLAG( Servo_AUX3, FLAG_MT_SNAPSHOT )
|
||||
| GET_FLAG( Servo_AUX4, FLAG_MT_VIDEO ); // max rate on MT99xx
|
||||
else
|
||||
if(sub_protocol==LS)
|
||||
packet[6] |= 0x40 | FLAG_MT_RATE2;
|
||||
else //LS
|
||||
{
|
||||
packet[6] |= FLAG_MT_RATE2 // max rate
|
||||
| GET_FLAG( Servo_AUX5, 0x10 ); //HEADLESS
|
||||
packet[7] = ls_mys_byte[ls_counter++];
|
||||
if(ls_counter >= sizeof(ls_mys_byte))
|
||||
ls_counter=0;
|
||||
}
|
||||
|
||||
uint8_t result=checksum_offset;
|
||||
for(uint8_t i=0; i<8; i++)
|
||||
result += packet[i];
|
||||
@ -102,7 +122,10 @@ static void __attribute__((unused)) MT99XX_send_packet()
|
||||
packet[8] = 0xff;
|
||||
}
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no] + channel_offset);
|
||||
if(sub_protocol == LS)
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // LS always transmits on the same channel
|
||||
else
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no] + channel_offset);
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
XN297_WritePayload(packet, MT99XX_PACKET_SIZE);
|
||||
@ -120,8 +143,11 @@ static void __attribute__((unused)) MT99XX_send_packet()
|
||||
static void __attribute__((unused)) MT99XX_init()
|
||||
{
|
||||
NRF24L01_Initialize();
|
||||
if(sub_protocol == YZ)
|
||||
XN297_SetScrambledMode(XN297_UNSCRAMBLED);
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
NRF24L01_FlushTx();
|
||||
XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5);
|
||||
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
|
||||
@ -133,19 +159,26 @@ static void __attribute__((unused)) MT99XX_init()
|
||||
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
|
||||
NRF24L01_SetPower();
|
||||
|
||||
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) | (sub_protocol == YZ ? BV(XN297_UNSCRAMBLED):0) );
|
||||
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) );
|
||||
|
||||
XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) MT99XX_initialize_txid()
|
||||
{
|
||||
rx_tx_addr[3] = 0xCC;
|
||||
rx_tx_addr[4] = 0xCC;
|
||||
if(sub_protocol == YZ)
|
||||
{
|
||||
rx_tx_addr[0] = 0x53; // test (SB id)
|
||||
rx_tx_addr[1] = 0x00;
|
||||
rx_tx_addr[2] = 0x00;
|
||||
}
|
||||
checksum_offset = (rx_tx_addr[0] + rx_tx_addr[1]) & 0xff;
|
||||
else
|
||||
if(sub_protocol == LS)
|
||||
rx_tx_addr[0] = 0xCC;
|
||||
else //MT99 & H7
|
||||
rx_tx_addr[2] = 0x00;
|
||||
checksum_offset = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2];
|
||||
channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8;
|
||||
}
|
||||
|
||||
@ -157,16 +190,16 @@ uint16_t MT99XX_callback()
|
||||
{
|
||||
if (bind_counter == 0)
|
||||
{
|
||||
rx_tx_addr[2] = 0x00;
|
||||
rx_tx_addr[3] = 0xCC;
|
||||
rx_tx_addr[4] = 0xCC;
|
||||
// set tx address for data packets
|
||||
XN297_SetTXAddr(rx_tx_addr, 5);
|
||||
BIND_DONE;
|
||||
}
|
||||
else
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
|
||||
if(sub_protocol == LS)
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // LS always transmits on the same channel
|
||||
else
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
XN297_WritePayload(packet, MT99XX_PACKET_SIZE); // bind packet
|
||||
@ -193,23 +226,30 @@ uint16_t initMT99XX(void)
|
||||
MT99XX_init();
|
||||
|
||||
packet[0] = 0x20;
|
||||
if(sub_protocol!=YZ)
|
||||
packet_period = MT99XX_PACKET_PERIOD_MT;
|
||||
switch(sub_protocol)
|
||||
{ // MT99 & H7
|
||||
packet_period = MT99XX_PACKET_PERIOD_MT;
|
||||
packet[1] = 0x14;
|
||||
packet[2] = 0x03;
|
||||
packet[3] = 0x25;
|
||||
case MT99:
|
||||
case H7:
|
||||
packet[1] = 0x14;
|
||||
packet[2] = 0x03;
|
||||
packet[3] = 0x25;
|
||||
break;
|
||||
case YZ:
|
||||
packet_period = MT99XX_PACKET_PERIOD_YZ;
|
||||
packet[1] = 0x15;
|
||||
packet[2] = 0x05;
|
||||
packet[3] = 0x06;
|
||||
break;
|
||||
case LS:
|
||||
packet[1] = 0x14;
|
||||
packet[2] = 0x05;
|
||||
packet[3] = 0x11;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{ // YZ
|
||||
packet_period = MT99XX_PACKET_PERIOD_YZ;
|
||||
packet[1] = 0x15;
|
||||
packet[2] = 0x05;
|
||||
packet[3] = 0x06;
|
||||
}
|
||||
packet[4] = rx_tx_addr[0]; // 1st byte for data state tx address
|
||||
packet[5] = rx_tx_addr[1]; // 2nd byte for data state tx address (always 0x00 on Yi Zhan ?)
|
||||
packet[6] = 0x00; // 3rd byte for data state tx address (always 0x00 ?)
|
||||
packet[4] = rx_tx_addr[0];
|
||||
packet[5] = rx_tx_addr[1];
|
||||
packet[6] = rx_tx_addr[2];
|
||||
packet[7] = checksum_offset; // checksum offset
|
||||
packet[8] = 0xAA; // fixed
|
||||
packet_count=0;
|
||||
|
@ -50,7 +50,8 @@ enum PROTOCOLS
|
||||
MODE_SHENQI=19, // =>NRF24L01
|
||||
MODE_FY326=20, // =>NRF24L01
|
||||
MODE_SFHSS=21, // =>CC2500
|
||||
MODE_J6PRO=22 // =>CYRF6936
|
||||
MODE_J6PRO=22, // =>CYRF6936
|
||||
MODE_FQ777=23 // =>NRF24L01
|
||||
};
|
||||
|
||||
enum Flysky
|
||||
@ -108,7 +109,8 @@ enum MT99XX
|
||||
{
|
||||
MT99 = 0,
|
||||
H7 = 1,
|
||||
YZ = 2
|
||||
YZ = 2,
|
||||
LS = 3
|
||||
};
|
||||
enum MJXQ
|
||||
{
|
||||
@ -512,6 +514,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
FY326 20
|
||||
SFHSS 21
|
||||
J6PRO 22
|
||||
FQ777 23
|
||||
BindBit=> 0x80 1=Bind/0=No
|
||||
AutoBindBit=> 0x40 1=Yes /0=No
|
||||
RangeCheck=> 0x20 1=Yes /0=No
|
||||
@ -558,6 +561,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
MT99 0
|
||||
H7 1
|
||||
YZ 2
|
||||
LS 3
|
||||
sub_protocol==MJXQ
|
||||
WLH08 0
|
||||
X600 1
|
||||
|
@ -22,7 +22,6 @@
|
||||
*/
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <util/delay.h>
|
||||
#include "Multiprotocol.h"
|
||||
|
||||
//#define DEBUG_TX
|
||||
@ -53,7 +52,6 @@ uint8_t phase;
|
||||
uint16_t bind_counter;
|
||||
uint8_t bind_phase;
|
||||
uint8_t binding_idx;
|
||||
uint32_t packet_counter;
|
||||
uint16_t packet_period;
|
||||
uint8_t packet_count;
|
||||
uint8_t packet_sent;
|
||||
@ -66,7 +64,7 @@ uint8_t throttle, rudder, elevator, aileron;
|
||||
uint8_t flags;
|
||||
uint16_t crc;
|
||||
//
|
||||
uint32_t state;
|
||||
uint16_t state;
|
||||
uint8_t len;
|
||||
uint8_t RX_num;
|
||||
|
||||
@ -558,6 +556,12 @@ static void protocol_init()
|
||||
next_callback=initFY326();
|
||||
remote_callback = FY326_callback;
|
||||
break;
|
||||
#endif
|
||||
#if defined(FQ777_NRF24L01_INO)
|
||||
case MODE_FQ777:
|
||||
next_callback=initFQ777();
|
||||
remote_callback = FQ777_callback;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -648,7 +652,7 @@ static void module_reset()
|
||||
case MODE_J6PRO:
|
||||
CYRF_Reset();
|
||||
break;
|
||||
default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI, MODE_FY326
|
||||
default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI, MODE_FY326, MODE_FQ777
|
||||
NRF24L01_Reset();
|
||||
break;
|
||||
}
|
||||
@ -824,6 +828,166 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
return id;
|
||||
}
|
||||
|
||||
/********************/
|
||||
/** SPI routines **/
|
||||
/********************/
|
||||
void SPI_Write(uint8_t command)
|
||||
{
|
||||
uint8_t n=8;
|
||||
|
||||
SCK_off;//SCK start low
|
||||
SDI_off;
|
||||
do
|
||||
{
|
||||
if(command&0x80)
|
||||
SDI_on;
|
||||
else
|
||||
SDI_off;
|
||||
SCK_on;
|
||||
command = command << 1;
|
||||
SCK_off;
|
||||
}
|
||||
while(--n) ;
|
||||
SDI_on;
|
||||
}
|
||||
|
||||
uint8_t SPI_Read(void)
|
||||
{
|
||||
uint8_t result;
|
||||
uint8_t i;
|
||||
for(i=0;i<8;i++)
|
||||
{
|
||||
result=result<<1;
|
||||
if(SDO_1)
|
||||
result |= 0x01;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/************************************/
|
||||
/** Arduino replacement routines **/
|
||||
/************************************/
|
||||
// replacement millis() and micros()
|
||||
// These work polled, no interrupts
|
||||
// micros() MUST be called at least once every 32 milliseconds
|
||||
uint16_t MillisPrecount ;
|
||||
uint16_t lastTimerValue ;
|
||||
uint32_t TotalMicros ;
|
||||
uint32_t TotalMillis ;
|
||||
uint8_t Correction ;
|
||||
|
||||
uint32_t micros()
|
||||
{
|
||||
uint16_t elapsed ;
|
||||
uint8_t millisToAdd ;
|
||||
uint8_t oldSREG = SREG ;
|
||||
cli() ;
|
||||
uint16_t time = TCNT1 ; // Read timer 1
|
||||
SREG = oldSREG ;
|
||||
|
||||
elapsed = time - lastTimerValue ;
|
||||
elapsed += Correction ;
|
||||
Correction = elapsed & 0x01 ;
|
||||
elapsed >>= 1 ;
|
||||
|
||||
uint32_t ltime = TotalMicros ;
|
||||
ltime += elapsed ;
|
||||
cli() ;
|
||||
TotalMicros = ltime ; // Done this way for RPM to work correctly
|
||||
lastTimerValue = time ;
|
||||
SREG = oldSREG ; // Still valid from above
|
||||
|
||||
elapsed += MillisPrecount;
|
||||
millisToAdd = 0 ;
|
||||
|
||||
if ( elapsed > 15999 )
|
||||
{
|
||||
millisToAdd = 16 ;
|
||||
elapsed -= 16000 ;
|
||||
}
|
||||
if ( elapsed > 7999 )
|
||||
{
|
||||
millisToAdd += 8 ;
|
||||
elapsed -= 8000 ;
|
||||
}
|
||||
if ( elapsed > 3999 )
|
||||
{
|
||||
millisToAdd += 4 ;
|
||||
elapsed -= 4000 ;
|
||||
}
|
||||
if ( elapsed > 1999 )
|
||||
{
|
||||
millisToAdd += 2 ;
|
||||
elapsed -= 2000 ;
|
||||
}
|
||||
if ( elapsed > 999 )
|
||||
{
|
||||
millisToAdd += 1 ;
|
||||
elapsed -= 1000 ;
|
||||
}
|
||||
TotalMillis += millisToAdd ;
|
||||
MillisPrecount = elapsed ;
|
||||
return TotalMicros ;
|
||||
}
|
||||
|
||||
uint32_t millis()
|
||||
{
|
||||
micros() ;
|
||||
return TotalMillis ;
|
||||
}
|
||||
|
||||
void delay(unsigned long ms)
|
||||
{
|
||||
uint16_t start = (uint16_t)micros();
|
||||
uint16_t lms = ms ;
|
||||
|
||||
while (lms > 0) {
|
||||
if (((uint16_t)micros() - start) >= 1000) {
|
||||
lms--;
|
||||
start += 1000;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Delay for the given number of microseconds. Assumes a 8 or 16 MHz clock. */
|
||||
void delayMicroseconds(unsigned int us)
|
||||
{
|
||||
// calling avrlib's delay_us() function with low values (e.g. 1 or
|
||||
// 2 microseconds) gives delays longer than desired.
|
||||
//delay_us(us);
|
||||
|
||||
// for the 16 MHz clock on most Arduino boards
|
||||
|
||||
// for a one-microsecond delay, simply return. the overhead
|
||||
// of the function call yields a delay of approximately 1 1/8 us.
|
||||
if (--us == 0)
|
||||
return;
|
||||
|
||||
// the following loop takes a quarter of a microsecond (4 cycles)
|
||||
// per iteration, so execute it four times for each microsecond of
|
||||
// delay requested.
|
||||
us <<= 2;
|
||||
|
||||
// account for the time taken in the preceeding commands.
|
||||
us -= 2;
|
||||
|
||||
// busy wait
|
||||
__asm__ __volatile__ (
|
||||
"1: sbiw %0,1" "\n\t" // 2 cycles
|
||||
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
|
||||
);
|
||||
}
|
||||
|
||||
void init()
|
||||
{
|
||||
// this needs to be called before setup() or some functions won't
|
||||
// work there
|
||||
sei();
|
||||
}
|
||||
|
||||
/**************************/
|
||||
/**************************/
|
||||
/** Interrupt routines **/
|
||||
|
@ -19,45 +19,6 @@
|
||||
//---------------------------
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
static void nrf_spi_write(uint8_t command)
|
||||
{
|
||||
uint8_t n=8;
|
||||
|
||||
SCK_off;//SCK start low
|
||||
SDI_off;
|
||||
while(n--) {
|
||||
if(command&0x80)
|
||||
SDI_on;
|
||||
else
|
||||
SDI_off;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
command = command << 1;
|
||||
}
|
||||
SDI_on;
|
||||
}
|
||||
|
||||
//VARIANT 2
|
||||
static uint8_t nrf_spi_read(void)
|
||||
{
|
||||
uint8_t result;
|
||||
uint8_t i;
|
||||
result=0;
|
||||
for(i=0;i<8;i++) {
|
||||
result<<=1;
|
||||
if(SDO_1) ///
|
||||
result|=0x01;
|
||||
SCK_on;
|
||||
NOP();
|
||||
SCK_off;
|
||||
NOP();
|
||||
}
|
||||
return result;
|
||||
}
|
||||
//--------------------------------------------
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
// NRF24L01+ SPI Specific Functions
|
||||
@ -73,8 +34,8 @@ void NRF24L01_Initialize()
|
||||
void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(W_REGISTER | (REGISTER_MASK & reg));
|
||||
nrf_spi_write(data);
|
||||
SPI_Write(W_REGISTER | (REGISTER_MASK & reg));
|
||||
SPI_Write(data);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -82,26 +43,26 @@ void NRF24L01_WriteRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
|
||||
nrf_spi_write(W_REGISTER | ( REGISTER_MASK & reg));
|
||||
SPI_Write(W_REGISTER | ( REGISTER_MASK & reg));
|
||||
for (uint8_t i = 0; i < length; i++)
|
||||
nrf_spi_write(data[i]);
|
||||
SPI_Write(data[i]);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
void NRF24L01_WritePayload(uint8_t * data, uint8_t length)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(W_TX_PAYLOAD);
|
||||
SPI_Write(W_TX_PAYLOAD);
|
||||
for (uint8_t i = 0; i < length; i++)
|
||||
nrf_spi_write(data[i]);
|
||||
SPI_Write(data[i]);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_ReadReg(uint8_t reg)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(R_REGISTER | (REGISTER_MASK & reg));
|
||||
uint8_t data = nrf_spi_read();
|
||||
SPI_Write(R_REGISTER | (REGISTER_MASK & reg));
|
||||
uint8_t data = SPI_Read();
|
||||
NRF_CSN_on;
|
||||
return data;
|
||||
}
|
||||
@ -109,25 +70,25 @@ uint8_t NRF24L01_ReadReg(uint8_t reg)
|
||||
/*static void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(R_REGISTER | (REGISTER_MASK & reg));
|
||||
SPI_Write(R_REGISTER | (REGISTER_MASK & reg));
|
||||
for(uint8_t i = 0; i < length; i++)
|
||||
data[i] = nrf_spi_read();
|
||||
data[i] = SPI_Read();
|
||||
NRF_CSN_on;
|
||||
}
|
||||
*/
|
||||
static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(R_RX_PAYLOAD);
|
||||
SPI_Write(R_RX_PAYLOAD);
|
||||
for(uint8_t i = 0; i < length; i++)
|
||||
data[i] = nrf_spi_read();
|
||||
data[i] = SPI_Read();
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
static void NRF24L01_Strobe(uint8_t state)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(state);
|
||||
SPI_Write(state);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -144,8 +105,8 @@ void NRF24L01_FlushRx()
|
||||
void NRF24L01_Activate(uint8_t code)
|
||||
{
|
||||
NRF_CSN_off;
|
||||
nrf_spi_write(ACTIVATE);
|
||||
nrf_spi_write(code);
|
||||
SPI_Write(ACTIVATE);
|
||||
SPI_Write(code);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
|
||||
@ -202,7 +163,7 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC) // switch to TX mode
|
||||
| (1 << NRF24L01_00_CRCO)
|
||||
| (1 << NRF24L01_00_PWR_UP));
|
||||
_delay_us(130);
|
||||
delayMicroseconds(130);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
else
|
||||
@ -217,7 +178,7 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
|
||||
| (1 << NRF24L01_00_CRCO)
|
||||
| (1 << NRF24L01_00_PWR_UP)
|
||||
| (1 << NRF24L01_00_PRIM_RX));
|
||||
_delay_us(130);
|
||||
delayMicroseconds(130);
|
||||
NRF_CSN_on;
|
||||
}
|
||||
else
|
||||
@ -241,7 +202,7 @@ void NRF24L01_Reset()
|
||||
NRF24L01_Strobe(0xff); // NOP
|
||||
NRF24L01_ReadReg(0x07);
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
_delay_us(100);
|
||||
delayMicroseconds(100);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_packet_ack()
|
||||
@ -258,7 +219,7 @@ uint8_t NRF24L01_packet_ack()
|
||||
|
||||
///////////////
|
||||
// XN297 emulation layer
|
||||
uint8_t xn297_scramble_enabled=1; //enabled by default
|
||||
uint8_t xn297_scramble_enabled=XN297_SCRAMBLED; //enabled by default
|
||||
uint8_t xn297_addr_len;
|
||||
uint8_t xn297_tx_addr[5];
|
||||
uint8_t xn297_rx_addr[5];
|
||||
@ -271,13 +232,6 @@ static const uint8_t xn297_scramble[] = {
|
||||
0x1b, 0x5d, 0x19, 0x10, 0x24, 0xd3, 0xdc, 0x3f,
|
||||
0x8e, 0xc5, 0x2f};
|
||||
|
||||
const uint16_t PROGMEM xn297_crc_xorout[] = {
|
||||
0x0000, 0x3d5f, 0xa6f1, 0x3a23, 0xaa16, 0x1caf,
|
||||
0x62b2, 0xe0eb, 0x0821, 0xbe07, 0x5f1a, 0xaf15,
|
||||
0x4f0a, 0xad24, 0x5e48, 0xed34, 0x068c, 0xf2c9,
|
||||
0x1852, 0xdf36, 0x129d, 0xb17c, 0xd5f5, 0x70d7,
|
||||
0xb798, 0x5133, 0x67db, 0xd94e};
|
||||
|
||||
const uint16_t PROGMEM xn297_crc_xorout_scrambled[] = {
|
||||
0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C,
|
||||
0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B,
|
||||
@ -285,6 +239,13 @@ const uint16_t PROGMEM xn297_crc_xorout_scrambled[] = {
|
||||
0x8B17, 0x2920, 0x8B5F, 0x61B1, 0xD391, 0x7401,
|
||||
0x2138, 0x129F, 0xB3A0, 0x2988};
|
||||
|
||||
const uint16_t PROGMEM xn297_crc_xorout[] = {
|
||||
0x0000, 0x3d5f, 0xa6f1, 0x3a23, 0xaa16, 0x1caf,
|
||||
0x62b2, 0xe0eb, 0x0821, 0xbe07, 0x5f1a, 0xaf15,
|
||||
0x4f0a, 0xad24, 0x5e48, 0xed34, 0x068c, 0xf2c9,
|
||||
0x1852, 0xdf36, 0x129d, 0xb17c, 0xd5f5, 0x70d7,
|
||||
0xb798, 0x5133, 0x67db, 0xd94e};
|
||||
|
||||
static uint8_t bit_reverse(uint8_t b_in)
|
||||
{
|
||||
uint8_t b_out = 0;
|
||||
@ -296,10 +257,9 @@ static uint8_t bit_reverse(uint8_t b_in)
|
||||
return b_out;
|
||||
}
|
||||
|
||||
static const uint16_t polynomial = 0x1021;
|
||||
static uint16_t crc16_update(uint16_t crc, uint8_t a)
|
||||
{
|
||||
static const uint16_t polynomial = 0x1021;
|
||||
|
||||
crc ^= a << 8;
|
||||
for (uint8_t i = 0; i < 8; ++i)
|
||||
if (crc & 0x8000)
|
||||
@ -345,14 +305,18 @@ void XN297_SetRXAddr(const uint8_t* addr, uint8_t len)
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5);
|
||||
}
|
||||
|
||||
void XN297_Configure(uint16_t flags)
|
||||
void XN297_Configure(uint8_t flags)
|
||||
{
|
||||
xn297_scramble_enabled = !(flags & BV(XN297_UNSCRAMBLED));
|
||||
xn297_crc = !!(flags & BV(NRF24L01_00_EN_CRC));
|
||||
flags &= ~(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags & 0xFF);
|
||||
}
|
||||
|
||||
void XN297_SetScrambledMode(const u8 mode)
|
||||
{
|
||||
xn297_scramble_enabled = mode;
|
||||
}
|
||||
|
||||
void XN297_WritePayload(uint8_t* msg, uint8_t len)
|
||||
{
|
||||
uint8_t buf[32];
|
||||
|
@ -18,7 +18,7 @@
|
||||
|
||||
#include "iface_cc2500.h"
|
||||
|
||||
//#define SFHSS_USE_TUNE_FREQ
|
||||
#define SFHSS_USE_TUNE_FREQ
|
||||
#define SFHSS_COARSE 0
|
||||
|
||||
#define SFHSS_PACKET_LEN 13
|
||||
@ -73,20 +73,6 @@ const PROGMEM uint8_t SFHSS_init_values[] = {
|
||||
/* 20 */ 0xF8, 0xB6, 0x10, 0xEA, 0x0A, 0x11, 0x11
|
||||
};
|
||||
|
||||
static void __attribute__((unused)) SFHSS_rf_init()
|
||||
{
|
||||
CC2500_Reset();
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
|
||||
for (uint8_t i = 0; i < 39; ++i)
|
||||
CC2500_WriteReg(i, pgm_read_byte_near(&SFHSS_init_values[i]));
|
||||
//CC2500_WriteRegisterMulti(CC2500_00_IOCFG2, init_values, sizeof(init_values));
|
||||
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
|
||||
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
CC2500_SetPower();
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) SFHSS_tune_chan()
|
||||
{
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
@ -99,7 +85,7 @@ static void __attribute__((unused)) SFHSS_tune_chan_fast()
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16);
|
||||
CC2500_WriteRegisterMulti(CC2500_23_FSCAL3, calData[rf_ch_num], 3);
|
||||
_delay_us(6);
|
||||
delayMicroseconds(6);
|
||||
}
|
||||
|
||||
#ifdef SFHSS_USE_TUNE_FREQ
|
||||
@ -112,6 +98,20 @@ static void __attribute__((unused)) SFHSS_tune_freq() {
|
||||
}
|
||||
#endif
|
||||
|
||||
static void __attribute__((unused)) SFHSS_rf_init()
|
||||
{
|
||||
CC2500_Reset();
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
|
||||
for (uint8_t i = 0; i < 39; ++i)
|
||||
CC2500_WriteReg(i, pgm_read_byte_near(&SFHSS_init_values[i]));
|
||||
//CC2500_WriteRegisterMulti(CC2500_00_IOCFG2, init_values, sizeof(init_values));
|
||||
//CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
|
||||
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
CC2500_SetPower();
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) SFHSS_calc_next_chan()
|
||||
{
|
||||
rf_ch_num += fhss_code + 2;
|
||||
@ -194,6 +194,9 @@ uint16_t ReadSFHSS()
|
||||
state = SFHSS_TUNE;
|
||||
return 2000;
|
||||
case SFHSS_TUNE:
|
||||
#ifdef SFHSS_USE_TUNE_FREQ
|
||||
SFHSS_tune_freq();
|
||||
#endif
|
||||
CC2500_SetPower();
|
||||
state = SFHSS_DATA1;
|
||||
return 3150;
|
||||
|
@ -161,7 +161,7 @@ static void __attribute__((unused)) SYMAX_send_packet(uint8_t bind)
|
||||
|
||||
NRF24L01_WritePayload(packet, packet_length);
|
||||
|
||||
if (packet_counter++ % 2) // use each channel twice
|
||||
if (packet_count++ % 2) // use each channel twice
|
||||
hopping_frequency_no = (hopping_frequency_no + 1) % rf_ch_num;
|
||||
|
||||
NRF24L01_SetPower(); // Set tx_power
|
||||
@ -243,7 +243,7 @@ static void __attribute__((unused)) symax_init1()
|
||||
memcpy(hopping_frequency, chans_bind, rf_ch_num);
|
||||
}
|
||||
hopping_frequency_no = 0;
|
||||
packet_counter = 0;
|
||||
packet_count = 0;
|
||||
}
|
||||
|
||||
// channels determined by last byte of tx address
|
||||
@ -306,7 +306,7 @@ static void __attribute__((unused)) symax_init2()
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
|
||||
}
|
||||
hopping_frequency_no = 0;
|
||||
packet_counter = 0;
|
||||
packet_count = 0;
|
||||
}
|
||||
|
||||
uint16_t symax_callback()
|
||||
@ -345,7 +345,7 @@ uint16_t symax_callback()
|
||||
|
||||
uint16_t initSymax()
|
||||
{
|
||||
packet_counter = 0;
|
||||
packet_count = 0;
|
||||
flags = 0;
|
||||
BIND_IN_PROGRESS; // autobind protocol
|
||||
symax_init();
|
||||
|
@ -58,6 +58,7 @@
|
||||
#define MJXQ_NRF24L01_INO
|
||||
#define SHENQI_NRF24L01_INO
|
||||
#define FY326_NRF24L01_INO
|
||||
#define FQ777_NRF24L01_INO
|
||||
#endif
|
||||
|
||||
//Uncomment to enable telemetry
|
||||
@ -153,6 +154,7 @@ const PPM_Parameters PPM_prot[15]= {
|
||||
MT99
|
||||
H7
|
||||
YZ
|
||||
LS
|
||||
MODE_MJXQ
|
||||
WLH08
|
||||
X600
|
||||
@ -166,6 +168,8 @@ const PPM_Parameters PPM_prot[15]= {
|
||||
NONE
|
||||
MODE_J6PRO
|
||||
NONE
|
||||
MODE_FQ777
|
||||
NONE
|
||||
|
||||
RX_Num value between 0 and 15
|
||||
|
||||
|
@ -103,6 +103,8 @@ enum {
|
||||
//#define NOP 0xFF
|
||||
|
||||
// XN297 emulation layer
|
||||
#define XN297_UNSCRAMBLED 8
|
||||
|
||||
enum {
|
||||
XN297_UNSCRAMBLED = 0,
|
||||
XN297_SCRAMBLED
|
||||
};
|
||||
#endif
|
Loading…
x
Reference in New Issue
Block a user