mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-11-25 21:39:39 +00:00
Compare commits
84 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
91e395884f | ||
|
|
7107c68a41 | ||
|
|
86728b79e3 | ||
|
|
e04f901590 | ||
|
|
47ad2b5cfa | ||
|
|
cea0f1766f | ||
|
|
407e57d334 | ||
|
|
c4e66d0c9c | ||
|
|
c54f1ca9b0 | ||
|
|
f9fdc36d0d | ||
|
|
6d546094ef | ||
|
|
8dc5ae4f86 | ||
|
|
fd7b81af10 | ||
|
|
3abd859664 | ||
|
|
6134ce39d4 | ||
|
|
8ea42ea432 | ||
|
|
fd4ff00ee2 | ||
|
|
9d981b09ca | ||
|
|
ed807e0fe5 | ||
|
|
32b962b036 | ||
|
|
8ac476b6bd | ||
|
|
9ab8b84d81 | ||
|
|
05cc4b4bd1 | ||
|
|
b28cf30f47 | ||
|
|
5bf8b0a2b6 | ||
|
|
d2891a49fc | ||
|
|
bec8ba6c2f | ||
|
|
9e097be657 | ||
|
|
b008f55847 | ||
|
|
487d90f260 | ||
|
|
671a745acc | ||
|
|
80880f4d2a | ||
|
|
109fba828b | ||
|
|
0a845fdfa6 | ||
|
|
5a5b8464fc | ||
|
|
86d0b92a66 | ||
|
|
9f75234dac | ||
|
|
a58b129503 | ||
|
|
6d752acb28 | ||
|
|
4486582006 | ||
|
|
ed027fd3ce | ||
|
|
a92cb848c0 | ||
|
|
e573e36aa6 | ||
|
|
fc61753953 | ||
|
|
9b74e19a99 | ||
|
|
e9e39cb985 | ||
|
|
d938f2ea50 | ||
|
|
6c3535951f | ||
|
|
cee78b4ae3 | ||
|
|
1ee646e1ce | ||
|
|
6199dec82f | ||
|
|
59f307bdb3 | ||
|
|
24747355ce | ||
|
|
3d287a2827 | ||
|
|
def28df4dd | ||
|
|
d90e698a15 | ||
|
|
f4d6f88e5c | ||
|
|
799dce4b13 | ||
|
|
a025d028d4 | ||
|
|
8cfa9a891d | ||
|
|
5b44439dd2 | ||
|
|
44fb7dcdaa | ||
|
|
4f5d1ba26b | ||
|
|
0a08b09d70 | ||
|
|
35eedda352 | ||
|
|
05fb8bc742 | ||
|
|
795df2937e | ||
|
|
5607740e77 | ||
|
|
d4287d3046 | ||
|
|
71ef72bae3 | ||
|
|
c310d698ca | ||
|
|
13ce3d1c92 | ||
|
|
122ed79a98 | ||
|
|
6d655242a6 | ||
|
|
09cab9d825 | ||
|
|
d8bd38c124 | ||
|
|
abc8bf0e62 | ||
|
|
24106ac3d2 | ||
|
|
bf506d382f | ||
|
|
84b1a9bbec | ||
|
|
d67afd4396 | ||
|
|
9f2f7eff5b | ||
|
|
c863d5976b | ||
|
|
d6338e9daf |
@@ -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;
|
||||
@@ -121,9 +102,8 @@ uint8_t A7105_Reset()
|
||||
{
|
||||
uint8_t result;
|
||||
|
||||
delay(10); //wait 10ms for A7105 wakeup
|
||||
A7105_WriteReg(0x00, 0x00);
|
||||
delay(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);
|
||||
@@ -132,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;
|
||||
}
|
||||
|
||||
@@ -180,7 +160,7 @@ void A7105_SetPower()
|
||||
|
||||
void A7105_Strobe(uint8_t address) {
|
||||
CS_off;
|
||||
A7105_Write(address);
|
||||
SPI_Write(address);
|
||||
CS_on;
|
||||
}
|
||||
|
||||
|
||||
@@ -19,18 +19,18 @@
|
||||
//-------------------------------
|
||||
#include "iface_cc2500.h"
|
||||
|
||||
void cc2500_readFifo(uint8_t *dpbuffer, uint8_t len)
|
||||
void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len)
|
||||
{
|
||||
ReadRegisterMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
|
||||
CC2500_ReadRegisterMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
|
||||
}
|
||||
|
||||
//----------------------
|
||||
static void ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
|
||||
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,83 +39,44 @@ static void ReadRegisterMulti(uint8_t address, 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);
|
||||
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;
|
||||
}
|
||||
|
||||
void cc2500_writeFifo(uint8_t *dpbuffer, uint8_t len)
|
||||
void CC2500_WriteData(uint8_t *dpbuffer, uint8_t len)
|
||||
{
|
||||
cc2500_strobe(CC2500_SFTX);//0x3B
|
||||
CC2500_Strobe(CC2500_SFTX);//0x3B
|
||||
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, dpbuffer, len);
|
||||
cc2500_strobe(CC2500_STX);//0x35
|
||||
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
|
||||
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)
|
||||
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);
|
||||
}
|
||||
//------------------------
|
||||
void cc2500_strobe(uint8_t address)
|
||||
void CC2500_Strobe(uint8_t address)
|
||||
{
|
||||
CC25_CSN_off;
|
||||
cc2500_spi_write(address);
|
||||
SPI_Write(address);
|
||||
CC25_CSN_on;
|
||||
}
|
||||
//------------------------
|
||||
@@ -123,21 +84,21 @@ 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);
|
||||
cc2500_strobe(CC2500_SRES);
|
||||
delayMicroseconds(45);
|
||||
CC2500_Strobe(CC2500_SRES);
|
||||
_delay_ms(100);
|
||||
}
|
||||
*/
|
||||
uint8_t CC2500_Reset()
|
||||
{
|
||||
cc2500_strobe(CC2500_SRES);
|
||||
_delay_us(1000);
|
||||
CC2500_Strobe(CC2500_SRES);
|
||||
delayMicroseconds(1000);
|
||||
CC2500_SetTxRxMode(TXRX_OFF);
|
||||
return cc2500_readReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
|
||||
return CC2500_ReadReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
|
||||
}
|
||||
/*
|
||||
static void CC2500_SetPower_Value(uint8_t power)
|
||||
@@ -154,7 +115,7 @@ static void CC2500_SetPower_Value(uint8_t power)
|
||||
};
|
||||
if (power > 7)
|
||||
power = 7;
|
||||
cc2500_writeReg(CC2500_3E_PATABLE, patable[power]);
|
||||
CC2500_WriteReg(CC2500_3E_PATABLE, patable[power]);
|
||||
}
|
||||
*/
|
||||
void CC2500_SetPower()
|
||||
@@ -164,25 +125,25 @@ void CC2500_SetPower()
|
||||
power=IS_POWER_FLAG_on?CC2500_HIGH_POWER:CC2500_LOW_POWER;
|
||||
if(IS_RANGE_FLAG_on)
|
||||
power=CC2500_RANGE_POWER;
|
||||
cc2500_writeReg(CC2500_3E_PATABLE, power);
|
||||
CC2500_WriteReg(CC2500_3E_PATABLE, power);
|
||||
}
|
||||
|
||||
void CC2500_SetTxRxMode(uint8_t mode)
|
||||
{
|
||||
if(mode == TX_EN)
|
||||
{//from deviation firmware
|
||||
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F | 0x40);
|
||||
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F);
|
||||
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F | 0x40);
|
||||
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
|
||||
}
|
||||
else
|
||||
if (mode == RX_EN)
|
||||
{
|
||||
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F);
|
||||
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F | 0x40);
|
||||
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
|
||||
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F | 0x40);
|
||||
}
|
||||
else
|
||||
{
|
||||
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F);
|
||||
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F);
|
||||
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
|
||||
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#define CG023_INITIAL_WAIT 500
|
||||
#define CG023_PACKET_SIZE 15 // packets have 15-byte payload
|
||||
#define CG023_RF_BIND_CHANNEL 0x2D
|
||||
#define CG023_BIND_COUNT 1000 // 8 seconds
|
||||
#define CG023_BIND_COUNT 500 // 4 seconds
|
||||
#define YD829_PACKET_PERIOD 4100 // Timeout for callback in uSec
|
||||
#define H8_3D_PACKET_PERIOD 1800 // Timeout for callback in uSec
|
||||
#define H8_3D_PACKET_SIZE 20
|
||||
|
||||
@@ -25,7 +25,6 @@
|
||||
#define Q282_PACKET_SIZE 21
|
||||
#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec
|
||||
#define CX10A_PACKET_PERIOD 6000
|
||||
#define CX10A_BIND_COUNT 400 // 2 seconds
|
||||
|
||||
#define CX10_INITIAL_WAIT 500
|
||||
|
||||
@@ -182,7 +181,8 @@ static void __attribute__((unused)) CX10_init()
|
||||
NRF24L01_SetPower();
|
||||
}
|
||||
|
||||
uint16_t CX10_callback() {
|
||||
uint16_t CX10_callback()
|
||||
{
|
||||
switch (phase) {
|
||||
case CX10_BIND1:
|
||||
if (bind_counter == 0)
|
||||
@@ -197,12 +197,6 @@ uint16_t CX10_callback() {
|
||||
}
|
||||
break;
|
||||
case CX10_BIND2:
|
||||
bind_counter--;
|
||||
if(bind_counter==0)
|
||||
{ // Needed for some CX-10A to properly finish the bind
|
||||
CX10_init();
|
||||
bind_counter=CX10A_BIND_COUNT;
|
||||
}
|
||||
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
|
||||
{ // RX fifo data ready
|
||||
XN297_ReadPayload(packet, packet_length);
|
||||
@@ -210,16 +204,18 @@ uint16_t CX10_callback() {
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
if(packet[9] == 1)
|
||||
{
|
||||
phase = CX10_BIND1;
|
||||
bind_counter=0;
|
||||
BIND_DONE;
|
||||
phase = CX10_DATA;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// switch to TX mode
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_FlushTx();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
CX10_Write_Packet(1);
|
||||
delayMicroseconds(400); // 300µs in deviation but not working so using 400µs instead
|
||||
delayMicroseconds(400);
|
||||
// switch to RX mode
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_FlushRx();
|
||||
@@ -269,7 +265,6 @@ uint16_t initCX10(void)
|
||||
packet_period = CX10A_PACKET_PERIOD;
|
||||
|
||||
phase = CX10_BIND2;
|
||||
bind_counter=CX10A_BIND_COUNT;
|
||||
|
||||
for(uint8_t i=0; i<4; i++)
|
||||
packet[5+i] = 0xff; // clear aircraft id
|
||||
|
||||
@@ -14,48 +14,12 @@
|
||||
*/
|
||||
#include "iface_cyrf6936.h"
|
||||
|
||||
static void cyrf_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;
|
||||
}
|
||||
|
||||
static uint8_t cyrf_spi_read()
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
@@ -64,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;
|
||||
}
|
||||
|
||||
@@ -75,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;
|
||||
}
|
||||
|
||||
@@ -85,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;
|
||||
}
|
||||
@@ -95,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);
|
||||
@@ -196,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;
|
||||
}
|
||||
/*
|
||||
@@ -215,11 +179,11 @@ static void CYRF_StartReceive()
|
||||
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, 0x10);
|
||||
}
|
||||
*/
|
||||
/*static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
|
||||
void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
|
||||
{
|
||||
ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
|
||||
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
|
||||
}
|
||||
*/
|
||||
|
||||
static void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len)
|
||||
{
|
||||
CYRF_WriteRegister(CYRF_01_TX_LENGTH, len);
|
||||
@@ -262,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);
|
||||
}
|
||||
|
||||
|
||||
@@ -17,11 +17,9 @@
|
||||
|
||||
#include "iface_cyrf6936.h"
|
||||
|
||||
#define DSM2_NUM_CHANNELS 7
|
||||
#define RANDOM_CHANNELS 0 // disabled
|
||||
//#define RANDOM_CHANNELS 1 // enabled
|
||||
#define BIND_CHANNEL 0x0d //13 This can be any odd channel
|
||||
#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
|
||||
|
||||
//During binding we will send BIND_COUNT/2 packets
|
||||
//One packet each 10msec
|
||||
@@ -86,7 +84,7 @@ const uint8_t PROGMEM pncodes[5][9][8] = {
|
||||
/* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
|
||||
/* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
|
||||
/* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
|
||||
/* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
|
||||
/* Col 8 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93}
|
||||
},
|
||||
{ /* Row 4 */
|
||||
/* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
|
||||
@@ -108,29 +106,19 @@ static void __attribute__((unused)) read_code(uint8_t *buf, uint8_t row, uint8_t
|
||||
}
|
||||
|
||||
//
|
||||
uint8_t chidx;
|
||||
uint8_t sop_col;
|
||||
uint8_t data_col;
|
||||
uint16_t cyrf_state;
|
||||
uint8_t crcidx;
|
||||
uint8_t binding;
|
||||
/*
|
||||
#ifdef USE_FIXED_MFGID
|
||||
const uint8_t cyrfmfg_id[6] = {0x5e, 0x28, 0xa3, 0x1b, 0x00, 0x00}; //dx8
|
||||
const uint8_t cyrfmfg_id[6] = {0xd4, 0x62, 0xd6, 0xad, 0xd3, 0xff}; //dx6i
|
||||
#else
|
||||
//uint8_t cyrfmfg_id[6];
|
||||
#endif
|
||||
*/
|
||||
|
||||
static void __attribute__((unused)) build_bind_packet()
|
||||
{
|
||||
uint8_t i;
|
||||
uint16_t sum = 384 - 0x10;//
|
||||
packet[0] = crc >> 8;
|
||||
packet[1] = crc & 0xff;
|
||||
packet[0] = 0xff ^ cyrfmfg_id[0];
|
||||
packet[1] = 0xff ^ cyrfmfg_id[1];
|
||||
packet[2] = 0xff ^ cyrfmfg_id[2];
|
||||
packet[3] = (0xff ^ cyrfmfg_id[3]) + RX_num;
|
||||
packet[3] = 0xff ^ cyrfmfg_id[3];
|
||||
packet[4] = packet[0];
|
||||
packet[5] = packet[1];
|
||||
packet[6] = packet[2];
|
||||
@@ -140,15 +128,15 @@ static void __attribute__((unused)) build_bind_packet()
|
||||
packet[8] = sum >> 8;
|
||||
packet[9] = sum & 0xff;
|
||||
packet[10] = 0x01; //???
|
||||
packet[11] = DSM2_NUM_CHANNELS;
|
||||
packet[11] = option>3?option:option+4;
|
||||
if(sub_protocol==DSMX) //DSMX type
|
||||
packet[12] = 0xb2; // Telemetry off: packet[12] = num_channels < 8 && Model.proto_opts[PROTOOPTS_TELEMETRY] == TELEM_OFF ? 0xa2 : 0xb2;
|
||||
else
|
||||
#if DSM2_NUM_CHANNELS < 8
|
||||
packet[12] = 0x01;
|
||||
#if defined DSM_TELEMETRY
|
||||
packet[12] = 0xb2; // Telemetry on
|
||||
#else
|
||||
packet[12] = 0x02;
|
||||
packet[12] = option<8? 0xa2 : 0xb2; // Telemetry off
|
||||
#endif
|
||||
else
|
||||
packet[12] = option<8?0x01:0x02;
|
||||
packet[13] = 0x00; //???
|
||||
for(i = 8; i < 14; i++)
|
||||
sum += packet[i];
|
||||
@@ -174,44 +162,48 @@ static uint8_t __attribute__((unused)) PROTOCOL_SticksMoved(uint8_t init)
|
||||
|
||||
static void __attribute__((unused)) build_data_packet(uint8_t upper)//
|
||||
{
|
||||
#if DSM2_NUM_CHANNELS==4
|
||||
const uint8_t ch_map[] = {0, 1, 2, 3, 0xff, 0xff, 0xff}; //Guess
|
||||
#elif DSM2_NUM_CHANNELS==5
|
||||
const uint8_t ch_map[] = {0, 1, 2, 3, 4, 0xff, 0xff}; //Guess
|
||||
#elif DSM2_NUM_CHANNELS==6
|
||||
const uint8_t ch_map[] = {1, 5, 2, 3, 0, 4, 0xff}; //HP6DSM
|
||||
#elif DSM2_NUM_CHANNELS==7
|
||||
const uint8_t ch_map[] = {1, 5, 2, 4, 3, 6, 0}; //DX6i
|
||||
#elif DSM2_NUM_CHANNELS==8
|
||||
const uint8_t ch_map[] = {1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 0xff, 0xff, 0xff, 0xff}; //DX8
|
||||
#elif DSM2_NUM_CHANNELS==9
|
||||
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xff, 0xff, 0xff, 0xff, 0xff}; //DM9
|
||||
#elif DSM2_NUM_CHANNELS==10
|
||||
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 0xff, 0xff, 0xff, 0xff};
|
||||
#elif DSM2_NUM_CHANNELS==11
|
||||
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 0xff, 0xff, 0xff};
|
||||
#elif DSM2_NUM_CHANNELS==12
|
||||
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 11, 0xff, 0xff};
|
||||
#endif
|
||||
|
||||
uint8_t i;
|
||||
uint8_t bits;
|
||||
|
||||
uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; //9 Channels - DM9 TX
|
||||
switch(option>3?option:option+4) // Create channel map based on number of channels
|
||||
{
|
||||
case 12:
|
||||
ch_map[11]=11; // 12 channels
|
||||
case 11:
|
||||
ch_map[10]=10; // 11 channels
|
||||
case 10:
|
||||
ch_map[9]=9; // 10 channels
|
||||
break;
|
||||
case 8:
|
||||
memcpy(ch_map,"\x01\x05\x02\x03\x06\xFF\xFF\x04\x00\x07",10); // 8 channels - DX8 TX
|
||||
break;
|
||||
case 7:
|
||||
memcpy(ch_map,"\x01\x05\x02\x04\x03\x06\x00",7); // 7 channels - DX6i TX
|
||||
break;
|
||||
case 6:
|
||||
memcpy(ch_map,"\x01\x05\x02\x03\x00\x04\xFF",7); // 6 channels - HP6DSM TX
|
||||
break;
|
||||
case 4:
|
||||
case 5:
|
||||
memcpy(ch_map,"\x00\x01\x02\x03\xFF\xFF\xFF",7); // 4 channels - Guess
|
||||
if(option&0x01)
|
||||
ch_map[4]=4; // 5 channels - Guess
|
||||
break;
|
||||
}
|
||||
//
|
||||
if( binding && PROTOCOL_SticksMoved(0) )
|
||||
{
|
||||
//BIND_DONE;
|
||||
binding = 0;
|
||||
}
|
||||
if (sub_protocol==DSMX)
|
||||
{
|
||||
packet[0] = cyrfmfg_id[2];
|
||||
packet[1] = cyrfmfg_id[3] + RX_num;
|
||||
packet[1] = cyrfmfg_id[3];
|
||||
bits=11;
|
||||
}
|
||||
else
|
||||
{
|
||||
packet[0] = (0xff ^ cyrfmfg_id[2]);
|
||||
packet[1] = (0xff ^ cyrfmfg_id[3]) + RX_num;
|
||||
packet[1] = (0xff ^ cyrfmfg_id[3]);
|
||||
bits=10;
|
||||
}
|
||||
//
|
||||
@@ -260,6 +252,18 @@ static void __attribute__((unused)) build_data_packet(uint8_t upper)//
|
||||
case 7:
|
||||
value=Servo_data[AUX4];
|
||||
break;
|
||||
case 8:
|
||||
value=Servo_data[AUX5];
|
||||
break;
|
||||
case 9:
|
||||
value=Servo_data[AUX6];
|
||||
break;
|
||||
case 10:
|
||||
value=Servo_data[AUX7];
|
||||
break;
|
||||
case 11:
|
||||
value=Servo_data[AUX8];
|
||||
break;
|
||||
}
|
||||
value=map(value,PPM_MIN,PPM_MAX,0,max-1);
|
||||
}
|
||||
@@ -276,7 +280,7 @@ static uint8_t __attribute__((unused)) get_pn_row(uint8_t channel)
|
||||
}
|
||||
|
||||
const uint8_t init_vals[][2] = {
|
||||
{CYRF_02_TX_CTRL, 0x00},
|
||||
{CYRF_02_TX_CTRL, 0x02}, //0x00 in deviation but needed to know when transmit is over
|
||||
{CYRF_05_RX_CTRL, 0x00},
|
||||
{CYRF_28_CLK_EN, 0x02},
|
||||
{CYRF_32_AUTO_CAL_TIME, 0x3c},
|
||||
@@ -323,7 +327,7 @@ static void __attribute__((unused)) initialize_bind_state()
|
||||
CYRF_ConfigSOPCode(code);
|
||||
read_code(code,pn_row,data_col,16);
|
||||
read_code(code+16,0,8,8);
|
||||
memcpy(code + 24, "\xc6\x94\x22\xfe\x48\xe6\x57\x4e", 8);
|
||||
memcpy(code + 24, (void *)"\xc6\x94\x22\xfe\x48\xe6\x57\x4e", 8);
|
||||
CYRF_ConfigDataCode(code, 32);
|
||||
|
||||
build_bind_packet();
|
||||
@@ -356,10 +360,11 @@ static void __attribute__((unused)) cyrf_configdata()
|
||||
static void __attribute__((unused)) set_sop_data_crc()
|
||||
{
|
||||
uint8_t code[16];
|
||||
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);
|
||||
CYRF_ConfigRFChannel(hopping_frequency[chidx]);
|
||||
CYRF_ConfigCRCSeed(crcidx ? ~crc : crc);
|
||||
uint8_t pn_row = get_pn_row(hopping_frequency[hopping_frequency_no]);
|
||||
//printf("Ch: %d Row: %d SOP: %d Data: %d\n", ch[hopping_frequency_no], pn_row, sop_col, data_col);
|
||||
CYRF_ConfigRFChannel(hopping_frequency[hopping_frequency_no]);
|
||||
CYRF_ConfigCRCSeed(crc);
|
||||
crc=~crc;
|
||||
|
||||
read_code(code,pn_row,sop_col,8);
|
||||
CYRF_ConfigSOPCode(code);
|
||||
@@ -367,10 +372,9 @@ static void __attribute__((unused)) set_sop_data_crc()
|
||||
CYRF_ConfigDataCode(code, 16);
|
||||
|
||||
if(sub_protocol == DSMX)
|
||||
chidx = (chidx + 1) % 23;
|
||||
hopping_frequency_no = (hopping_frequency_no + 1) % 23;
|
||||
else
|
||||
chidx = (chidx + 1) % 2;
|
||||
crcidx = !crcidx;
|
||||
hopping_frequency_no = (hopping_frequency_no + 1) % 2;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) calc_dsmx_channel()
|
||||
@@ -384,7 +388,7 @@ static void __attribute__((unused)) calc_dsmx_channel()
|
||||
uint8_t count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
|
||||
id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
|
||||
uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
|
||||
if (((next_ch ^ id) & 0x01 )== 0)
|
||||
if ( (next_ch ^ cyrfmfg_id[3]) & 0x01 )
|
||||
continue;
|
||||
for (i = 0; i < idx; i++)
|
||||
{
|
||||
@@ -409,10 +413,10 @@ static void __attribute__((unused)) calc_dsmx_channel()
|
||||
|
||||
uint16_t ReadDsm2()
|
||||
{
|
||||
#define CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
|
||||
#define WRITE_DELAY 1650 // 1550 original, Time after write to verify write complete
|
||||
#define READ_DELAY 400 // Time before write to check read state, and switch channels
|
||||
uint8_t i = 0;
|
||||
#define DSM_CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
|
||||
#define DSM_WRITE_DELAY 1550 // Time after write to verify write complete
|
||||
#define DSM_READ_DELAY 600 // Time before write to check read state, and switch channels. Was 400 but 500 seems what the 328p needs to read a packet
|
||||
uint32_t start;
|
||||
|
||||
switch(cyrf_state)
|
||||
{
|
||||
@@ -422,8 +426,7 @@ uint16_t ReadDsm2()
|
||||
if(cyrf_state & 1)
|
||||
{
|
||||
//Send packet on even states
|
||||
//Note state has already incremented,
|
||||
// so this is actually 'even' state
|
||||
//Note state has already incremented, so this is actually 'even' state
|
||||
CYRF_WriteDataPacket(packet);
|
||||
return 8500;
|
||||
}
|
||||
@@ -439,48 +442,99 @@ uint16_t ReadDsm2()
|
||||
//CYRF_FindBestChannels(ch, 2, 10, 1, 79);
|
||||
cyrf_configdata();
|
||||
CYRF_SetTxRxMode(TX_EN);
|
||||
chidx = 0;
|
||||
crcidx = 0;
|
||||
cyrf_state = DSM2_CH1_WRITE_A; // in fact cyrf_state++
|
||||
hopping_frequency_no = 0;
|
||||
cyrf_state = DSM2_CH1_WRITE_A; // in fact cyrf_state++
|
||||
set_sop_data_crc();
|
||||
return 10000;
|
||||
case DSM2_CH1_WRITE_A:
|
||||
case DSM2_CH1_WRITE_B:
|
||||
build_data_packet(cyrf_state == DSM2_CH1_WRITE_B);//compare state and DSM2_CH1_WRITE_B return 0 or 1
|
||||
case DSM2_CH2_WRITE_A:
|
||||
case DSM2_CH2_WRITE_B:
|
||||
build_data_packet(cyrf_state == DSM2_CH1_WRITE_B);// build lower or upper channels
|
||||
CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS); // clear IRQ flags
|
||||
CYRF_WriteDataPacket(packet);
|
||||
cyrf_state++; // change from WRITE to CHECK mode
|
||||
return WRITE_DELAY;
|
||||
cyrf_state++; // change from WRITE to CHECK mode
|
||||
return DSM_WRITE_DELAY;
|
||||
case DSM2_CH1_CHECK_A:
|
||||
case DSM2_CH1_CHECK_B:
|
||||
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
|
||||
if(++i > NUM_WAIT_LOOPS)
|
||||
start=micros();
|
||||
while (micros()-start < 500) // Wait max 500µs
|
||||
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
|
||||
break;
|
||||
set_sop_data_crc();
|
||||
cyrf_state++; // change from CH1_CHECK to CH2_WRITE
|
||||
return CH1_CH2_DELAY - WRITE_DELAY;
|
||||
cyrf_state++; // change from CH1_CHECK to CH2_WRITE
|
||||
return DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
|
||||
case DSM2_CH2_CHECK_A:
|
||||
case DSM2_CH2_CHECK_B:
|
||||
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
|
||||
if(++i > NUM_WAIT_LOOPS)
|
||||
start=micros();
|
||||
while (micros()-start < 500) // Wait max 500µs
|
||||
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
|
||||
break;
|
||||
if (cyrf_state == DSM2_CH2_CHECK_A)
|
||||
CYRF_SetPower(0x28); //Keep transmit power in sync
|
||||
// No telemetry...
|
||||
CYRF_SetPower(0x28); //Keep transmit power in sync
|
||||
#if defined DSM_TELEMETRY
|
||||
cyrf_state++; // change from CH2_CHECK to CH2_READ
|
||||
if(option<=3 || option>7)
|
||||
{ // disable telemetry for option between 4 and 7 ie 4,5,6,7 channels @11ms since it does not work...
|
||||
CYRF_SetTxRxMode(RX_EN); //Receive mode
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
|
||||
}
|
||||
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY - DSM_READ_DELAY;
|
||||
case DSM2_CH2_READ_A:
|
||||
case DSM2_CH2_READ_B:
|
||||
//Read telemetry
|
||||
uint8_t rx_state = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
|
||||
if((rx_state & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
|
||||
rx_state |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
|
||||
if((rx_state & 0x07) == 0x02)
|
||||
{ // good data (complete with no errors)
|
||||
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
|
||||
uint8_t len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
|
||||
if(len>MAX_PKT-2)
|
||||
len=MAX_PKT-2;
|
||||
CYRF_ReadDataPacketLen(pkt+1, len);
|
||||
pkt[0]=CYRF_ReadRegister(CYRF_13_RSSI)&0x1F; // store RSSI of the received telemetry signal
|
||||
telemetry_link=1;
|
||||
}
|
||||
if (cyrf_state == DSM2_CH2_READ_A && option <= 3) // normal 22ms mode if option<=3 ie 4,5,6,7 channels @22ms
|
||||
{
|
||||
//Force end read state
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, (CYRF_ReadRegister(CYRF_0F_XACT_CFG) | 0x20)); // Force end state
|
||||
start=micros();
|
||||
while (micros()-start < 100) // Wait max 100 µs
|
||||
if((CYRF_ReadRegister(CYRF_0F_XACT_CFG) & 0x20) == 0)
|
||||
break;
|
||||
cyrf_state = DSM2_CH2_READ_B;
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
|
||||
return 11000;
|
||||
}
|
||||
if (cyrf_state == DSM2_CH2_READ_A && option>7)
|
||||
cyrf_state = DSM2_CH1_WRITE_B; //Transmit upper
|
||||
else
|
||||
cyrf_state = DSM2_CH1_WRITE_A; //Force 11ms if option>3 ie 4,5,6,7 channels @11ms
|
||||
CYRF_SetTxRxMode(TX_EN); //Write mode
|
||||
set_sop_data_crc();
|
||||
return DSM_READ_DELAY;
|
||||
#else
|
||||
// No telemetry
|
||||
set_sop_data_crc();
|
||||
if (cyrf_state == DSM2_CH2_CHECK_A)
|
||||
{
|
||||
#if DSM2_NUM_CHANNELS < 8
|
||||
cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper)
|
||||
return 11000 - CH1_CH2_DELAY - WRITE_DELAY ; // Original is 22000 from deviation but it works better this way
|
||||
#else
|
||||
cyrf_state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper)
|
||||
#endif
|
||||
if(option < 8)
|
||||
{
|
||||
cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper)
|
||||
if(option>3)
|
||||
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY ; // force 11ms if option>3 ie 4,5,6,7 channels @11ms
|
||||
else
|
||||
return 22000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY ; // normal 22ms mode if option<=3 ie 4,5,6,7 channels @22ms
|
||||
}
|
||||
else
|
||||
cyrf_state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper)
|
||||
}
|
||||
else
|
||||
cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_B to CH1_WRITE_A (upper already transmitted so transmit lower)
|
||||
return 11000 - CH1_CH2_DELAY - WRITE_DELAY;
|
||||
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
|
||||
#endif
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@@ -489,10 +543,12 @@ uint16_t initDsm2()
|
||||
{
|
||||
CYRF_Reset();
|
||||
CYRF_GetMfgData(cyrfmfg_id);//
|
||||
|
||||
//Model match
|
||||
cyrfmfg_id[3]+=RX_num;
|
||||
|
||||
cyrf_config();
|
||||
|
||||
if (sub_protocol ==DSMX)
|
||||
if (sub_protocol == DSMX)
|
||||
calc_dsmx_channel();
|
||||
else
|
||||
{
|
||||
@@ -516,12 +572,12 @@ uint16_t initDsm2()
|
||||
#endif
|
||||
}
|
||||
|
||||
///}
|
||||
crc = ~((cyrfmfg_id[0] << 8) + cyrfmfg_id[1]); //The crc for channel 'a' is NOT(mfgid[1] << 8 + mfgid[0])
|
||||
crcidx = 0;//The crc for channel 'b' is (mfgid[1] << 8 + mfgid[0])
|
||||
//The crc for channel '1' is NOT(mfgid[0] << 8 + mfgid[1])
|
||||
//The crc for channel '2' is (mfgid[0] << 8 + mfgid[1])
|
||||
crc = ~((cyrfmfg_id[0] << 8) + cyrfmfg_id[1]);
|
||||
//
|
||||
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;//Ok
|
||||
data_col = 7 - sop_col;//ok
|
||||
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
|
||||
data_col = 7 - sop_col;
|
||||
|
||||
CYRF_SetTxRxMode(TX_EN);
|
||||
//
|
||||
|
||||
@@ -117,11 +117,10 @@ static void __attribute__((unused)) ESKY_send_packet(uint8_t bind)
|
||||
// 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)
|
||||
packet[i*2] = Servo_data[CH_AETR[i]]>>8; //high byte of servo timing(1000-2000us)
|
||||
packet[i*2+1] = Servo_data[CH_AETR[i]]&0xFF; //low byte of servo timing(1000-2000us)
|
||||
}
|
||||
}
|
||||
rf_ch = hopping_frequency[hopping_frequency_no];
|
||||
|
||||
209
Multiprotocol/FQ777_nrf24l01.ino
Normal file
209
Multiprotocol/FQ777_nrf24l01.ino
Normal file
@@ -0,0 +1,209 @@
|
||||
/*
|
||||
This project is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Multiprotocol is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
// 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 2000
|
||||
#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;
|
||||
|
||||
crc.val=0x3c18;
|
||||
for (i = 0; i < 7; ++i)
|
||||
crc.val=crc16_update(crc.val,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();
|
||||
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 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
|
||||
167
Multiprotocol/FY326_nrf24l01.ino
Normal file
167
Multiprotocol/FY326_nrf24l01.ino
Normal file
@@ -0,0 +1,167 @@
|
||||
/*
|
||||
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/fy326_nrf24l01.c dated 2015-07-29
|
||||
|
||||
#if defined(FY326_NRF24L01_INO)
|
||||
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
#define FY326_INITIAL_WAIT 500
|
||||
#define FY326_PACKET_PERIOD 1500
|
||||
#define FY326_PACKET_CHKTIME 300
|
||||
#define FY326_PACKET_SIZE 15
|
||||
#define FY326_BIND_COUNT 16
|
||||
#define FY326_RF_BIND_CHANNEL 0x17
|
||||
#define FY326_NUM_RF_CHANNELS 5
|
||||
|
||||
enum {
|
||||
FY326_BIND1=0,
|
||||
FY326_BIND2,
|
||||
FY326_DATA
|
||||
};
|
||||
|
||||
#define rxid channel
|
||||
|
||||
#define CHAN_TO_TRIM(chanval) ((chanval/10)-10)
|
||||
static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
|
||||
{
|
||||
packet[0] = rx_tx_addr[3];
|
||||
if(bind)
|
||||
packet[1] = 0x55;
|
||||
else
|
||||
packet[1] = GET_FLAG(Servo_AUX3, 0x80) // Headless
|
||||
| GET_FLAG(Servo_AUX2, 0x40) // RTH
|
||||
| GET_FLAG(Servo_AUX1, 0x02) // Flip
|
||||
| GET_FLAG(Servo_AUX5, 0x01) // Calibrate
|
||||
| GET_FLAG(Servo_AUX4, 0x04); // Expert
|
||||
packet[2] = 200 - convert_channel_8b_scale(AILERON, 0, 200); // aileron
|
||||
packet[3] = convert_channel_8b_scale(ELEVATOR, 0, 200); // elevator
|
||||
packet[4] = 200 - convert_channel_8b_scale(RUDDER, 0, 200); // rudder
|
||||
packet[5] = convert_channel_8b_scale(THROTTLE, 0, 200); // throttle
|
||||
packet[6] = rx_tx_addr[0];
|
||||
packet[7] = rx_tx_addr[1];
|
||||
packet[8] = rx_tx_addr[2];
|
||||
packet[9] = CHAN_TO_TRIM(packet[2]); // aileron_trim;
|
||||
packet[10] = CHAN_TO_TRIM(packet[3]); // elevator_trim;
|
||||
packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim;
|
||||
packet[12] = 0; // throttle_trim;
|
||||
packet[13] = rxid;
|
||||
packet[14] = rx_tx_addr[4];
|
||||
|
||||
if (bind)
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL);
|
||||
else
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
|
||||
hopping_frequency_no %= FY326_NUM_RF_CHANNELS;
|
||||
}
|
||||
|
||||
// clear packet status bits and TX FIFO
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
|
||||
NRF24L01_WritePayload(packet, FY326_PACKET_SIZE);
|
||||
|
||||
NRF24L01_SetPower(); // Set tx_power
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) FY326_init()
|
||||
{
|
||||
NRF24L01_Initialize();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x15\x59\x23\xc6\x29", 5);
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x15\x59\x23\xc6\x29", 5);
|
||||
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 Acknowledgement on all data pipes
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
|
||||
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_PACKET_SIZE);
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL);
|
||||
NRF24L01_SetBitrate(NRF24L01_BR_250K);
|
||||
NRF24L01_SetPower();
|
||||
|
||||
NRF24L01_Activate(0x73);
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f);
|
||||
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07);
|
||||
NRF24L01_Activate(0x73);
|
||||
}
|
||||
|
||||
uint16_t FY326_callback()
|
||||
{
|
||||
switch (phase)
|
||||
{
|
||||
case FY326_BIND1:
|
||||
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
|
||||
{ // RX fifo data ready
|
||||
NRF24L01_ReadPayload(packet, FY326_PACKET_SIZE);
|
||||
rxid = packet[13];
|
||||
rx_tx_addr[0] = 0xAA;
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
BIND_DONE;
|
||||
phase = FY326_DATA;
|
||||
}
|
||||
else
|
||||
if (bind_counter-- == 0)
|
||||
{
|
||||
bind_counter = FY326_BIND_COUNT;
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
FY326_send_packet(1);
|
||||
phase = FY326_BIND2;
|
||||
return FY326_PACKET_CHKTIME;
|
||||
}
|
||||
break;
|
||||
case FY326_BIND2:
|
||||
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS))
|
||||
{ // TX data sent -> switch to RX mode
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_FlushRx();
|
||||
NRF24L01_SetTxRxMode(RX_EN);
|
||||
phase = FY326_BIND1;
|
||||
}
|
||||
else
|
||||
return FY326_PACKET_CHKTIME;
|
||||
break;
|
||||
case FY326_DATA:
|
||||
FY326_send_packet(0);
|
||||
break;
|
||||
}
|
||||
return FY326_PACKET_PERIOD;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) FY326_initialize_txid()
|
||||
{
|
||||
hopping_frequency[0] = (rx_tx_addr[0]&0x0f);
|
||||
hopping_frequency[1] = 0x10 + (rx_tx_addr[0] >> 4);
|
||||
hopping_frequency[2] = 0x20 + (rx_tx_addr[1]&0x0f);
|
||||
hopping_frequency[3] = 0x30 + (rx_tx_addr[1] >> 4);
|
||||
hopping_frequency[4] = 0x40 + (rx_tx_addr[2] >> 4);
|
||||
}
|
||||
|
||||
uint16_t initFY326(void)
|
||||
{
|
||||
BIND_IN_PROGRESS; // autobind protocol
|
||||
rxid = 0xAA;
|
||||
bind_counter = 0;
|
||||
FY326_initialize_txid();
|
||||
FY326_init();
|
||||
phase=FY326_BIND1;
|
||||
return FY326_INITIAL_WAIT;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -21,31 +21,12 @@
|
||||
//FlySky constants & variables
|
||||
#define FLYSKY_BIND_COUNT 2500
|
||||
|
||||
const uint8_t PROGMEM tx_channels[] = {
|
||||
0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0,
|
||||
0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a,
|
||||
0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82,
|
||||
0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a,
|
||||
0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96,
|
||||
0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28,
|
||||
0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64,
|
||||
0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50,
|
||||
0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64,
|
||||
0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50,
|
||||
0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64,
|
||||
0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46,
|
||||
0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82,
|
||||
0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46,
|
||||
0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64,
|
||||
0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46
|
||||
};
|
||||
|
||||
enum {
|
||||
// flags going to byte 10
|
||||
FLAG_V9X9_VIDEO = 0x40,
|
||||
FLAG_V9X9_CAMERA= 0x80,
|
||||
// flags going to byte 12
|
||||
FLAG_V9X9_UNK = 0x10, // undocumented ?
|
||||
FLAG_V9X9_FLIP = 0x10,
|
||||
FLAG_V9X9_LED = 0x20,
|
||||
};
|
||||
|
||||
@@ -82,7 +63,7 @@ static void __attribute__((unused)) flysky_apply_extension_flags()
|
||||
{
|
||||
case V9X9:
|
||||
if(Servo_AUX1)
|
||||
packet[12] |= FLAG_V9X9_UNK;
|
||||
packet[12] |= FLAG_V9X9_FLIP;
|
||||
if(Servo_AUX2)
|
||||
packet[12] |= FLAG_V9X9_LED;
|
||||
if(Servo_AUX3)
|
||||
@@ -161,15 +142,33 @@ static void __attribute__((unused)) flysky_build_packet(uint8_t init)
|
||||
packet[2] = rx_tx_addr[2];
|
||||
packet[3] = rx_tx_addr[1];
|
||||
packet[4] = rx_tx_addr[0];
|
||||
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)
|
||||
packet[6+2*i]=highByte(Servo_data[ch[i]]); //high byte of servo timing(1000-2000us)
|
||||
packet[5 + i*2]=Servo_data[CH_AETR[i]]&0xFF; //low byte of servo timing(1000-2000us)
|
||||
packet[6 + i*2]=(Servo_data[CH_AETR[i]]>>8)&0xFF; //high byte of servo timing(1000-2000us)
|
||||
}
|
||||
flysky_apply_extension_flags();
|
||||
}
|
||||
|
||||
const uint8_t PROGMEM tx_channels[16][16] = {
|
||||
{0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0},
|
||||
{0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a},
|
||||
{0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82},
|
||||
{0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a},
|
||||
{0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96},
|
||||
{0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28},
|
||||
{0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64},
|
||||
{0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50},
|
||||
{0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64},
|
||||
{0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50},
|
||||
{0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
|
||||
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46},
|
||||
{0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82},
|
||||
{0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46},
|
||||
{0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
|
||||
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46},
|
||||
};
|
||||
|
||||
uint16_t ReadFlySky()
|
||||
{
|
||||
if (bind_counter)
|
||||
@@ -182,26 +181,24 @@ uint16_t ReadFlySky()
|
||||
}
|
||||
else
|
||||
{
|
||||
flysky_build_packet(0);
|
||||
A7105_WriteData(21, pgm_read_byte_near(&tx_channels[chanrow*16+chancol])-chanoffset);
|
||||
flysky_build_packet(0);
|
||||
A7105_WriteData(21, pgm_read_byte_near(&tx_channels[chanrow][chancol])-chanoffset);
|
||||
chancol = (chancol + 1) % 16;
|
||||
if (! chancol) //Keep transmit power updated
|
||||
A7105_SetPower();
|
||||
}
|
||||
return 1460;
|
||||
return 1510; //1460 on deviation but not working with the latest V911 bricks... Turnigy 9X v2 is 1533, Flysky TX for 9XR/9XR Pro is 1510, V911 TX is 1490.
|
||||
}
|
||||
|
||||
uint16_t initFlySky() {
|
||||
//A7105_Reset();
|
||||
A7105_Init(INIT_FLYSKY); //flysky_init();
|
||||
|
||||
if (rx_tx_addr[3] > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912)
|
||||
rx_tx_addr[3] = rx_tx_addr[3] - 0x70;
|
||||
chanrow=rx_tx_addr[3] % 16;
|
||||
if ((rx_tx_addr[3]&0xF0) > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912)
|
||||
rx_tx_addr[3]=rx_tx_addr[3]-0x70;
|
||||
chanrow=rx_tx_addr[3] & 0x0F;
|
||||
chancol=0;
|
||||
chanoffset=rx_tx_addr[3] / 16;
|
||||
chanoffset=rx_tx_addr[3]/16;
|
||||
|
||||
|
||||
if(IS_AUTOBIND_FLAG_on)
|
||||
bind_counter = FLYSKY_BIND_COUNT;
|
||||
else
|
||||
|
||||
@@ -17,299 +17,319 @@
|
||||
*/
|
||||
|
||||
#if defined(FRSKYX_CC2500_INO)
|
||||
|
||||
#include "iface_cc2500.h"
|
||||
|
||||
uint8_t chanskip;
|
||||
uint8_t calData[48][3];
|
||||
uint8_t channr;
|
||||
uint8_t pass_ = 1 ;
|
||||
uint8_t counter_rst;
|
||||
uint8_t ctr;
|
||||
uint8_t FS_flag=0;
|
||||
// uint8_t ptr[4]={0x01,0x12,0x23,0x30};
|
||||
//uint8_t ptr[4]={0x00,0x11,0x22,0x33};
|
||||
|
||||
const PROGMEM uint8_t hop_data[]={
|
||||
0x02, 0xD4, 0xBB, 0xA2, 0x89,
|
||||
0x70, 0x57, 0x3E, 0x25, 0x0C,
|
||||
0xDE, 0xC5, 0xAC, 0x93, 0x7A,
|
||||
0x61, 0x48, 0x2F, 0x16, 0xE8,
|
||||
0xCF, 0xB6, 0x9D, 0x84, 0x6B,
|
||||
0x52, 0x39, 0x20, 0x07, 0xD9,
|
||||
0xC0, 0xA7, 0x8E, 0x75, 0x5C,
|
||||
0x43, 0x2A, 0x11, 0xE3, 0xCA,
|
||||
0xB1, 0x98, 0x7F, 0x66, 0x4D,
|
||||
0x34, 0x1B, 0x00, 0x1D, 0x03
|
||||
};
|
||||
|
||||
uint8_t hop(uint8_t byte)
|
||||
{
|
||||
return pgm_read_byte_near(&hop_data[byte]);
|
||||
}
|
||||
#include "iface_cc2500.h"
|
||||
|
||||
uint16_t initFrSkyX()
|
||||
uint8_t chanskip;
|
||||
uint8_t channr;
|
||||
uint8_t counter_rst;
|
||||
uint8_t ctr;
|
||||
uint8_t FS_flag=0;
|
||||
uint8_t seq_last_sent;
|
||||
uint8_t seq_last_rcvd;
|
||||
|
||||
const PROGMEM uint8_t hop_data[]={
|
||||
0x02, 0xD4, 0xBB, 0xA2, 0x89,
|
||||
0x70, 0x57, 0x3E, 0x25, 0x0C,
|
||||
0xDE, 0xC5, 0xAC, 0x93, 0x7A,
|
||||
0x61, 0x48, 0x2F, 0x16, 0xE8,
|
||||
0xCF, 0xB6, 0x9D, 0x84, 0x6B,
|
||||
0x52, 0x39, 0x20, 0x07, 0xD9,
|
||||
0xC0, 0xA7, 0x8E, 0x75, 0x5C,
|
||||
0x43, 0x2A, 0x11, 0xE3, 0xCA,
|
||||
0xB1, 0x98, 0x7F, 0x66, 0x4D,
|
||||
0x34, 0x1B, 0x00, 0x1D, 0x03
|
||||
};
|
||||
|
||||
static uint8_t __attribute__((unused)) hop(uint8_t byte)
|
||||
{
|
||||
return pgm_read_byte_near(&hop_data[byte]);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) set_start(uint8_t ch )
|
||||
{
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_23_FSCAL3, calData[ch][0]);
|
||||
CC2500_WriteReg(CC2500_24_FSCAL2, calData[ch][1]);
|
||||
CC2500_WriteReg(CC2500_25_FSCAL1, calData[ch][2]);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, ch==47? 0:pgm_read_word(&hop_data[ch]));
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) frskyX_init()
|
||||
{
|
||||
CC2500_Reset();
|
||||
|
||||
for(uint8_t i=0;i<36;i++)
|
||||
{
|
||||
while(!chanskip)
|
||||
{
|
||||
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
|
||||
chanskip=random(0xfefefefe)%47;
|
||||
}
|
||||
while((chanskip-ctr)%4)
|
||||
ctr=(ctr+1)%4;
|
||||
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
|
||||
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
|
||||
|
||||
counter_rst=(chanskip-ctr)>>2;
|
||||
//for test***************
|
||||
//rx_tx_addr[3]=0xB3;
|
||||
//rx_tx_addr[2]=0xFD;
|
||||
//************************
|
||||
frskyX_init();
|
||||
//
|
||||
if(IS_AUTOBIND_FLAG_on)
|
||||
{
|
||||
state = FRSKY_BIND;
|
||||
initialize_data(1);
|
||||
}
|
||||
if(reg==CC2500_06_PKTLEN)
|
||||
val=0x1E;
|
||||
else
|
||||
{
|
||||
state = FRSKY_DATA1;
|
||||
initialize_data(0);
|
||||
}
|
||||
return 10000;
|
||||
}
|
||||
|
||||
uint16_t ReadFrSkyX()
|
||||
{
|
||||
switch(state)
|
||||
{
|
||||
default:
|
||||
set_start(47);
|
||||
CC2500_SetPower();
|
||||
cc2500_strobe(CC2500_SFRX);
|
||||
//
|
||||
frskyX_build_bind_packet();
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeFifo(packet, packet[0]+1);
|
||||
state++;
|
||||
return 9000;
|
||||
case FRSKY_BIND_DONE:
|
||||
initialize_data(0);
|
||||
channr=0;
|
||||
BIND_DONE;
|
||||
state++;
|
||||
break;
|
||||
case FRSKY_DATA1:
|
||||
LED_ON;
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
set_start(channr);
|
||||
CC2500_SetPower();
|
||||
cc2500_strobe(CC2500_SFRX);
|
||||
channr = (channr+chanskip)%47;
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeFifo(packet, packet[0]+1);
|
||||
//
|
||||
frskyX_data_frame();
|
||||
state++;
|
||||
return 5500;
|
||||
case FRSKY_DATA2:
|
||||
CC2500_SetTxRxMode(RX_EN);
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
state++;
|
||||
return 200;
|
||||
case FRSKY_DATA3:
|
||||
cc2500_strobe(CC2500_SRX);
|
||||
state++;
|
||||
return 3000;
|
||||
case FRSKY_DATA4:
|
||||
len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
||||
if (len &&(len<MAX_PKT))
|
||||
{
|
||||
cc2500_readFifo(pkt, len);
|
||||
#if defined TELEMETRY
|
||||
frsky_check_telemetry(pkt,len); //check if valid telemetry packets
|
||||
//parse telemetry packets here
|
||||
//The same telemetry function used by FrSky(D8).
|
||||
#endif
|
||||
}
|
||||
state = FRSKY_DATA1;
|
||||
return 300;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
void set_start(uint8_t ch )
|
||||
{
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, calData[ch][0]);
|
||||
cc2500_writeReg(CC2500_24_FSCAL2, calData[ch][1]);
|
||||
cc2500_writeReg(CC2500_25_FSCAL1, calData[ch][2]);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR, ch==47?0:pgm_read_word(&hop_data[ch]));
|
||||
}
|
||||
|
||||
void frskyX_init()
|
||||
{
|
||||
CC2500_Reset();
|
||||
cc2500_writeReg(CC2500_02_IOCFG0, 0x06);
|
||||
cc2500_writeReg(CC2500_00_IOCFG2, 0x06);
|
||||
cc2500_writeReg(CC2500_17_MCSM1, 0x0C);
|
||||
cc2500_writeReg(CC2500_18_MCSM0, 0x18);
|
||||
cc2500_writeReg(CC2500_06_PKTLEN, 0x1E);
|
||||
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x04);
|
||||
cc2500_writeReg(CC2500_08_PKTCTRL0, 0x01);
|
||||
cc2500_writeReg(CC2500_3E_PATABLE, 0xff);
|
||||
cc2500_writeReg(CC2500_0B_FSCTRL1, 0x0A);
|
||||
cc2500_writeReg(CC2500_0C_FSCTRL0, 0x00);
|
||||
cc2500_writeReg(CC2500_0D_FREQ2, 0x5c);
|
||||
cc2500_writeReg(CC2500_0E_FREQ1, 0x76);
|
||||
cc2500_writeReg(CC2500_0F_FREQ0, 0x27);
|
||||
cc2500_writeReg(CC2500_10_MDMCFG4, 0x7B);
|
||||
cc2500_writeReg(CC2500_11_MDMCFG3, 0x61);
|
||||
cc2500_writeReg(CC2500_12_MDMCFG2, 0x13);
|
||||
cc2500_writeReg(CC2500_13_MDMCFG1, 0x23);
|
||||
cc2500_writeReg(CC2500_14_MDMCFG0, 0x7a);
|
||||
cc2500_writeReg(CC2500_15_DEVIATN, 0x51);
|
||||
cc2500_writeReg(CC2500_19_FOCCFG, 0x16);
|
||||
cc2500_writeReg(CC2500_1A_BSCFG, 0x6c);
|
||||
cc2500_writeReg(CC2500_1B_AGCCTRL2,0x43);
|
||||
cc2500_writeReg(CC2500_1C_AGCCTRL1,0x40);
|
||||
cc2500_writeReg(CC2500_1D_AGCCTRL0,0x91);
|
||||
cc2500_writeReg(CC2500_21_FREND1, 0x56);
|
||||
cc2500_writeReg(CC2500_22_FREND0, 0x10);
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0xa9);
|
||||
cc2500_writeReg(CC2500_24_FSCAL2, 0x0A);
|
||||
cc2500_writeReg(CC2500_25_FSCAL1, 0x00);
|
||||
cc2500_writeReg(CC2500_26_FSCAL0, 0x11);
|
||||
cc2500_writeReg(CC2500_29_FSTEST, 0x59);
|
||||
cc2500_writeReg(CC2500_2C_TEST2, 0x88);
|
||||
cc2500_writeReg(CC2500_2D_TEST1, 0x31);
|
||||
cc2500_writeReg(CC2500_2E_TEST0, 0x0B);
|
||||
cc2500_writeReg(CC2500_03_FIFOTHR, 0x07);
|
||||
cc2500_writeReg(CC2500_09_ADDR, 0x00);
|
||||
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x04);
|
||||
cc2500_writeReg(CC2500_0C_FSCTRL0, option);
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
//
|
||||
for(uint8_t c=0;c < 47;c++){//calibrate hop channels
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR,pgm_read_word(&hop_data[c]));
|
||||
cc2500_strobe(CC2500_SCAL);
|
||||
delayMicroseconds(900);//
|
||||
calData[c][0] = cc2500_readReg(CC2500_23_FSCAL3);
|
||||
calData[c][1] = cc2500_readReg(CC2500_24_FSCAL2);
|
||||
calData[c][2] = cc2500_readReg(CC2500_25_FSCAL1);
|
||||
}
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR,0x00);
|
||||
cc2500_strobe(CC2500_SCAL);
|
||||
delayMicroseconds(900);
|
||||
calData[47][0] = cc2500_readReg(CC2500_23_FSCAL3);
|
||||
calData[47][1] = cc2500_readReg(CC2500_24_FSCAL2);
|
||||
calData[47][2] = cc2500_readReg(CC2500_25_FSCAL1);
|
||||
//#######END INIT########
|
||||
}
|
||||
|
||||
void initialize_data(uint8_t adr)
|
||||
{
|
||||
cc2500_writeReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
|
||||
cc2500_writeReg(CC2500_18_MCSM0, 0x8);
|
||||
cc2500_writeReg(CC2500_09_ADDR, adr ? 0x03 : rx_tx_addr[3]);
|
||||
cc2500_writeReg(CC2500_07_PKTCTRL1,0x05);
|
||||
}
|
||||
|
||||
void frskyX_build_bind_packet()
|
||||
{
|
||||
crc=0;
|
||||
packet[0] = 0x1D;
|
||||
packet[1] = 0x03;
|
||||
packet[2] = 0x01;
|
||||
//
|
||||
packet[3] = crc_Byte(rx_tx_addr[3]);
|
||||
packet[4] = crc_Byte(rx_tx_addr[2]);
|
||||
int idx = ((state -FRSKY_BIND) % 10) * 5;
|
||||
packet[5] = crc_Byte(idx);
|
||||
packet[6] = crc_Byte(pgm_read_word(&hop_data[idx++]));
|
||||
packet[7] = crc_Byte(pgm_read_word(&hop_data[idx++]));
|
||||
packet[8] = crc_Byte(pgm_read_word(&hop_data[idx++]));
|
||||
packet[9] = crc_Byte(pgm_read_word(&hop_data[idx++]));
|
||||
packet[10] = crc_Byte(pgm_read_word(&hop_data[idx++]));
|
||||
packet[11] = crc_Byte(0x02);
|
||||
packet[12] = crc_Byte(RX_num);
|
||||
//
|
||||
for(uint8_t i=13;i<28;i++)
|
||||
packet[i]=crc_Byte(0);
|
||||
//
|
||||
packet[28]=highByte(crc);
|
||||
packet[29]=lowByte(crc);
|
||||
//
|
||||
}
|
||||
|
||||
void frskyX_data_frame()
|
||||
{
|
||||
//0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12
|
||||
//
|
||||
uint8_t lpass = pass_ ;
|
||||
uint16_t chan_0 ;
|
||||
uint16_t chan_1 ;
|
||||
uint8_t flag2 = 0;
|
||||
uint8_t startChan = 0;
|
||||
crc = 0;
|
||||
//static uint8_t p = 0;
|
||||
//
|
||||
packet[0] = 0x1D;
|
||||
packet[1] = rx_tx_addr[3];
|
||||
packet[2] = rx_tx_addr[2];
|
||||
packet[3] = crc_Byte(0x02);
|
||||
//
|
||||
packet[4] = crc_Byte((ctr<<6)+channr); //*64
|
||||
packet[5] = crc_Byte(counter_rst);
|
||||
packet[6] = crc_Byte(RX_num);
|
||||
// FLAGS 00 - standard packet
|
||||
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
|
||||
//20 - range check packet
|
||||
packet[7] = crc_Byte(FS_flag);
|
||||
packet[8] = crc_Byte(flag2);
|
||||
//
|
||||
if ( lpass & 1 )
|
||||
startChan += 8 ;
|
||||
if(reg==CC2500_08_PKTCTRL0)
|
||||
val=0x01;
|
||||
else
|
||||
if(reg==CC2500_0B_FSCTRL1)
|
||||
val=0x0A;
|
||||
else
|
||||
if(reg==CC2500_10_MDMCFG4)
|
||||
val=0x7B;
|
||||
else
|
||||
if(reg==CC2500_11_MDMCFG3)
|
||||
val=0x61;
|
||||
else
|
||||
if(reg==CC2500_12_MDMCFG2)
|
||||
val=0x13;
|
||||
else
|
||||
if(reg==CC2500_15_DEVIATN)
|
||||
val=0x51;
|
||||
|
||||
for(uint8_t i = 0; i <12 ; i+=3)
|
||||
{//12 bytes
|
||||
chan_0 = scaleForPXX(startChan);
|
||||
if(lpass & 1 )
|
||||
chan_0+=2048;
|
||||
|
||||
packet[9+i] = crc_Byte(lowByte(chan_0));//3 bytes*4
|
||||
startChan++;
|
||||
chan_1 = scaleForPXX(startChan);
|
||||
if(lpass & 1 )
|
||||
chan_1+= 2048;
|
||||
|
||||
startChan++;
|
||||
packet[9+i+1]=crc_Byte((((chan_0>>8) & 0x0F)|(chan_1 << 4)));
|
||||
packet[9+i+2]=crc_Byte(chan_1>>4);
|
||||
}
|
||||
//packet[21]=crc_Byte(0x08);//first
|
||||
packet[21]=crc_Byte(0x80);//??? when received first telemetry frame is changed to 0x80
|
||||
//packet[21]=crc_Byte(ptr[p]);//???
|
||||
//p=(p+1)%4;//repeating 4 bytes sequence pattern every 4th frame.
|
||||
|
||||
pass_=lpass+1;
|
||||
|
||||
for (uint8_t i=22;i<28;i++)
|
||||
packet[i]=crc_Byte(0);
|
||||
|
||||
packet[28]=highByte(crc);
|
||||
packet[29]=lowByte(crc);
|
||||
CC2500_WriteReg(reg,val);
|
||||
}
|
||||
|
||||
uint16_t scaleForPXX( uint8_t i )
|
||||
{ //mapped 860,2140(125%) range to 64,1984(PXX values);
|
||||
return (uint16_t)(((Servo_data[i]-PPM_MIN)*3)>>1)+64;
|
||||
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x04);
|
||||
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
//
|
||||
for(uint8_t c=0;c < 47;c++)
|
||||
{//calibrate hop channels
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR,pgm_read_word(&hop_data[c]));
|
||||
CC2500_Strobe(CC2500_SCAL);
|
||||
delayMicroseconds(900);//
|
||||
calData[c][0] = CC2500_ReadReg(CC2500_23_FSCAL3);
|
||||
calData[c][1] = CC2500_ReadReg(CC2500_24_FSCAL2);
|
||||
calData[c][2] = CC2500_ReadReg(CC2500_25_FSCAL1);
|
||||
}
|
||||
|
||||
uint8_t crc_Byte( uint8_t byte )
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR,0x00);
|
||||
CC2500_Strobe(CC2500_SCAL);
|
||||
delayMicroseconds(900);
|
||||
calData[47][0] = CC2500_ReadReg(CC2500_23_FSCAL3);
|
||||
calData[47][1] = CC2500_ReadReg(CC2500_24_FSCAL2);
|
||||
calData[47][2] = CC2500_ReadReg(CC2500_25_FSCAL1);
|
||||
//#######END INIT########
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) initialize_data(uint8_t adr)
|
||||
{
|
||||
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
|
||||
CC2500_WriteReg(CC2500_18_MCSM0, 0x8);
|
||||
CC2500_WriteReg(CC2500_09_ADDR, adr ? 0x03 : rx_tx_addr[3]);
|
||||
CC2500_WriteReg(CC2500_07_PKTCTRL1,0x05);
|
||||
}
|
||||
/*
|
||||
static uint8_t __attribute__((unused)) crc_Byte( uint8_t byte )
|
||||
{
|
||||
crc = (crc<<8) ^ pgm_read_word(&CRCTable[((uint8_t)(crc>>8) ^ byte) & 0xFF]);
|
||||
return byte;
|
||||
}
|
||||
*/
|
||||
static uint16_t __attribute__((unused)) crc_x(uint8_t *data, uint8_t len)
|
||||
{
|
||||
uint16_t crc = 0;
|
||||
for(uint8_t i=0; i < len; i++)
|
||||
crc = (crc<<8) ^ pgm_read_word(&CRCTable[((uint8_t)(crc>>8) ^ *data++) & 0xFF]);
|
||||
return crc;
|
||||
}
|
||||
|
||||
// 0-2047, 0 = 817, 1024 = 1500, 2047 = 2182
|
||||
//64=860,1024=1500,1984=2140//Taranis 125%
|
||||
|
||||
static uint16_t __attribute__((unused)) scaleForPXX( uint8_t i )
|
||||
{ //mapped 860,2140(125%) range to 64,1984(PXX values);
|
||||
return (uint16_t)(((Servo_data[i]-PPM_MIN)*3)>>1)+64;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) frskyX_build_bind_packet()
|
||||
{
|
||||
packet[0] = 0x1D;
|
||||
packet[1] = 0x03;
|
||||
packet[2] = 0x01;
|
||||
//
|
||||
packet[3] = rx_tx_addr[3];
|
||||
packet[4] = rx_tx_addr[2];
|
||||
int idx = ((state -FRSKY_BIND) % 10) * 5;
|
||||
packet[5] = idx;
|
||||
packet[6] = pgm_read_word(&hop_data[idx++]);
|
||||
packet[7] = pgm_read_word(&hop_data[idx++]);
|
||||
packet[8] = pgm_read_word(&hop_data[idx++]);
|
||||
packet[9] = pgm_read_word(&hop_data[idx++]);
|
||||
packet[10] = pgm_read_word(&hop_data[idx++]);
|
||||
packet[11] = 0x02;
|
||||
packet[12] = RX_num;
|
||||
//
|
||||
memset(&packet[13], 0, 15);
|
||||
uint16_t lcrc = crc_x(&packet[3], 25);
|
||||
//
|
||||
packet[28] = lcrc >> 8;
|
||||
packet[29] = lcrc;
|
||||
//
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) frskyX_data_frame()
|
||||
{
|
||||
//0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12
|
||||
//
|
||||
static uint8_t lpass;
|
||||
uint16_t chan_0 ;
|
||||
uint16_t chan_1 ;
|
||||
uint8_t startChan = 0;
|
||||
//
|
||||
packet[0] = 0x1D;
|
||||
packet[1] = rx_tx_addr[3];
|
||||
packet[2] = rx_tx_addr[2];
|
||||
packet[3] = 0x02;
|
||||
//
|
||||
packet[4] = (ctr<<6)+channr;
|
||||
packet[5] = counter_rst;
|
||||
packet[6] = RX_num;
|
||||
//FLAGS 00 - standard packet
|
||||
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
|
||||
//20 - range check packet
|
||||
packet[7] = FS_flag;
|
||||
packet[8] = 0;
|
||||
//
|
||||
if ( lpass & 1 )
|
||||
startChan += 8 ;
|
||||
|
||||
for(uint8_t i = 0; i <12 ; i+=3)
|
||||
{//12 bytes
|
||||
chan_0 = scaleForPXX(startChan);
|
||||
if(lpass & 1 )
|
||||
chan_0+=2048;
|
||||
startChan+=1;
|
||||
//
|
||||
chan_1 = scaleForPXX(startChan);
|
||||
if(lpass & 1 )
|
||||
chan_1+= 2048;
|
||||
startChan+=1;
|
||||
//
|
||||
packet[9+i] = lowByte(chan_0);//3 bytes*4
|
||||
packet[9+i+1]=(((chan_0>>8) & 0x0F)|(chan_1 << 4));
|
||||
packet[9+i+2]=chan_1>>4;
|
||||
}
|
||||
|
||||
packet[21] = seq_last_sent << 4 | seq_last_rcvd;//8 at start
|
||||
if (seq_last_sent < 0x08 && seq_last_rcvd < 8)
|
||||
seq_last_sent = (seq_last_sent + 1) % 4;
|
||||
else if (seq_last_rcvd == 0x00)
|
||||
seq_last_sent = 1;
|
||||
|
||||
if(sub_protocol== CH_8 )// in X8 mode send only 8ch every 9ms
|
||||
lpass = 0 ;
|
||||
else
|
||||
lpass += 1 ;
|
||||
|
||||
for (uint8_t i=22;i<28;i++)
|
||||
packet[i]=0;
|
||||
uint16_t lcrc = crc_x(&packet[3], 25);
|
||||
|
||||
packet[28]=lcrc>>8;//high byte
|
||||
packet[29]=lcrc;//low byte
|
||||
}
|
||||
|
||||
uint16_t ReadFrSkyX()
|
||||
{
|
||||
switch(state)
|
||||
{
|
||||
default:
|
||||
set_start(47);
|
||||
CC2500_SetPower();
|
||||
CC2500_Strobe(CC2500_SFRX);
|
||||
//
|
||||
frskyX_build_bind_packet();
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteData(packet, packet[0]+1);
|
||||
state++;
|
||||
return 9000;
|
||||
case FRSKY_BIND_DONE:
|
||||
initialize_data(0);
|
||||
channr=0;
|
||||
BIND_DONE;
|
||||
state++;
|
||||
break;
|
||||
case FRSKY_DATA1:
|
||||
LED_ON;
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
set_start(channr);
|
||||
CC2500_SetPower();
|
||||
CC2500_Strobe(CC2500_SFRX);
|
||||
channr = (channr+chanskip)%47;
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteData(packet, packet[0]+1);
|
||||
//
|
||||
frskyX_data_frame();
|
||||
state++;
|
||||
return 5500;
|
||||
case FRSKY_DATA2:
|
||||
CC2500_SetTxRxMode(RX_EN);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
state++;
|
||||
return 200;
|
||||
case FRSKY_DATA3:
|
||||
CC2500_Strobe(CC2500_SRX);
|
||||
state++;
|
||||
return 3000;
|
||||
case FRSKY_DATA4:
|
||||
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
||||
if (len && (len<MAX_PKT))
|
||||
{
|
||||
CC2500_ReadData(pkt, len);
|
||||
#if defined TELEMETRY
|
||||
frsky_check_telemetry(pkt,len); //check if valid telemetry packets
|
||||
//parse telemetry packets here
|
||||
//The same telemetry function used by FrSky(D8).
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
counter++;
|
||||
// restart sequence on missed packet - might need count or timeout instead of one missed
|
||||
if(counter>100)
|
||||
{//~1sec
|
||||
seq_last_sent = 0;
|
||||
seq_last_rcvd = 8;
|
||||
counter=0;
|
||||
}
|
||||
}
|
||||
state = FRSKY_DATA1;
|
||||
return 300;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint16_t initFrSkyX()
|
||||
{
|
||||
while(!chanskip)
|
||||
{
|
||||
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
|
||||
chanskip=random(0xfefefefe)%47;
|
||||
}
|
||||
while((chanskip-ctr)%4)
|
||||
ctr=(ctr+1)%4;
|
||||
|
||||
counter_rst=(chanskip-ctr)>>2;
|
||||
//for test***************
|
||||
//rx_tx_addr[3]=0xB3;
|
||||
//rx_tx_addr[2]=0xFD;
|
||||
//************************
|
||||
frskyX_init();
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
//
|
||||
if(IS_AUTOBIND_FLAG_on)
|
||||
{
|
||||
state = FRSKY_BIND;
|
||||
initialize_data(1);
|
||||
}
|
||||
else
|
||||
{
|
||||
state = FRSKY_DATA1;
|
||||
initialize_data(0);
|
||||
}
|
||||
seq_last_sent = 0;
|
||||
seq_last_rcvd = 8;
|
||||
return 10000;
|
||||
}
|
||||
#endif
|
||||
@@ -38,57 +38,31 @@ static void __attribute__((unused)) frsky2way_init(uint8_t bind)
|
||||
// Configure cc2500 for tx mode
|
||||
CC2500_Reset();
|
||||
//
|
||||
cc2500_writeReg(CC2500_02_IOCFG0, 0x06);
|
||||
cc2500_writeReg(CC2500_00_IOCFG2, 0x06);
|
||||
cc2500_writeReg(CC2500_17_MCSM1, 0x0c);
|
||||
cc2500_writeReg(CC2500_18_MCSM0, 0x18);
|
||||
cc2500_writeReg(CC2500_06_PKTLEN, 0x19);
|
||||
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x04);
|
||||
cc2500_writeReg(CC2500_08_PKTCTRL0, 0x05);
|
||||
cc2500_writeReg(CC2500_3E_PATABLE, 0xff);
|
||||
cc2500_writeReg(CC2500_0B_FSCTRL1, 0x08);
|
||||
cc2500_writeReg(CC2500_0C_FSCTRL0, option);
|
||||
//base freq FREQ = 0x5C7627 (F = 2404MHz)
|
||||
cc2500_writeReg(CC2500_0D_FREQ2, 0x5c);
|
||||
cc2500_writeReg(CC2500_0E_FREQ1, 0x76);
|
||||
cc2500_writeReg(CC2500_0F_FREQ0, 0x27);
|
||||
//
|
||||
cc2500_writeReg(CC2500_10_MDMCFG4, 0xAA);
|
||||
cc2500_writeReg(CC2500_11_MDMCFG3, 0x39);
|
||||
cc2500_writeReg(CC2500_12_MDMCFG2, 0x11);
|
||||
cc2500_writeReg(CC2500_13_MDMCFG1, 0x23);
|
||||
cc2500_writeReg(CC2500_14_MDMCFG0, 0x7a);
|
||||
cc2500_writeReg(CC2500_15_DEVIATN, 0x42);
|
||||
cc2500_writeReg(CC2500_19_FOCCFG, 0x16);
|
||||
cc2500_writeReg(CC2500_1A_BSCFG, 0x6c);
|
||||
cc2500_writeReg(CC2500_1B_AGCCTRL2, bind ? 0x43 : 0x03);
|
||||
cc2500_writeReg(CC2500_1C_AGCCTRL1,0x40);
|
||||
cc2500_writeReg(CC2500_1D_AGCCTRL0,0x91);
|
||||
cc2500_writeReg(CC2500_21_FREND1, 0x56);
|
||||
cc2500_writeReg(CC2500_22_FREND0, 0x10);
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0xa9);
|
||||
cc2500_writeReg(CC2500_24_FSCAL2, 0x0A);
|
||||
cc2500_writeReg(CC2500_25_FSCAL1, 0x00);
|
||||
cc2500_writeReg(CC2500_26_FSCAL0, 0x11);
|
||||
cc2500_writeReg(CC2500_29_FSTEST, 0x59);
|
||||
cc2500_writeReg(CC2500_2C_TEST2, 0x88);
|
||||
cc2500_writeReg(CC2500_2D_TEST1, 0x31);
|
||||
cc2500_writeReg(CC2500_2E_TEST0, 0x0B);
|
||||
cc2500_writeReg(CC2500_03_FIFOTHR, 0x07);
|
||||
cc2500_writeReg(CC2500_09_ADDR, 0x00);
|
||||
//
|
||||
for(uint8_t i=0;i<36;i++)
|
||||
{
|
||||
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
|
||||
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
|
||||
|
||||
if(reg==CC2500_0C_FSCTRL0)
|
||||
val=option;
|
||||
else
|
||||
if(reg==CC2500_1B_AGCCTRL2)
|
||||
val=bind ? 0x43 : 0x03;
|
||||
CC2500_WriteReg(reg,val);
|
||||
}
|
||||
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
CC2500_SetPower();
|
||||
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
|
||||
cc2500_writeReg(CC2500_09_ADDR, bind ? 0x03 : rx_tx_addr[3]);
|
||||
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x05);
|
||||
cc2500_strobe(CC2500_SIDLE); // Go to idle...
|
||||
CC2500_WriteReg(CC2500_09_ADDR, bind ? 0x03 : rx_tx_addr[3]);
|
||||
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05);
|
||||
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
|
||||
//
|
||||
cc2500_writeReg(CC2500_0A_CHANNR, 0x00);
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
|
||||
cc2500_strobe(CC2500_SFRX);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
|
||||
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
|
||||
CC2500_Strobe(CC2500_SFRX);
|
||||
//#######END INIT########
|
||||
}
|
||||
|
||||
@@ -184,11 +158,11 @@ uint16_t ReadFrSky_2way()
|
||||
if (state < FRSKY_BIND_DONE)
|
||||
{
|
||||
frsky2way_build_bind_packet();
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR, 0x00);
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
|
||||
cc2500_strobe(CC2500_SFRX);//0x3A
|
||||
cc2500_writeFifo(packet, packet[0]+1);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
|
||||
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
|
||||
CC2500_Strobe(CC2500_SFRX);//0x3A
|
||||
CC2500_WriteData(packet, packet[0]+1);
|
||||
state++;
|
||||
return 9000;
|
||||
}
|
||||
@@ -202,7 +176,7 @@ uint16_t ReadFrSky_2way()
|
||||
else
|
||||
if (state == FRSKY_DATA5)
|
||||
{
|
||||
cc2500_strobe(CC2500_SRX);//0x34 RX enable
|
||||
CC2500_Strobe(CC2500_SRX);//0x34 RX enable
|
||||
state = FRSKY_DATA1;
|
||||
return 9200;
|
||||
}
|
||||
@@ -210,9 +184,9 @@ uint16_t ReadFrSky_2way()
|
||||
if (state == FRSKY_DATA4)
|
||||
{ //telemetry receive
|
||||
CC2500_SetTxRxMode(RX_EN);
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
|
||||
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
|
||||
state++;
|
||||
return 1300;
|
||||
}
|
||||
@@ -220,10 +194,10 @@ uint16_t ReadFrSky_2way()
|
||||
{
|
||||
if (state == FRSKY_DATA1)
|
||||
{
|
||||
len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
||||
if (len<=MAX_PKT)//27 bytes
|
||||
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
||||
if (len && len<=MAX_PKT)//27 bytes
|
||||
{
|
||||
cc2500_readFifo(pkt, len); //received telemetry packets
|
||||
CC2500_ReadData(pkt, len); //received telemetry packets
|
||||
#if defined(TELEMETRY)
|
||||
//parse telemetry packet here
|
||||
frsky_check_telemetry(pkt,len); //check if valid telemetry packets and buffer them.
|
||||
@@ -232,12 +206,12 @@ uint16_t ReadFrSky_2way()
|
||||
CC2500_SetTxRxMode(TX_EN);
|
||||
CC2500_SetPower(); // Set tx_power
|
||||
}
|
||||
cc2500_strobe(CC2500_SIDLE);
|
||||
cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
|
||||
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
|
||||
cc2500_strobe(CC2500_SFRX);
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
|
||||
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
|
||||
CC2500_Strobe(CC2500_SFRX);
|
||||
frsky2way_data_frame();
|
||||
cc2500_writeFifo(packet, packet[0]+1);
|
||||
CC2500_WriteData(packet, packet[0]+1);
|
||||
state++;
|
||||
}
|
||||
return state == FRSKY_DATA4 ? 7500 : 9000;
|
||||
|
||||
@@ -120,9 +120,8 @@ static void __attribute__((unused)) build_ch_data()
|
||||
{
|
||||
uint16_t temp;
|
||||
uint8_t i,j;
|
||||
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
|
||||
for (i = 0; i< 8; i++) {
|
||||
j=ch[i];
|
||||
j=CH_AETR[i];
|
||||
temp=map(limit_channel_100(j),PPM_MIN_100,PPM_MAX_100,0,1000);
|
||||
if (j == THROTTLE) // It is clear that hisky's throttle stick is made reversely, so I adjust it here on purpose
|
||||
temp = 1000 -temp;
|
||||
|
||||
@@ -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;
|
||||
|
||||
272
Multiprotocol/J6Pro_cyrf6936.ino
Normal file
272
Multiprotocol/J6Pro_cyrf6936.ino
Normal file
@@ -0,0 +1,272 @@
|
||||
/*
|
||||
This project is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Multiprotocol is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#if defined(J6PRO_CYRF6936_INO)
|
||||
|
||||
#include "iface_cyrf6936.h"
|
||||
|
||||
enum PktState {
|
||||
J6PRO_BIND,
|
||||
J6PRO_BIND_01,
|
||||
J6PRO_BIND_03_START,
|
||||
J6PRO_BIND_03_CHECK,
|
||||
J6PRO_BIND_05_1,
|
||||
J6PRO_BIND_05_2,
|
||||
J6PRO_BIND_05_3,
|
||||
J6PRO_BIND_05_4,
|
||||
J6PRO_BIND_05_5,
|
||||
J6PRO_BIND_05_6,
|
||||
J6PRO_CHANSEL,
|
||||
J6PRO_CHAN_1,
|
||||
J6PRO_CHAN_2,
|
||||
J6PRO_CHAN_3,
|
||||
J6PRO_CHAN_4,
|
||||
};
|
||||
|
||||
const uint8_t j6pro_sopcodes[][8] = {
|
||||
/* Note these are in order transmitted (LSB 1st) */
|
||||
{0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91},
|
||||
{0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F},
|
||||
{0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A},
|
||||
{0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50},
|
||||
{0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44},
|
||||
{0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46},
|
||||
{0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C},
|
||||
{0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74},
|
||||
{0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49},
|
||||
{0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72},
|
||||
{0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17},
|
||||
{0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table
|
||||
{0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above,
|
||||
{0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped
|
||||
{0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50},
|
||||
{0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44},
|
||||
{0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46},
|
||||
{0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C},
|
||||
{0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74},
|
||||
};
|
||||
const uint8_t bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49};
|
||||
const uint8_t data_code[] = {0x02, 0xf9, 0x93, 0x97, 0x02, 0xfa, 0x5c, 0xe3, 0x01, 0x2b, 0xf1, 0xdb, 0x01, 0x32, 0xbe, 0x6f};
|
||||
|
||||
static void __attribute__((unused)) j6pro_build_bind_packet()
|
||||
{
|
||||
packet[0] = 0x01; //Packet type
|
||||
packet[1] = 0x01; //FIXME: What is this? Model number maybe?
|
||||
packet[2] = 0x56; //FIXME: What is this?
|
||||
packet[3] = cyrfmfg_id[0];
|
||||
packet[4] = cyrfmfg_id[1];
|
||||
packet[5] = cyrfmfg_id[2];
|
||||
packet[6] = cyrfmfg_id[3];
|
||||
packet[7] = cyrfmfg_id[4];
|
||||
packet[8] = cyrfmfg_id[5];
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) j6pro_build_data_packet()
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t upperbits = 0;
|
||||
uint16_t value;
|
||||
packet[0] = 0xaa; //FIXME what is this?
|
||||
for (i = 0; i < 12; i++)
|
||||
{
|
||||
value = convert_channel_10b(CH_AETR[i]);
|
||||
packet[i+1] = value & 0xff;
|
||||
upperbits |= (value >> 8) << (i * 2);
|
||||
}
|
||||
packet[13] = upperbits & 0xff;
|
||||
packet[14] = (upperbits >> 8) & 0xff;
|
||||
packet[15] = (upperbits >> 16) & 0xff;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) j6pro_cyrf_init()
|
||||
{
|
||||
/* Initialise CYRF chip */
|
||||
CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02);
|
||||
CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3c);
|
||||
CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14);
|
||||
CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05);
|
||||
CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55);
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
CYRF_SetPower(0x05);
|
||||
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x8a);
|
||||
CYRF_SetPower(0x28);
|
||||
CYRF_WriteRegister(CYRF_12_DATA64_THOLD, 0x0e);
|
||||
CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xee);
|
||||
CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00);
|
||||
CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x00);
|
||||
CYRF_ConfigDataCode(data_code, 16);
|
||||
CYRF_WritePreamble(0x023333);
|
||||
|
||||
CYRF_GetMfgData(cyrfmfg_id);
|
||||
//Model match
|
||||
cyrfmfg_id[3]+=RX_num;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) cyrf_bindinit()
|
||||
{
|
||||
/* Use when binding */
|
||||
//0.060470# 03 2f
|
||||
CYRF_SetPower(0x28); //Deviation using max power, replaced by bind power...
|
||||
|
||||
CYRF_ConfigRFChannel(0x52);
|
||||
CYRF_ConfigSOPCode(bind_sop_code);
|
||||
CYRF_ConfigCRCSeed(0x0000);
|
||||
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
|
||||
//0.061511# 13 20
|
||||
|
||||
CYRF_ConfigRFChannel(0x52);
|
||||
//0.062684# 0f 05
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
//0.062792# 0f 05
|
||||
CYRF_WriteRegister(CYRF_02_TX_CTRL, 0x40);
|
||||
j6pro_build_bind_packet(); //01 01 e9 49 ec a9 c4 c1 ff
|
||||
//CYRF_WriteDataPacketLen(packet, 0x09);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) cyrf_datainit()
|
||||
{
|
||||
/* Use when already bound */
|
||||
//0.094007# 0f 05
|
||||
uint8_t sop_idx = (0xff & (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[5])) % 19;
|
||||
uint16_t crc = (0xff & (cyrfmfg_id[1] - cyrfmfg_id[4] + cyrfmfg_id[5])) |
|
||||
((0xff & (cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[4] + cyrfmfg_id[5])) << 8);
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
CYRF_ConfigSOPCode(j6pro_sopcodes[sop_idx]);
|
||||
CYRF_ConfigCRCSeed(crc);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) j6pro_set_radio_channels()
|
||||
{
|
||||
//FIXME: Query free channels
|
||||
//lowest channel is 0x08, upper channel is 0x4d?
|
||||
CYRF_FindBestChannels(hopping_frequency, 3, 5, 8, 77);
|
||||
hopping_frequency[3] = hopping_frequency[0];
|
||||
}
|
||||
|
||||
uint16_t ReadJ6Pro()
|
||||
{
|
||||
uint32_t start;
|
||||
|
||||
switch(phase)
|
||||
{
|
||||
case J6PRO_BIND:
|
||||
cyrf_bindinit();
|
||||
phase = J6PRO_BIND_01;
|
||||
//no break because we want to send the 1st bind packet now
|
||||
case J6PRO_BIND_01:
|
||||
CYRF_ConfigRFChannel(0x52);
|
||||
CYRF_SetTxRxMode(TX_EN);
|
||||
//0.062684# 0f 05
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
//0.062684# 0f 05
|
||||
CYRF_WriteDataPacketLen(packet, 0x09);
|
||||
phase = J6PRO_BIND_03_START;
|
||||
return 3000; //3msec
|
||||
case J6PRO_BIND_03_START:
|
||||
start=micros();
|
||||
while (micros()-start < 500) // Wait max 500µs
|
||||
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x06)
|
||||
break;
|
||||
CYRF_ConfigRFChannel(0x53);
|
||||
CYRF_SetTxRxMode(RX_EN);
|
||||
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
|
||||
phase = J6PRO_BIND_03_CHECK;
|
||||
return 30000; //30msec
|
||||
case J6PRO_BIND_03_CHECK:
|
||||
{
|
||||
uint8_t rx = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
|
||||
if((rx & 0x1a) == 0x1a) {
|
||||
rx = CYRF_ReadRegister(CYRF_0A_RX_LENGTH);
|
||||
if(rx == 0x0f) {
|
||||
rx = CYRF_ReadRegister(CYRF_09_RX_COUNT);
|
||||
if(rx == 0x0f) {
|
||||
//Expected and actual length are both 15
|
||||
CYRF_ReadDataPacketLen(packet, rx);
|
||||
if (packet[0] == 0x03 &&
|
||||
packet[3] == cyrfmfg_id[0] &&
|
||||
packet[4] == cyrfmfg_id[1] &&
|
||||
packet[5] == cyrfmfg_id[2] &&
|
||||
packet[6] == cyrfmfg_id[3] &&
|
||||
packet[7] == cyrfmfg_id[4] &&
|
||||
packet[8] == cyrfmfg_id[5])
|
||||
{
|
||||
//Send back Ack
|
||||
packet[0] = 0x05;
|
||||
CYRF_ConfigRFChannel(0x54);
|
||||
CYRF_SetTxRxMode(TX_EN);
|
||||
phase = J6PRO_BIND_05_1;
|
||||
return 2000; //2msec
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
phase = J6PRO_BIND_01;
|
||||
return 500;
|
||||
}
|
||||
case J6PRO_BIND_05_1:
|
||||
case J6PRO_BIND_05_2:
|
||||
case J6PRO_BIND_05_3:
|
||||
case J6PRO_BIND_05_4:
|
||||
case J6PRO_BIND_05_5:
|
||||
case J6PRO_BIND_05_6:
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
CYRF_WriteDataPacketLen(packet, 0x0f);
|
||||
phase = phase + 1;
|
||||
return 4600; //4.6msec
|
||||
case J6PRO_CHANSEL:
|
||||
BIND_DONE;
|
||||
j6pro_set_radio_channels();
|
||||
cyrf_datainit();
|
||||
phase = J6PRO_CHAN_1;
|
||||
case J6PRO_CHAN_1:
|
||||
//Keep transmit power updated
|
||||
CYRF_SetPower(0);
|
||||
j6pro_build_data_packet();
|
||||
//return 3400;
|
||||
case J6PRO_CHAN_2:
|
||||
//return 3500;
|
||||
case J6PRO_CHAN_3:
|
||||
//return 3750
|
||||
case J6PRO_CHAN_4:
|
||||
CYRF_ConfigRFChannel(hopping_frequency[phase - J6PRO_CHAN_1]);
|
||||
CYRF_SetTxRxMode(TX_EN);
|
||||
CYRF_WriteDataPacket(packet);
|
||||
if (phase == J6PRO_CHAN_4) {
|
||||
phase = J6PRO_CHAN_1;
|
||||
return 13900;
|
||||
}
|
||||
phase = phase + 1;
|
||||
return 3550;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint16_t initJ6Pro()
|
||||
{
|
||||
CYRF_Reset();
|
||||
j6pro_cyrf_init();
|
||||
|
||||
if(IS_AUTOBIND_FLAG_on) {
|
||||
phase = J6PRO_BIND;
|
||||
}
|
||||
else {
|
||||
phase = J6PRO_CHANSEL;
|
||||
}
|
||||
return 2400;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -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)
|
||||
@@ -37,40 +37,70 @@ enum{
|
||||
FLAG_MT_FLIP = 0x80,
|
||||
};
|
||||
|
||||
enum{
|
||||
// flags going to packet[6] (LS)
|
||||
FLAG_LS_INVERT = 0x01,
|
||||
FLAG_LS_RATE = 0x02,
|
||||
FLAG_LS_HEADLESS= 0x10,
|
||||
FLAG_LS_SNAPSHOT= 0x20,
|
||||
FLAG_LS_VIDEO = 0x40,
|
||||
FLAG_LS_FLIP = 0x80,
|
||||
};
|
||||
|
||||
enum {
|
||||
MT99XX_INIT = 0,
|
||||
MT99XX_BIND,
|
||||
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
|
||||
packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0xE1); // throttle
|
||||
{ // MT99XX & H7 & LS
|
||||
packet[0] = convert_channel_8b_scale(THROTTLE,0xE1,0x00); // throttle
|
||||
packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0xE1); // rudder
|
||||
packet[2] = convert_channel_8b_scale(AILERON ,0x00,0xE1); // aileron
|
||||
packet[2] = convert_channel_8b_scale(AILERON ,0xE1,0x00); // 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 //LS
|
||||
{
|
||||
packet[6] |= FLAG_LS_RATE // max rate
|
||||
| GET_FLAG( Servo_AUX2, FLAG_LS_INVERT ) //INVERT
|
||||
| GET_FLAG( Servo_AUX3, FLAG_LS_SNAPSHOT ) //SNAPSHOT
|
||||
| GET_FLAG( Servo_AUX4, FLAG_LS_VIDEO ) //VIDEO
|
||||
| GET_FLAG( Servo_AUX5, FLAG_LS_HEADLESS ); //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];
|
||||
@@ -79,9 +109,9 @@ static void __attribute__((unused)) MT99XX_send_packet()
|
||||
else
|
||||
{ // YZ
|
||||
packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0x64); // throttle
|
||||
packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0x64); // rudder
|
||||
packet[1] = convert_channel_8b_scale(RUDDER ,0x64,0x00); // rudder
|
||||
packet[2] = convert_channel_8b_scale(ELEVATOR,0x00,0x64); // elevator
|
||||
packet[3] = convert_channel_8b_scale(AILERON ,0x00,0x64); // aileron
|
||||
packet[3] = convert_channel_8b_scale(AILERON ,0x64,0x00); // aileron
|
||||
if(packet_count++ >= 23)
|
||||
{
|
||||
yz_seq_num ++;
|
||||
@@ -102,7 +132,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 +153,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 +169,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 *)"\0xCC\0xCC\0xCC\0xCC\0xCC", 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 +200,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
|
||||
@@ -187,31 +230,38 @@ uint16_t initMT99XX(void)
|
||||
BIND_IN_PROGRESS; // autobind protocol
|
||||
bind_counter = MT99XX_BIND_COUNT;
|
||||
|
||||
memcpy(hopping_frequency,"\0x02\0x48\0x0C\0x3e\0x16\0x34\0x20\0x2A,\0x2A\0x20\0x34\0x16\0x3e\0x0c\0x48\0x02",16);
|
||||
memcpy(hopping_frequency,"\x02\x48\x0C\x3e\x16\x34\x20\x2A\x2A\x20\x34\x16\x3e\x0c\x48\x02",16);
|
||||
|
||||
MT99XX_initialize_txid();
|
||||
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; // 3th 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[8] = 0xAA; // fixed
|
||||
packet_count=0;
|
||||
return MT99XX_INITIAL_WAIT+MT99XX_PACKET_PERIOD_MT;
|
||||
}
|
||||
|
||||
624
Multiprotocol/Makefile.xmega
Normal file
624
Multiprotocol/Makefile.xmega
Normal file
@@ -0,0 +1,624 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#----------------------------------------------------------------------------
|
||||
# WinAVR Makefile
|
||||
#
|
||||
# On command line:
|
||||
#
|
||||
# make all = Make software.
|
||||
#
|
||||
# make clean = Clean out built project files.
|
||||
#
|
||||
# make coff = Convert ELF to AVR COFF.
|
||||
#
|
||||
# make extcoff = Convert ELF to AVR Extended COFF.
|
||||
#
|
||||
# make program = Download the hex file to the device, using avrdude.
|
||||
# Please customize the avrdude settings below first!
|
||||
#
|
||||
# make debug = Start either simulavr or avarice as specified for debugging,
|
||||
# with avr-gdb or avr-insight as the front end for debugging.
|
||||
#
|
||||
# make filename.s = Just compile filename.c into the assembler code only.
|
||||
#
|
||||
# make filename.i = Create a preprocessed source file for use in submitting
|
||||
# bug reports to the GCC project.
|
||||
#
|
||||
# To rebuild project do "make clean" then "make all".
|
||||
#----------------------------------------------------------------------------
|
||||
|
||||
|
||||
# MCU name
|
||||
MCU = atxmega32d4
|
||||
|
||||
|
||||
# Processor frequency.
|
||||
# This will define a symbol, F_CPU, in all source code files equal to the
|
||||
# processor frequency. You can then use this symbol in your source code to
|
||||
# calculate timings. Do NOT tack on a 'UL' at the end, this will be done
|
||||
# automatically to create a 32-bit value in your source code.
|
||||
# Typical values are:
|
||||
# F_CPU = 1000000
|
||||
# F_CPU = 1843200
|
||||
# F_CPU = 2000000
|
||||
# F_CPU = 3686400
|
||||
# F_CPU = 4000000
|
||||
# F_CPU = 7372800
|
||||
# F_CPU = 8000000
|
||||
# F_CPU = 11059200
|
||||
# F_CPU = 14745600
|
||||
# F_CPU = 16000000
|
||||
# F_CPU = 18432000
|
||||
# F_CPU = 20000000
|
||||
F_CPU = 32000000
|
||||
|
||||
|
||||
# Output format. (can be srec, ihex, binary)
|
||||
FORMAT = ihex
|
||||
|
||||
|
||||
# Target file name (without extension).
|
||||
TARGET = MultiOrange
|
||||
|
||||
|
||||
# Object files directory
|
||||
# To put object files in current directory, use a dot (.), do NOT make
|
||||
# this an empty or blank macro!
|
||||
OBJDIR = .
|
||||
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
SRC =
|
||||
|
||||
|
||||
# List C++ source files here. (C dependencies are automatically generated.)
|
||||
CPPSRC = $(TARGET).cpp
|
||||
CPPSRC += Wmath.cpp
|
||||
#CPPSRC += DSM2_cyrf6936.cpp
|
||||
|
||||
# List Assembler source files here.
|
||||
# Make them always end in a capital .S. Files ending in a lowercase .s
|
||||
# will not be considered source files but generated files (assembler
|
||||
# output from the compiler), and will be deleted upon "make clean"!
|
||||
# Even though the DOS/Win* filesystem matches both .s and .S the same,
|
||||
# it will preserve the spelling of the filenames, and gcc itself does
|
||||
# care about how the name is spelled on its command-line.
|
||||
ASRC =
|
||||
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
|
||||
OPT = s
|
||||
|
||||
|
||||
# Debugging format.
|
||||
# Native formats for AVR-GCC's -g are dwarf-2 [default] or stabs.
|
||||
# AVR Studio 4.10 requires dwarf-2.
|
||||
# AVR [Extended] COFF format requires stabs, plus an avr-objcopy run.
|
||||
#DEBUG = stabs
|
||||
DEBUG = dwarf-2
|
||||
|
||||
|
||||
# List any extra directories to look for include files here.
|
||||
# Each directory must be seperated by a space.
|
||||
# Use forward slashes for directory separators.
|
||||
# For a directory that has spaces, enclose it in quotes.
|
||||
EXTRAINCDIRS =
|
||||
|
||||
|
||||
# Compiler flag to set the C Standard level.
|
||||
# c89 = "ANSI" C
|
||||
# gnu89 = c89 plus GCC extensions
|
||||
# c99 = ISO C99 standard (not yet fully implemented)
|
||||
# gnu99 = c99 plus GCC extensions
|
||||
CSTANDARD = -std=gnu99
|
||||
|
||||
|
||||
# Place -D or -U options here for C sources
|
||||
CDEFS = -DF_CPU=$(F_CPU)UL
|
||||
|
||||
|
||||
# Place -D or -U options here for ASM sources
|
||||
ADEFS = -DF_CPU=$(F_CPU)
|
||||
|
||||
|
||||
# Place -D or -U options here for C++ sources
|
||||
CPPDEFS = -DF_CPU=$(F_CPU)UL
|
||||
#CPPDEFS += -D__STDC_LIMIT_MACROS
|
||||
#CPPDEFS += -D__STDC_CONSTANT_MACROS
|
||||
|
||||
|
||||
|
||||
#---------------- Compiler Options C ----------------
|
||||
# -g*: generate debugging information
|
||||
# -O*: optimization level
|
||||
# -f...: tuning, see GCC manual and avr-libc documentation
|
||||
# -Wall...: warning level
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns...: create assembler listing
|
||||
CFLAGS = -g$(DEBUG)
|
||||
CFLAGS += $(CDEFS)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -funsigned-char
|
||||
CFLAGS += -funsigned-bitfields
|
||||
CFLAGS += -fpack-struct
|
||||
CFLAGS += -fshort-enums
|
||||
CFLAGS += -Wall
|
||||
CFLAGS += -Wno-main
|
||||
CFLAGS += -Wstrict-prototypes
|
||||
#CFLAGS += -mshort-calls
|
||||
#CFLAGS += -fno-unit-at-a-time
|
||||
#CFLAGS += -Wundef
|
||||
#CFLAGS += -Wunreachable-code
|
||||
#CFLAGS += -Wsign-compare
|
||||
CFLAGS += -Wa,-adlns=$(<:%.c=$(OBJDIR)/%.lst)
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
CFLAGS += $(CSTANDARD)
|
||||
# Next line dumps rtl file
|
||||
#CFLAGS += -dr
|
||||
#CFLAGS += -Wa,-adhlns=$(<:%.c=$(OBJDIR)/%.lst)
|
||||
|
||||
|
||||
#---------------- Compiler Options C++ ----------------
|
||||
# -g*: generate debugging information
|
||||
# -O*: optimization level
|
||||
# -f...: tuning, see GCC manual and avr-libc documentation
|
||||
# -Wall...: warning level
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns...: create assembler listing
|
||||
CPPFLAGS = -g$(DEBUG)
|
||||
CPPFLAGS += $(CPPDEFS)
|
||||
CPPFLAGS += -O$(OPT)
|
||||
CPPFLAGS += -funsigned-char
|
||||
CPPFLAGS += -funsigned-bitfields
|
||||
CPPFLAGS += -fpack-struct
|
||||
CPPFLAGS += -fshort-enums
|
||||
CPPFLAGS += -fno-exceptions
|
||||
CPPFLAGS += -Wall
|
||||
CFLAGS += -Wundef
|
||||
#CPPFLAGS += -mshort-calls
|
||||
#CPPFLAGS += -fno-unit-at-a-time
|
||||
#CPPFLAGS += -Wstrict-prototypes
|
||||
#CPPFLAGS += -Wunreachable-code
|
||||
#CPPFLAGS += -Wsign-compare
|
||||
CPPFLAGS += -Wa,-adlns=$(<:%.cpp=$(OBJDIR)/%.lst)
|
||||
CPPFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
#CPPFLAGS += $(CSTANDARD)
|
||||
#CPPFLAGS += -Wa,-adhlns=$(<:%.cpp=$(OBJDIR)/%.lst)
|
||||
|
||||
|
||||
#---------------- Assembler Options ----------------
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns: create listing
|
||||
# -gstabs: have the assembler create line number information; note that
|
||||
# for use in COFF files, additional information about filenames
|
||||
# and function names needs to be present in the assembler source
|
||||
# files -- see avr-libc docs [FIXME: not yet described there]
|
||||
# -listing-cont-lines: Sets the maximum number of continuation lines of hex
|
||||
# dump that will be displayed for a given single line of source input.
|
||||
ASFLAGS = $(ADEFS) -Wa,-adhlns=$(<:%.S=$(OBJDIR)/%.lst),-gstabs,--listing-cont-lines=100
|
||||
|
||||
|
||||
#---------------- Library Options ----------------
|
||||
# Minimalistic printf version
|
||||
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
|
||||
|
||||
# Floating point printf version (requires MATH_LIB = -lm below)
|
||||
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard printf version.
|
||||
PRINTF_LIB =
|
||||
#PRINTF_LIB = $(PRINTF_LIB_MIN)
|
||||
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
|
||||
|
||||
|
||||
# Minimalistic scanf version
|
||||
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
|
||||
|
||||
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
|
||||
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard scanf version.
|
||||
SCANF_LIB =
|
||||
#SCANF_LIB = $(SCANF_LIB_MIN)
|
||||
#SCANF_LIB = $(SCANF_LIB_FLOAT)
|
||||
|
||||
|
||||
MATH_LIB = -lm
|
||||
|
||||
|
||||
# List any extra directories to look for libraries here.
|
||||
# Each directory must be seperated by a space.
|
||||
# Use forward slashes for directory separators.
|
||||
# For a directory that has spaces, enclose it in quotes.
|
||||
EXTRALIBDIRS =
|
||||
|
||||
|
||||
|
||||
#---------------- External Memory Options ----------------
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# used for variables (.data/.bss) and heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,-Tdata=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# only used for heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,--section-start,.data=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
EXTMEMOPTS =
|
||||
|
||||
|
||||
|
||||
#---------------- Linker Options ----------------
|
||||
# -Wl,...: tell GCC to pass this to linker.
|
||||
# -Map: create map file
|
||||
# --cref: add cross reference to map file
|
||||
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
|
||||
LDFLAGS += $(EXTMEMOPTS)
|
||||
LDFLAGS += $(patsubst %,-L%,$(EXTRALIBDIRS))
|
||||
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
|
||||
#LDFLAGS += -Wl,--section-start=.text=0x00D0
|
||||
#LDFLAGS += -Wl,--section-start=.vectors=0x0080
|
||||
#LDFLAGS += -T avr3-167.ld
|
||||
LDFLAGS += -N
|
||||
|
||||
|
||||
|
||||
#---------------- Programming Options (avrdude) ----------------
|
||||
|
||||
# Programming hardware: alf avr910 avrisp bascom bsd
|
||||
# dt006 pavr picoweb pony-stk200 sp12 stk200 stk500
|
||||
#
|
||||
# Type: avrdude -c ?
|
||||
# to get a full listing.
|
||||
#
|
||||
AVRDUDE_PROGRAMMER = stk500
|
||||
|
||||
# com1 = serial port. Use lpt1 to connect to parallel port.
|
||||
AVRDUDE_PORT = com3
|
||||
|
||||
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
|
||||
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
|
||||
|
||||
|
||||
# Uncomment the following if you want avrdude's erase cycle counter.
|
||||
# Note that this counter needs to be initialized first using -Yn,
|
||||
# see avrdude manual.
|
||||
#AVRDUDE_ERASE_COUNTER = -y
|
||||
|
||||
# Uncomment the following if you do /not/ wish a verification to be
|
||||
# performed after programming the device.
|
||||
#AVRDUDE_NO_VERIFY = -V
|
||||
|
||||
# Increase verbosity level. Please use this when submitting bug
|
||||
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
|
||||
# to submit bug reports.
|
||||
#AVRDUDE_VERBOSE = -v -v
|
||||
|
||||
AVRDUDE_FLAGS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER)
|
||||
|
||||
|
||||
|
||||
#---------------- Debugging Options ----------------
|
||||
|
||||
# For simulavr only - target MCU frequency.
|
||||
DEBUG_MFREQ = $(F_CPU)
|
||||
|
||||
# Set the DEBUG_UI to either gdb or insight.
|
||||
# DEBUG_UI = gdb
|
||||
DEBUG_UI = insight
|
||||
|
||||
# Set the debugging back-end to either avarice, simulavr.
|
||||
DEBUG_BACKEND = avarice
|
||||
#DEBUG_BACKEND = simulavr
|
||||
|
||||
# GDB Init Filename.
|
||||
GDBINIT_FILE = __avr_gdbinit
|
||||
|
||||
# When using avarice settings for the JTAG
|
||||
JTAG_DEV = /dev/com1
|
||||
|
||||
# Debugging port used to communicate between GDB / avarice / simulavr.
|
||||
DEBUG_PORT = 4242
|
||||
|
||||
# Debugging host used to communicate between GDB / avarice / simulavr, normally
|
||||
# just set to localhost unless doing some sort of crazy debugging when
|
||||
# avarice is running on a different computer.
|
||||
DEBUG_HOST = localhost
|
||||
|
||||
|
||||
|
||||
#============================================================================
|
||||
|
||||
|
||||
# Define programs and commands.
|
||||
SHELL = sh
|
||||
CC = avr-gcc
|
||||
OBJCOPY = avr-objcopy
|
||||
OBJDUMP = avr-objdump
|
||||
SIZE = avr-size
|
||||
AR = avr-ar rcs
|
||||
NM = avr-nm
|
||||
AVRDUDE = avrdude
|
||||
REMOVE = rm -f
|
||||
REMOVEDIR = rm -rf
|
||||
COPY = cp
|
||||
WINSHELL = cmd
|
||||
|
||||
|
||||
# Define Messages
|
||||
# English
|
||||
MSG_ERRORS_NONE = Errors: none
|
||||
MSG_BEGIN = -------- begin --------
|
||||
MSG_END = -------- end --------
|
||||
MSG_SIZE_BEFORE = Size before:
|
||||
MSG_SIZE_AFTER = Size after:
|
||||
MSG_COFF = Converting to AVR COFF:
|
||||
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
|
||||
MSG_FLASH = Creating load file for Flash:
|
||||
MSG_EEPROM = Creating load file for EEPROM:
|
||||
MSG_EXTENDED_LISTING = Creating Extended Listing:
|
||||
MSG_SYMBOL_TABLE = Creating Symbol Table:
|
||||
MSG_LINKING = Linking:
|
||||
MSG_COMPILING = Compiling C:
|
||||
MSG_COMPILING_CPP = Compiling C++:
|
||||
MSG_ASSEMBLING = Assembling:
|
||||
MSG_CLEANING = Cleaning project:
|
||||
MSG_CREATING_LIBRARY = Creating library:
|
||||
|
||||
|
||||
|
||||
|
||||
# Define all object files.
|
||||
OBJ = $(SRC:%.c=$(OBJDIR)/%.o) $(CPPSRC:%.cpp=$(OBJDIR)/%.o) $(ASRC:%.S=$(OBJDIR)/%.o)
|
||||
|
||||
# Define all listing files.
|
||||
LST = $(SRC:%.c=$(OBJDIR)/%.lst) $(CPPSRC:%.cpp=$(OBJDIR)/%.lst) $(ASRC:%.S=$(OBJDIR)/%.lst)
|
||||
|
||||
|
||||
# Compiler flags to generate dependency files.
|
||||
GENDEPFLAGS = -MMD -MP -MF .dep/$(@F).d
|
||||
|
||||
|
||||
# Combine all necessary flags and optional flags.
|
||||
# Add target processor to flags.
|
||||
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) $(GENDEPFLAGS)
|
||||
ALL_CPPFLAGS = -mmcu=$(MCU) -I. -x c++ $(CPPFLAGS) $(GENDEPFLAGS)
|
||||
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
# Default target.
|
||||
all: begin gccversion sizebefore build sizeafter end
|
||||
|
||||
# Change the build target to build a HEX file or a library.
|
||||
build: elf hex eep lss sym bin
|
||||
#build: lib
|
||||
|
||||
|
||||
elf: $(TARGET).elf
|
||||
hex: $(TARGET).hex
|
||||
bin: $(TARGET).bin
|
||||
eep: $(TARGET).eep
|
||||
lss: $(TARGET).lss
|
||||
sym: $(TARGET).sym
|
||||
LIBNAME=lib$(TARGET).a
|
||||
lib: $(LIBNAME)
|
||||
|
||||
|
||||
|
||||
# Eye candy.
|
||||
# AVR Studio 3.x does not check make's exit code but relies on
|
||||
# the following magic strings to be generated by the compile job.
|
||||
begin:
|
||||
@echo
|
||||
@echo $(MSG_BEGIN)
|
||||
|
||||
end:
|
||||
@echo $(MSG_END)
|
||||
@echo
|
||||
|
||||
|
||||
# Display size of file.
|
||||
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
|
||||
ELFSIZE = $(SIZE) --mcu=$(MCU) --format=avr $(TARGET).elf
|
||||
|
||||
sizebefore:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); \
|
||||
2>/dev/null; echo; fi
|
||||
|
||||
sizeafter:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); \
|
||||
2>/dev/null; echo; fi
|
||||
|
||||
|
||||
|
||||
# Display compiler version information.
|
||||
gccversion :
|
||||
@$(CC) --version
|
||||
|
||||
|
||||
|
||||
# Program the device.
|
||||
program: $(TARGET).hex $(TARGET).eep
|
||||
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
|
||||
|
||||
|
||||
# Generate avr-gdb config/init file which does the following:
|
||||
# define the reset signal, load the target file, connect to target, and set
|
||||
# a breakpoint at main().
|
||||
gdb-config:
|
||||
@$(REMOVE) $(GDBINIT_FILE)
|
||||
@echo define reset >> $(GDBINIT_FILE)
|
||||
@echo SIGNAL SIGHUP >> $(GDBINIT_FILE)
|
||||
@echo end >> $(GDBINIT_FILE)
|
||||
@echo file $(TARGET).elf >> $(GDBINIT_FILE)
|
||||
@echo target remote $(DEBUG_HOST):$(DEBUG_PORT) >> $(GDBINIT_FILE)
|
||||
ifeq ($(DEBUG_BACKEND),simulavr)
|
||||
@echo load >> $(GDBINIT_FILE)
|
||||
endif
|
||||
@echo break main >> $(GDBINIT_FILE)
|
||||
|
||||
debug: gdb-config $(TARGET).elf
|
||||
ifeq ($(DEBUG_BACKEND), avarice)
|
||||
@echo Starting AVaRICE - Press enter when "waiting to connect" message displays.
|
||||
@$(WINSHELL) /c start avarice --jtag $(JTAG_DEV) --erase --program --file \
|
||||
$(TARGET).elf $(DEBUG_HOST):$(DEBUG_PORT)
|
||||
@$(WINSHELL) /c pause
|
||||
|
||||
else
|
||||
@$(WINSHELL) /c start simulavr --gdbserver --device $(MCU) --clock-freq \
|
||||
$(DEBUG_MFREQ) --port $(DEBUG_PORT)
|
||||
endif
|
||||
@$(WINSHELL) /c start avr-$(DEBUG_UI) --command=$(GDBINIT_FILE)
|
||||
|
||||
|
||||
|
||||
|
||||
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
|
||||
COFFCONVERT = $(OBJCOPY) --debugging
|
||||
COFFCONVERT += --change-section-address .data-0x800000
|
||||
COFFCONVERT += --change-section-address .bss-0x800000
|
||||
COFFCONVERT += --change-section-address .noinit-0x800000
|
||||
COFFCONVERT += --change-section-address .eeprom-0x810000
|
||||
|
||||
|
||||
|
||||
coff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
extcoff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
|
||||
# Create final output files (.hex, .eep) from ELF output file.
|
||||
%.hex: %.elf
|
||||
@echo
|
||||
@echo $(MSG_FLASH) $@
|
||||
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
|
||||
|
||||
%.bin: %.elf
|
||||
$(OBJCOPY) -O binary $< $@
|
||||
|
||||
%.eep: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EEPROM) $@
|
||||
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
|
||||
--change-section-lma .eeprom=0 --no-change-warnings -O $(FORMAT) $< $@ || exit 0
|
||||
|
||||
# Create extended listing file from ELF output file.
|
||||
%.lss: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_LISTING) $@
|
||||
$(OBJDUMP) -h -S $< > $@
|
||||
|
||||
# Create a symbol table from ELF output file.
|
||||
%.sym: %.elf
|
||||
@echo
|
||||
@echo $(MSG_SYMBOL_TABLE) $@
|
||||
$(NM) -n $< > $@
|
||||
|
||||
|
||||
|
||||
# Create library from object files.
|
||||
.SECONDARY : $(TARGET).a
|
||||
.PRECIOUS : $(OBJ)
|
||||
%.a: $(OBJ)
|
||||
@echo
|
||||
@echo $(MSG_CREATING_LIBRARY) $@
|
||||
$(AR) $@ $(OBJ)
|
||||
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(TARGET).elf
|
||||
.PRECIOUS : $(OBJ)
|
||||
%.elf: $(OBJ)
|
||||
@echo
|
||||
@echo $(MSG_LINKING) $@
|
||||
$(CC) $(ALL_CFLAGS) $^ --output $@ $(LDFLAGS)
|
||||
|
||||
|
||||
# Compile: create object files from C source files.
|
||||
$(OBJDIR)/%.o : %.c
|
||||
@echo
|
||||
@echo $(MSG_COMPILING) $<
|
||||
$(CC) -c $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Compile: create object files from C++ source files.
|
||||
$(OBJDIR)/%.o : %.cpp
|
||||
@echo
|
||||
@echo $(MSG_COMPILING_CPP) $<
|
||||
$(CC) -c $(ALL_CPPFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Compile: create assembler files from C source files.
|
||||
%.s : %.c
|
||||
$(CC) -S $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Compile: create assembler files from C++ source files.
|
||||
%.s : %.cpp
|
||||
$(CC) -S $(ALL_CPPFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Assemble: create object files from assembler source files.
|
||||
$(OBJDIR)/%.o : %.S
|
||||
@echo
|
||||
@echo $(MSG_ASSEMBLING) $<
|
||||
$(CC) -c $(ALL_ASFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Create preprocessed source for use in sending a bug report.
|
||||
%.i : %.c
|
||||
$(CC) -E -mmcu=$(MCU) -I. $(CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Target: clean project.
|
||||
clean: begin clean_list end
|
||||
|
||||
clean_list :
|
||||
@echo
|
||||
@echo $(MSG_CLEANING)
|
||||
$(REMOVE) $(TARGET).hex
|
||||
$(REMOVE) $(TARGET).eep
|
||||
$(REMOVE) $(TARGET).cof
|
||||
$(REMOVE) $(TARGET).elf
|
||||
$(REMOVE) $(TARGET).map
|
||||
$(REMOVE) $(TARGET).sym
|
||||
$(REMOVE) $(TARGET).lss
|
||||
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.o)
|
||||
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.lst)
|
||||
$(REMOVE) $(SRC:.c=.s)
|
||||
$(REMOVE) $(SRC:.c=.d)
|
||||
$(REMOVE) $(SRC:.c=.i)
|
||||
$(REMOVEDIR) .dep
|
||||
|
||||
|
||||
# Create object files directory
|
||||
$(shell mkdir $(OBJDIR) 2>/dev/null)
|
||||
|
||||
|
||||
# Include the dependency files.
|
||||
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
|
||||
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all begin finish end sizebefore sizeafter gccversion \
|
||||
build elf hex eep lss sym coff extcoff \
|
||||
clean clean_list program debug gdb-config
|
||||
|
||||
|
||||
|
||||
|
||||
479
Multiprotocol/MultiOrange.cpp.xmega
Normal file
479
Multiprotocol/MultiOrange.cpp.xmega
Normal file
@@ -0,0 +1,479 @@
|
||||
#define ARDUINO_AVR_PRO 1
|
||||
//#define __AVR_ATmega328P__ 1
|
||||
|
||||
#define XMEGA 1
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
static void protocol_init(void) ;
|
||||
static void update_aux_flags(void) ;
|
||||
static void PPM_Telemetry_serial_init(void) ;
|
||||
static uint32_t random_id(uint16_t adress, uint8_t create_new) ;
|
||||
static void update_serial_data(void) ;
|
||||
static void Mprotocol_serial_init(void) ;
|
||||
static void module_reset(void) ;
|
||||
static void update_led_status(void) ;
|
||||
static void set_rx_tx_addr(uint32_t id) ;
|
||||
uint16_t limit_channel_100(uint8_t ch) ;
|
||||
|
||||
|
||||
extern void NRF24L01_Reset(void ) ;
|
||||
extern void A7105_Reset(void ) ;
|
||||
extern void CC2500_Reset(void ) ;
|
||||
extern uint8_t CYRF_Reset(void ) ;
|
||||
extern void CYRF_SetTxRxMode(uint8_t mode) ;
|
||||
|
||||
extern void frskyUpdate(void) ;
|
||||
extern uint16_t initDsm2(void) ;
|
||||
extern uint16_t ReadDsm2(void) ;
|
||||
extern uint16_t DevoInit(void) ;
|
||||
extern uint16_t devo_callback(void) ;
|
||||
|
||||
extern void randomSeed(unsigned int seed) ;
|
||||
extern long random(long howbig) ;
|
||||
extern long map(long x, long in_min, long in_max, long out_min, long out_max) ;
|
||||
|
||||
extern uint32_t millis(void) ;
|
||||
extern uint32_t micros(void) ;
|
||||
extern void delayMicroseconds(uint16_t x) ;
|
||||
extern void init(void) ;
|
||||
|
||||
extern int analogRead(uint8_t pin) ;
|
||||
|
||||
#define A6 20
|
||||
#define A7 21
|
||||
|
||||
#define yield()
|
||||
|
||||
//void _delay_us( uint16_t x )
|
||||
//{
|
||||
// delayMicroseconds( x ) ;
|
||||
//}
|
||||
|
||||
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
|
||||
#define clockCyclesToMicroseconds(a) ( (a) / clockCyclesPerMicrosecond() )
|
||||
|
||||
// the prescaler is set so that timer0 ticks every 64 clock cycles, and the
|
||||
// the overflow handler is called every 256 ticks.
|
||||
#define MICROSECONDS_PER_TIMER0_OVERFLOW (clockCyclesToMicroseconds(64 * 256))
|
||||
|
||||
// the whole number of milliseconds per timer0 overflow
|
||||
#define MILLIS_INC (MICROSECONDS_PER_TIMER0_OVERFLOW / 1000)
|
||||
|
||||
// the fractional number of milliseconds per timer0 overflow. we shift right
|
||||
// by three to fit these numbers into a byte. (for the clock speeds we care
|
||||
// about - 8 and 16 MHz - this doesn't lose precision.)
|
||||
#define FRACT_INC ((MICROSECONDS_PER_TIMER0_OVERFLOW % 1000) >> 3)
|
||||
#define FRACT_MAX (1000 >> 3)
|
||||
|
||||
volatile unsigned long timer0_overflow_count = 0;
|
||||
volatile unsigned long timer0_millis = 0;
|
||||
static unsigned char timer0_fract = 0;
|
||||
|
||||
|
||||
|
||||
//void chipInit()
|
||||
//{
|
||||
// PR.PRGEN = 0 ; // RTC and event system active
|
||||
// PR.PRPC = 0 ; // No power reduction port C
|
||||
// PR.PRPD = 0 ; // No power reduction port D
|
||||
// PMIC.CTRL = 7 ;
|
||||
// OSC.CTRL = 0xC3 ; // unclear
|
||||
// OSC.CTRL |= 0x08 ; // Enable external oscillator
|
||||
// while( ( OSC.STATUS & 0x08 ) == 0 ) ; // Wait for ext osc to be ready
|
||||
// OSC.PLLCTRL = 0xC2 ; // Ext. Osc times 2
|
||||
// OSC.CTRL |= 0x10 ; // Enable PLL
|
||||
// while( ( OSC.STATUS & 0x10 ) == 0 ) ; // Wait PLL ready
|
||||
// CPU_CCP = 0xD8 ; // 0x34
|
||||
// CLK.CTRL = 0 ; // Select 2MHz internal clock
|
||||
// CPU_CCP = 0xD8 ; // 0x34
|
||||
// CLK.CTRL = 0x04 ; // Select PLL as clock (32MHz)
|
||||
// PORTD.OUTSET = 0x17 ;
|
||||
// PORTD.DIRSET = 0xB2 ;
|
||||
// PORTD.DIRCLR = 0x4D ;
|
||||
// PORTD.PIN0CTRL = 0x18 ;
|
||||
// PORTD.PIN2CTRL = 0x18 ;
|
||||
// PORTE.DIRSET = 0x01 ;
|
||||
// PORTE.DIRCLR = 0x02 ;
|
||||
// PORTE.OUTSET = 0x01 ;
|
||||
// PORTA.DIRCLR = 0xFF ;
|
||||
// PORTA.PIN0CTRL = 0x18 ;
|
||||
// PORTA.PIN1CTRL = 0x18 ;
|
||||
// PORTA.PIN2CTRL = 0x18 ;
|
||||
// PORTA.PIN3CTRL = 0x18 ;
|
||||
// PORTA.PIN4CTRL = 0x18 ;
|
||||
// PORTA.PIN5CTRL = 0x18 ;
|
||||
// PORTA.PIN6CTRL = 0x18 ;
|
||||
// PORTA.PIN7CTRL = 0x18 ;
|
||||
// PORTC.DIRSET = 0x20 ;
|
||||
// PORTC.OUTCLR = 0x20 ;
|
||||
// SPID.CTRL = 0x51 ;
|
||||
// PORTC.OUTSET = 0x08 ;
|
||||
// PORTC.DIRSET = 0x08 ;
|
||||
// PORTC.PIN3CTRL = 0x18 ;
|
||||
// PORTC.PIN2CTRL = 0x18 ;
|
||||
// USARTC0.BAUDCTRLA = 19 ;
|
||||
// USARTC0.BAUDCTRLB = 0 ;
|
||||
// USARTC0.CTRLB = 0x18 ;
|
||||
// USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
|
||||
// USARTC0.CTRLC = 0x03 ;
|
||||
|
||||
// TCC0.CTRLB = 0 ;
|
||||
// TCC0.CTRLC = 0 ;
|
||||
// TCC0.CTRLD = 0 ;
|
||||
// TCC0.CTRLE = 0 ;
|
||||
// TCC0.INTCTRLA = 0x01 ;
|
||||
// TCC0.INTCTRLB = 0 ;
|
||||
// TCC0.PER = 0x00FF ;
|
||||
// TCC0.CTRLA = 4 ;
|
||||
|
||||
// TCC1.CTRLB = 0 ;
|
||||
// TCC1.CTRLC = 0 ;
|
||||
// TCC1.CTRLD = 0 ;
|
||||
// TCC1.CTRLE = 0 ;
|
||||
// TCC1.INTCTRLA = 0x03 ;
|
||||
// TCC1.INTCTRLB = 0 ;
|
||||
// TCC1.PER = 0xFFFF ;
|
||||
// TCC1.CNT = 0 ;
|
||||
// TCC1.CTRLA = 4 ;
|
||||
|
||||
// TCD0.CTRLA = 4 ;
|
||||
// TCD0.INTCTRLA = 0x03 ;
|
||||
// TCD0.PER = 0x02ED ;
|
||||
|
||||
//// L0EDB() ;
|
||||
|
||||
// NVM.CTRLB &= 0xF7 ; // No EEPROM mapping
|
||||
//}
|
||||
|
||||
|
||||
|
||||
ISR(TCC0_OVF_vect)
|
||||
{
|
||||
// copy these to local variables so they can be stored in registers
|
||||
// (volatile variables must be read from memory on every access)
|
||||
unsigned long m = timer0_millis;
|
||||
unsigned char f = timer0_fract;
|
||||
|
||||
m += MILLIS_INC;
|
||||
f += FRACT_INC;
|
||||
if (f >= FRACT_MAX) {
|
||||
f -= FRACT_MAX;
|
||||
m += 1;
|
||||
}
|
||||
|
||||
timer0_fract = f;
|
||||
timer0_millis = m;
|
||||
timer0_overflow_count++;
|
||||
}
|
||||
|
||||
unsigned long millis()
|
||||
{
|
||||
unsigned long m;
|
||||
uint8_t oldSREG = SREG;
|
||||
|
||||
// disable interrupts while we read timer0_millis or we might get an
|
||||
// inconsistent value (e.g. in the middle of a write to timer0_millis)
|
||||
cli();
|
||||
m = timer0_millis;
|
||||
SREG = oldSREG;
|
||||
|
||||
return m;
|
||||
}
|
||||
|
||||
unsigned long micros()
|
||||
{
|
||||
unsigned long m;
|
||||
uint8_t oldSREG = SREG, t;
|
||||
|
||||
cli();
|
||||
m = timer0_overflow_count;
|
||||
t = TCC0.CNT ;
|
||||
|
||||
if ((TCC0.INTFLAGS & TC0_OVFIF_bm) && (t < 255))
|
||||
m++;
|
||||
|
||||
SREG = oldSREG;
|
||||
|
||||
return ((m << 8) + t) * (64 / clockCyclesPerMicrosecond());
|
||||
}
|
||||
|
||||
void delay(unsigned long ms)
|
||||
{
|
||||
uint16_t start = (uint16_t)micros();
|
||||
|
||||
while (ms > 0) {
|
||||
yield();
|
||||
if (((uint16_t)micros() - start) >= 1000) {
|
||||
ms--;
|
||||
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);
|
||||
#if F_CPU >= 20000000L
|
||||
// for the 20 MHz clock on rare Arduino boards
|
||||
|
||||
// for a one-microsecond delay, simply wait 2 cycle and return. The overhead
|
||||
// of the function call yields a delay of exactly a one microsecond.
|
||||
__asm__ __volatile__ (
|
||||
"nop" "\n\t"
|
||||
"nop"); //just waiting 2 cycle
|
||||
if (--us == 0)
|
||||
return;
|
||||
|
||||
// the following loop takes a 1/5 of a microsecond (4 cycles)
|
||||
// per iteration, so execute it five times for each microsecond of
|
||||
// delay requested.
|
||||
us = (us<<2) + us; // x5 us
|
||||
|
||||
// account for the time taken in the preceeding commands.
|
||||
us -= 2;
|
||||
|
||||
#elif F_CPU >= 16000000L
|
||||
// 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;
|
||||
#else
|
||||
// for the 8 MHz internal clock on the ATmega168
|
||||
|
||||
// for a one- or two-microsecond delay, simply return. the overhead of
|
||||
// the function calls takes more than two microseconds. can't just
|
||||
// subtract two, since us is unsigned; we'd overflow.
|
||||
if (--us == 0)
|
||||
return;
|
||||
if (--us == 0)
|
||||
return;
|
||||
|
||||
// the following loop takes half of a microsecond (4 cycles)
|
||||
// per iteration, so execute it twice for each microsecond of
|
||||
// delay requested.
|
||||
us <<= 1;
|
||||
|
||||
// partially compensate for the time taken by the preceeding commands.
|
||||
// we can't subtract any more than this or we'd overflow w/ small delays.
|
||||
us--;
|
||||
#endif
|
||||
|
||||
// busy wait
|
||||
__asm__ __volatile__ (
|
||||
"1: sbiw %0,1" "\n\t" // 2 cycles
|
||||
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
|
||||
);
|
||||
}
|
||||
|
||||
#ifndef cbi
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif
|
||||
#ifndef sbi
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
|
||||
|
||||
void init()
|
||||
{
|
||||
// this needs to be called before setup() or some functions won't
|
||||
// work there
|
||||
|
||||
// Enable external oscillator (16MHz)
|
||||
OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_256CLK_gc ;
|
||||
OSC.CTRL |= OSC_XOSCEN_bm ;
|
||||
while( ( OSC.STATUS & OSC_XOSCRDY_bm ) == 0 )
|
||||
/* wait */ ;
|
||||
// Enable PLL (*2 = 32MHz)
|
||||
OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2 ;
|
||||
OSC.CTRL |= OSC_PLLEN_bm ;
|
||||
while( ( OSC.STATUS & OSC_PLLRDY_bm ) == 0 )
|
||||
/* wait */ ;
|
||||
// Switch to PLL clock
|
||||
CPU_CCP = 0xD8 ;
|
||||
CLK.CTRL = CLK_SCLKSEL_RC2M_gc ;
|
||||
CPU_CCP = 0xD8 ;
|
||||
CLK.CTRL = CLK_SCLKSEL_PLL_gc ;
|
||||
|
||||
PMIC.CTRL = 7 ; // Enable all interrupt levels
|
||||
sei();
|
||||
|
||||
// on the ATmega168, timer 0 is also used for fast hardware pwm
|
||||
// (using phase-correct PWM would mean that timer 0 overflowed half as often
|
||||
// resulting in different millis() behavior on the ATmega8 and ATmega168)
|
||||
//#if defined(TCCR0A) && defined(WGM01)
|
||||
// sbi(TCCR0A, WGM01);
|
||||
// sbi(TCCR0A, WGM00);
|
||||
//#endif
|
||||
|
||||
|
||||
// TCC0 counts 0-255 at 4uS clock rate
|
||||
EVSYS.CH2MUX = 0x80 + 0x07 ; // Prescaler of 128
|
||||
TCC0.CTRLB = 0 ;
|
||||
TCC0.CTRLC = 0 ;
|
||||
TCC0.CTRLD = 0 ;
|
||||
TCC0.CTRLE = 0 ;
|
||||
TCC0.INTCTRLA = 0x01 ;
|
||||
TCC0.INTCTRLB = 0 ;
|
||||
TCC0.PER = 0x00FF ;
|
||||
TCC0.CTRLA = 0x0A ;
|
||||
|
||||
|
||||
#if defined(ADCSRA)
|
||||
// set a2d prescale factor to 128
|
||||
// 16 MHz / 128 = 125 KHz, inside the desired 50-200 KHz range.
|
||||
// XXX: this will not work properly for other clock speeds, and
|
||||
// this code should use F_CPU to determine the prescale factor.
|
||||
sbi(ADCSRA, ADPS2);
|
||||
sbi(ADCSRA, ADPS1);
|
||||
sbi(ADCSRA, ADPS0);
|
||||
|
||||
// enable a2d conversions
|
||||
sbi(ADCSRA, ADEN);
|
||||
#endif
|
||||
|
||||
// the bootloader connects pins 0 and 1 to the USART; disconnect them
|
||||
// here so they can be used as normal digital i/o; they will be
|
||||
// reconnected in Serial.begin()
|
||||
#if defined(UCSRB)
|
||||
UCSRB = 0;
|
||||
#elif defined(UCSR0B)
|
||||
UCSR0B = 0;
|
||||
#endif
|
||||
|
||||
// PPM interrupt
|
||||
PORTD.DIRCLR = 0x08 ; // D3 is input
|
||||
PORTD.PIN3CTRL = 0x01 ; // Rising edge
|
||||
PORTD.INT0MASK = 0x08 ;
|
||||
PORTD.INTCTRL = 0x02 ; // Medium level interrupt
|
||||
|
||||
// Dip Switch inputs
|
||||
PORTA.DIRCLR = 0xFF ;
|
||||
PORTA.PIN0CTRL = 0x18 ;
|
||||
PORTA.PIN1CTRL = 0x18 ;
|
||||
PORTA.PIN2CTRL = 0x18 ;
|
||||
PORTA.PIN3CTRL = 0x18 ;
|
||||
PORTA.PIN4CTRL = 0x18 ;
|
||||
PORTA.PIN5CTRL = 0x18 ;
|
||||
PORTA.PIN6CTRL = 0x18 ;
|
||||
PORTA.PIN7CTRL = 0x18 ;
|
||||
}
|
||||
|
||||
#define DEFAULT 1
|
||||
|
||||
uint8_t analog_reference = DEFAULT;
|
||||
|
||||
void analogReference(uint8_t mode)
|
||||
{
|
||||
// can't actually set the register here because the default setting
|
||||
// will connect AVCC and the AREF pin, which would cause a short if
|
||||
// there's something connected to AREF.
|
||||
analog_reference = mode;
|
||||
}
|
||||
|
||||
int analogRead(uint8_t pin)
|
||||
{
|
||||
uint8_t low, high;
|
||||
|
||||
#if defined(analogPinToChannel)
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
if (pin >= 18) pin -= 18; // allow for channel or pin numbers
|
||||
#endif
|
||||
pin = analogPinToChannel(pin);
|
||||
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
if (pin >= 54) pin -= 54; // allow for channel or pin numbers
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
if (pin >= 18) pin -= 18; // allow for channel or pin numbers
|
||||
#elif defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__)
|
||||
if (pin >= 24) pin -= 24; // allow for channel or pin numbers
|
||||
#else
|
||||
if (pin >= 14) pin -= 14; // allow for channel or pin numbers
|
||||
#endif
|
||||
|
||||
#if defined(ADCSRB) && defined(MUX5)
|
||||
// the MUX5 bit of ADCSRB selects whether we're reading from channels
|
||||
// 0 to 7 (MUX5 low) or 8 to 15 (MUX5 high).
|
||||
ADCSRB = (ADCSRB & ~(1 << MUX5)) | (((pin >> 3) & 0x01) << MUX5);
|
||||
#endif
|
||||
|
||||
// set the analog reference (high two bits of ADMUX) and select the
|
||||
// channel (low 4 bits). this also sets ADLAR (left-adjust result)
|
||||
// to 0 (the default).
|
||||
#if defined(ADMUX)
|
||||
ADMUX = (analog_reference << 6) | (pin & 0x07);
|
||||
#endif
|
||||
|
||||
// without a delay, we seem to read from the wrong channel
|
||||
//delay(1);
|
||||
|
||||
#if defined(ADCSRA) && defined(ADCL)
|
||||
// start the conversion
|
||||
sbi(ADCSRA, ADSC);
|
||||
|
||||
// ADSC is cleared when the conversion finishes
|
||||
while (bit_is_set(ADCSRA, ADSC));
|
||||
|
||||
// we have to read ADCL first; doing so locks both ADCL
|
||||
// and ADCH until ADCH is read. reading ADCL second would
|
||||
// cause the results of each conversion to be discarded,
|
||||
// as ADCL and ADCH would be locked when it completed.
|
||||
low = ADCL;
|
||||
high = ADCH;
|
||||
#else
|
||||
// we dont have an ADC, return 0
|
||||
low = 0;
|
||||
high = 0;
|
||||
#endif
|
||||
|
||||
// combine the two bytes
|
||||
return (high << 8) | low;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void A7105_Reset()
|
||||
{
|
||||
}
|
||||
void CC2500_Reset()
|
||||
{
|
||||
}
|
||||
void NRF24L01_Reset()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
#include "Multiprotocol.ino"
|
||||
|
||||
#include "cyrf6936_SPI.ino"
|
||||
#include "DSM2_cyrf6936.ino"
|
||||
#include "Devo_cyrf6936.ino"
|
||||
|
||||
#include "Telemetry.ino"
|
||||
|
||||
|
||||
int main(void)
|
||||
{
|
||||
init() ;
|
||||
setup() ;
|
||||
for(;;)
|
||||
{
|
||||
loop() ;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -14,12 +14,14 @@
|
||||
*/
|
||||
|
||||
// Check selected board type
|
||||
#ifndef ARDUINO_AVR_PRO
|
||||
#error You must select the board type "Arduino Pro or Pro Mini"
|
||||
#ifndef XMEGA
|
||||
#if not defined(ARDUINO_AVR_PRO) && not defined(ARDUINO_AVR_MINI)
|
||||
#error You must select the board type "Arduino Pro or Pro Mini" or "Arduino Mini"
|
||||
#endif
|
||||
#if F_CPU != 16000000L || not defined(__AVR_ATmega328P__)
|
||||
#error You must select the processor type "ATmega328(5V, 16MHz)"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//******************
|
||||
// Protocols
|
||||
@@ -44,7 +46,12 @@ enum PROTOCOLS
|
||||
MODE_FRSKYX = 15, // =>CC2500
|
||||
MODE_ESKY = 16, // =>NRF24L01
|
||||
MODE_MT99XX=17, // =>NRF24L01
|
||||
MODE_MJXQ=18 // =>NRF24L01
|
||||
MODE_MJXQ=18, // =>NRF24L01
|
||||
MODE_SHENQI=19, // =>NRF24L01
|
||||
MODE_FY326=20, // =>NRF24L01
|
||||
MODE_SFHSS=21, // =>CC2500
|
||||
MODE_J6PRO=22, // =>CYRF6936
|
||||
MODE_FQ777=23 // =>NRF24L01
|
||||
};
|
||||
|
||||
enum Flysky
|
||||
@@ -102,7 +109,8 @@ enum MT99XX
|
||||
{
|
||||
MT99 = 0,
|
||||
H7 = 1,
|
||||
YZ = 2
|
||||
YZ = 2,
|
||||
LS = 3
|
||||
};
|
||||
enum MJXQ
|
||||
{
|
||||
@@ -112,6 +120,12 @@ enum MJXQ
|
||||
H26D = 3
|
||||
};
|
||||
|
||||
enum FRSKYX
|
||||
{
|
||||
CH_16 = 0,
|
||||
CH_8 = 1,
|
||||
};
|
||||
|
||||
#define NONE 0
|
||||
#define P_HIGH 1
|
||||
#define P_LOW 0
|
||||
@@ -135,7 +149,11 @@ struct PPM_Parameters
|
||||
#define LED_pin 13 //Promini original led on B5
|
||||
//
|
||||
#define PPM_pin 3 //PPM -D3
|
||||
#ifdef XMEGA
|
||||
#define SDI_pin 6 //SDIO-D6
|
||||
#else
|
||||
#define SDI_pin 5 //SDIO-D5
|
||||
#endif
|
||||
#define SCLK_pin 4 //SCK-D4
|
||||
#define CS_pin 2 //CS-D2
|
||||
#define SDO_pin 6 //D6
|
||||
@@ -143,23 +161,51 @@ struct PPM_Parameters
|
||||
#define CTRL1 1 //C1 (A1)
|
||||
#define CTRL2 2 //C2 (A2)
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define CTRL1_on
|
||||
#define CTRL1_off
|
||||
//
|
||||
#define CTRL2_on
|
||||
#define CTRL2_off
|
||||
#else
|
||||
#define CTRL1_on PORTC |= _BV(1)
|
||||
#define CTRL1_off PORTC &= ~_BV(1)
|
||||
//
|
||||
#define CTRL2_on PORTC |= _BV(2)
|
||||
#define CTRL2_off PORTC &= ~_BV(2)
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define CS_on PORTD.OUTSET = _BV(4) //D4
|
||||
#define CS_off PORTD.OUTCLR = _BV(4) //D4
|
||||
#else
|
||||
#define CS_on PORTD |= _BV(2) //D2
|
||||
#define CS_off PORTD &= ~_BV(2) //D2
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define SCK_on PORTD.OUTSET = _BV(7) //D7
|
||||
#define SCK_off PORTD.OUTCLR = _BV(7) //D7
|
||||
#else
|
||||
#define SCK_on PORTD |= _BV(4) //D4
|
||||
#define SCK_off PORTD &= ~_BV(4) //D4
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define SDI_on PORTD.OUTSET = _BV(5) //D5
|
||||
#define SDI_off PORTD.OUTCLR = _BV(5) //D5
|
||||
#else
|
||||
#define SDI_on PORTD |= _BV(5) //D5
|
||||
#define SDI_off PORTD &= ~_BV(5) //D5
|
||||
#endif
|
||||
|
||||
#ifdef XMEGA
|
||||
#define SDI_1 (PORTD.IN & (1<<SDI_pin)) == (1<<SDI_pin) //D5
|
||||
#define SDI_0 (PORTD.IN & (1<<SDI_pin)) == 0x00 //D5
|
||||
#else
|
||||
#define SDI_1 (PIND & (1<<SDI_pin)) == (1<<SDI_pin) //D5
|
||||
#define SDI_0 (PIND & (1<<SDI_pin)) == 0x00 //D5
|
||||
#endif
|
||||
//
|
||||
#define SDI_SET_INPUT DDRD &= ~_BV(5) //D5
|
||||
#define SDI_SET_OUTPUT DDRD |= _BV(5) //D5
|
||||
@@ -170,17 +216,37 @@ struct PPM_Parameters
|
||||
//
|
||||
#define CYRF_RST_pin A5 //reset pin
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define CC25_CSN_on PORTD.OUTSET = _BV(7) //D7
|
||||
#define CC25_CSN_off PORTD.OUTCLR = _BV(7) //D7
|
||||
#else
|
||||
#define CC25_CSN_on PORTD |= _BV(7) //D7
|
||||
#define CC25_CSN_off PORTD &= ~_BV(7) //D7
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define NRF_CSN_on
|
||||
#define NRF_CSN_off
|
||||
#else
|
||||
#define NRF_CSN_on PORTB |= _BV(0) //D8
|
||||
#define NRF_CSN_off PORTB &= ~_BV(0) //D8
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define CYRF_CSN_on PORTD.OUTSET = _BV(4) //D9
|
||||
#define CYRF_CSN_off PORTD.OUTCLR = _BV(4) //D9
|
||||
#else
|
||||
#define CYRF_CSN_on PORTB |= _BV(1) //D9
|
||||
#define CYRF_CSN_off PORTB &= ~_BV(1) //D9
|
||||
#endif
|
||||
//
|
||||
#ifdef XMEGA
|
||||
#define SDO_1 (PORTD.IN & (1<<SDO_pin)) == (1<<SDO_pin) //D6
|
||||
#define SDO_0 (PORTD.IN & (1<<SDO_pin)) == 0x00 //D6
|
||||
#else
|
||||
#define SDO_1 (PIND & (1<<SDO_pin)) == (1<<SDO_pin) //D6
|
||||
#define SDO_0 (PIND & (1<<SDO_pin)) == 0x00 //D6
|
||||
#endif
|
||||
//
|
||||
#define RS_HI PORTC|=_BV(5) //reset pin cyrf
|
||||
#define RX_LO PORTB &= ~_BV(5)//
|
||||
@@ -188,11 +254,25 @@ struct PPM_Parameters
|
||||
//
|
||||
|
||||
// LED
|
||||
#ifdef XMEGA
|
||||
#define LED_ON PORTD.OUTCLR = _BV(1)
|
||||
#define LED_OFF PORTD.OUTSET = _BV(1)
|
||||
#define LED_TOGGLE PORTD.OUTTGL = _BV(1)
|
||||
#define LED_SET_OUTPUT PORTD.DIRSET = _BV(1)
|
||||
#define IS_LED_on ( (PORTD.OUT & _BV(1)) != 0x00 )
|
||||
#else
|
||||
#define LED_ON PORTB |= _BV(5)
|
||||
#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 )
|
||||
#endif
|
||||
|
||||
// TX
|
||||
#define TX_ON PORTD |= _BV(1)
|
||||
#define TX_OFF PORTD &= ~_BV(1)
|
||||
#define TX_TOGGLE PORTD ^= _BV(1)
|
||||
#define TX_SET_OUTPUT DDRD |= _BV(1)
|
||||
|
||||
// Macros
|
||||
#define NOP() __asm__ __volatile__("nop")
|
||||
@@ -281,10 +361,10 @@ enum A7105_POWER
|
||||
A7105_POWER_6 = 0x03<<3 | 0x07, // TXPOWER_100mW = 1dBm == PAC=3 TBG=7
|
||||
A7105_POWER_7 = 0x03<<3 | 0x07 // TXPOWER_150mW = 1dBm == PAC=3 TBG=7
|
||||
};
|
||||
#define A7105_HIGH_POWER A7105_POWER_5
|
||||
#define A7105_HIGH_POWER A7105_POWER_7
|
||||
#define A7105_LOW_POWER A7105_POWER_3
|
||||
#define A7105_BIND_POWER A7105_POWER_0
|
||||
#define A7105_RANGE_POWER A7105_POWER_0
|
||||
#define A7105_BIND_POWER A7105_POWER_0
|
||||
|
||||
// NRF Power
|
||||
// Power setting is 0..3 for nRF24L01
|
||||
@@ -298,25 +378,36 @@ enum NRF_POWER
|
||||
};
|
||||
#define NRF_HIGH_POWER NRF_POWER_2
|
||||
#define NRF_LOW_POWER NRF_POWER_1
|
||||
#define NRF_BIND_POWER NRF_POWER_0
|
||||
#define NRF_RANGE_POWER NRF_POWER_0
|
||||
#define NRF_BIND_POWER NRF_POWER_0
|
||||
|
||||
// CC2500 power
|
||||
// CC2500 power output from the chip itself
|
||||
// The numbers do not take into account any outside amplifier
|
||||
enum CC2500_POWER
|
||||
{
|
||||
CC2500_POWER_0 = 0xC5, // -12dbm
|
||||
CC2500_POWER_1 = 0x97, // -10dbm
|
||||
CC2500_POWER_2 = 0x6E, // -8dbm
|
||||
CC2500_POWER_3 = 0x7F, // -6dbm
|
||||
CC2500_POWER_4 = 0xA9, // -4dbm
|
||||
CC2500_POWER_5 = 0xBB, // -2dbm
|
||||
CC2500_POWER_6 = 0xFE, // 0dbm
|
||||
CC2500_POWER_7 = 0xFF // 1.5dbm
|
||||
CC2500_POWER_0 = 0x00, // –55dbm or less
|
||||
CC2500_POWER_1 = 0x50, // -30dbm
|
||||
CC2500_POWER_2 = 0x44, // –28dbm
|
||||
CC2500_POWER_3 = 0xC0, // –26dbm
|
||||
CC2500_POWER_4 = 0x84, // –24dbm
|
||||
CC2500_POWER_5 = 0x81, // –22dbm
|
||||
CC2500_POWER_6 = 0x46, // –20dbm
|
||||
CC2500_POWER_7 = 0x93, // –18dbm
|
||||
CC2500_POWER_8 = 0x55, // –16dbm
|
||||
CC2500_POWER_9 = 0x8D, // –14dbm
|
||||
CC2500_POWER_10 = 0xC6, // -12dbm
|
||||
CC2500_POWER_11 = 0x97, // -10dbm
|
||||
CC2500_POWER_12 = 0x6E, // -8dbm
|
||||
CC2500_POWER_13 = 0x7F, // -6dbm
|
||||
CC2500_POWER_14 = 0xA9, // -4dbm
|
||||
CC2500_POWER_15 = 0xBB, // -2dbm
|
||||
CC2500_POWER_16 = 0xFE, // 0dbm
|
||||
CC2500_POWER_17 = 0xFF // +1dbm
|
||||
};
|
||||
#define CC2500_HIGH_POWER CC2500_POWER_6
|
||||
#define CC2500_LOW_POWER CC2500_POWER_3
|
||||
#define CC2500_BIND_POWER CC2500_POWER_0
|
||||
#define CC2500_RANGE_POWER CC2500_POWER_0
|
||||
#define CC2500_HIGH_POWER CC2500_POWER_16
|
||||
#define CC2500_LOW_POWER CC2500_POWER_13
|
||||
#define CC2500_RANGE_POWER CC2500_POWER_1
|
||||
#define CC2500_BIND_POWER CC2500_POWER_1
|
||||
|
||||
// CYRF power
|
||||
enum CYRF_POWER
|
||||
@@ -332,8 +423,8 @@ enum CYRF_POWER
|
||||
};
|
||||
#define CYRF_HIGH_POWER CYRF_POWER_7
|
||||
#define CYRF_LOW_POWER CYRF_POWER_3
|
||||
#define CYRF_RANGE_POWER CYRF_POWER_1 // 1/30 of the full power distance
|
||||
#define CYRF_BIND_POWER CYRF_POWER_0
|
||||
#define CYRF_RANGE_POWER CYRF_POWER_0
|
||||
|
||||
enum TXRX_State {
|
||||
TXRX_OFF,
|
||||
@@ -419,6 +510,11 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
ESky 16
|
||||
MT99XX 17
|
||||
MJXQ 18
|
||||
SHENQI 19
|
||||
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
|
||||
@@ -465,11 +561,15 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
MT99 0
|
||||
H7 1
|
||||
YZ 2
|
||||
LS 3
|
||||
sub_protocol==MJXQ
|
||||
WLH08 0
|
||||
X600 1
|
||||
X800 2
|
||||
H26D 3
|
||||
sub_protocol==FRSKYX
|
||||
CH_16 0
|
||||
CH_8 1
|
||||
Power value => 0x80 0=High/1=Low
|
||||
Stream[3] = option_protocol;
|
||||
option_protocol value is -127..127
|
||||
@@ -482,4 +582,4 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
2047 +125%
|
||||
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
|
||||
*/
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
http://www.rcgroups.com/forums/showthread.php?t=2165676
|
||||
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/edit/master/README.md
|
||||
|
||||
Thanks to PhracturedBlue, Hexfet, Goebish and all protocol developers
|
||||
Thanks to PhracturedBlue, Hexfet, Goebish, Victzh and all protocol developers
|
||||
Ported from deviation firmware
|
||||
|
||||
This project is free software: you can redistribute it and/or modify
|
||||
@@ -22,9 +22,10 @@
|
||||
*/
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <util/delay.h>
|
||||
#include "Multiprotocol.h"
|
||||
|
||||
//#define DEBUG_TX
|
||||
|
||||
//Multiprotocol module configuration file
|
||||
#include "_Config.h"
|
||||
|
||||
@@ -44,8 +45,6 @@ uint8_t packet[40];
|
||||
// Servo data
|
||||
uint16_t Servo_data[NUM_CHN];
|
||||
uint8_t Servo_AUX;
|
||||
// PPM variable
|
||||
volatile uint16_t PPM_data[NUM_CHN];
|
||||
|
||||
// Protocol variables
|
||||
uint8_t rx_tx_addr[5];
|
||||
@@ -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,17 +64,29 @@ 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;
|
||||
|
||||
#if defined(FRSKYX_CC2500_INO) || defined(SFHSS_CC2500_INO)
|
||||
uint8_t calData[48][3];
|
||||
#endif
|
||||
|
||||
//Channel mapping for protocols
|
||||
const uint8_t CH_AETR[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
|
||||
//const uint8_t CH_TAER[]={THROTTLE, AILERON, ELEVATOR, RUDDER, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
|
||||
//const uint8_t CH_RETA[]={RUDDER, ELEVATOR, THROTTLE, AILERON, AUX1, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, AUX8};
|
||||
|
||||
// Mode_select variables
|
||||
uint8_t mode_select;
|
||||
uint8_t protocol_flags=0,protocol_flags2=0;
|
||||
|
||||
// PPM variable
|
||||
volatile uint16_t PPM_data[NUM_CHN];
|
||||
|
||||
// Serial variables
|
||||
#define RXBUFFER_SIZE 25
|
||||
#define TXBUFFER_SIZE 12
|
||||
#define TXBUFFER_SIZE 20
|
||||
volatile uint8_t rx_buff[RXBUFFER_SIZE];
|
||||
volatile uint8_t rx_ok_buff[RXBUFFER_SIZE];
|
||||
volatile uint8_t tx_buff[TXBUFFER_SIZE];
|
||||
@@ -92,9 +102,18 @@ uint8_t prev_protocol=0;
|
||||
#define MAX_PKT 27
|
||||
uint8_t pkt[MAX_PKT];//telemetry receiving packets
|
||||
#if defined(TELEMETRY)
|
||||
#if defined DSM2_CYRF6936_INO
|
||||
#define DSM_TELEMETRY
|
||||
#endif
|
||||
#if defined FRSKYX_CC2500_INO
|
||||
#define SPORT_TELEMETRY
|
||||
#endif
|
||||
#if defined FRSKY_CC2500_INO
|
||||
#define HUB_TELEMETRY
|
||||
#endif
|
||||
uint8_t pktt[MAX_PKT];//telemetry receiving packets
|
||||
volatile uint8_t tx_head;
|
||||
volatile uint8_t tx_tail;
|
||||
volatile uint8_t tx_head=0;
|
||||
volatile uint8_t tx_tail=0;
|
||||
uint8_t v_lipo;
|
||||
int16_t RSSI_dBm;
|
||||
//const uint8_t RSSI_offset=72;//69 71.72 values db
|
||||
@@ -110,6 +129,20 @@ static void CheckTimer(uint16_t (*cb)(void));
|
||||
// Init
|
||||
void setup()
|
||||
{
|
||||
#ifdef XMEGA
|
||||
PORTD.OUTSET = 0x17 ;
|
||||
PORTD.DIRSET = 0xB2 ;
|
||||
PORTD.DIRCLR = 0x4D ;
|
||||
PORTD.PIN0CTRL = 0x18 ;
|
||||
PORTD.PIN2CTRL = 0x18 ;
|
||||
PORTE.DIRSET = 0x01 ;
|
||||
PORTE.DIRCLR = 0x02 ;
|
||||
PORTE.OUTSET = 0x01 ;
|
||||
|
||||
for ( uint8_t count = 0 ; count < 20 ; count += 1 )
|
||||
asm("nop") ;
|
||||
PORTE.OUTCLR = 0x01 ;
|
||||
#else
|
||||
// General pinout
|
||||
DDRD = (1<<CS_pin)|(1<<SDI_pin)|(1<<SCLK_pin)|(1<<CS_pin)|(1<< CC25_CSN_pin);
|
||||
DDRC = (1<<CTRL1)|(1<<CTRL2); //output
|
||||
@@ -117,6 +150,7 @@ void setup()
|
||||
DDRB = _BV(0)|_BV(1);
|
||||
PORTB = _BV(2)|_BV(3)|_BV(4)|_BV(5);//pullup 10,11,12 and bind button
|
||||
PORTC = _BV(0);//A0 high pullup
|
||||
#endif
|
||||
|
||||
// Set Chip selects
|
||||
CS_on;
|
||||
@@ -127,9 +161,24 @@ void setup()
|
||||
SDI_on;
|
||||
SCK_off;
|
||||
|
||||
//#ifdef XMEGA
|
||||
// // SPI enable, master, prescale of 16
|
||||
// SPID.CTRL = SPI_ENABLE_bm | SPI_MASTER_bm | SPI_PRESCALER0_bm ;
|
||||
//#endif
|
||||
|
||||
// Timer1 config
|
||||
#ifdef XMEGA
|
||||
// TCC1 16-bit timer, clocked at 0.5uS
|
||||
EVSYS.CH3MUX = 0x80 + 0x04 ; // Prescaler of 16
|
||||
TCC1.CTRLB = 0; TCC1.CTRLC = 0; TCC1.CTRLD = 0; TCC1.CTRLE = 0;
|
||||
TCC1.INTCTRLA = 0; TCC1.INTCTRLB = 0;
|
||||
TCC1.PER = 0xFFFF ;
|
||||
TCC1.CNT = 0 ;
|
||||
TCC1.CTRLA = 0x0B ; // Event3 (prescale of 16)
|
||||
#else
|
||||
TCCR1A = 0;
|
||||
TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer
|
||||
#endif
|
||||
|
||||
// Set servos positions
|
||||
for(uint8_t i=0;i<NUM_CHN;i++)
|
||||
@@ -137,15 +186,27 @@ void setup()
|
||||
Servo_data[THROTTLE]=PPM_MIN_100;
|
||||
memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data));
|
||||
|
||||
//Wait for every component to start
|
||||
delay(100);
|
||||
|
||||
// Read status of bind button
|
||||
#ifdef XMEGA
|
||||
if( (PORTD.IN & _BV(2)) == 0x00 )
|
||||
#else
|
||||
if( (PINB & _BV(5)) == 0x00 )
|
||||
#endif
|
||||
BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan
|
||||
|
||||
// Read status of mode select binary switch
|
||||
// after this mode_select will be one of {0000, 0001, ..., 1111}
|
||||
#ifdef XMEGA
|
||||
mode_select=0x0F - ( PORTA.IN & 0x0F ) ; //encoder dip switches 1,2,4,8=>B2,B3,B4,C0
|
||||
mode_select = MODE_SERIAL ;
|
||||
#else
|
||||
mode_select=0x0F - ( ( (PINB>>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0
|
||||
#endif
|
||||
//**********************************
|
||||
//mode_select=14; // here to test PPM
|
||||
//mode_select=1; // here to test PPM
|
||||
//**********************************
|
||||
|
||||
// Update LED
|
||||
@@ -156,7 +217,18 @@ void setup()
|
||||
MProtocol_id_master=random_id(10,false);
|
||||
|
||||
//Init RF modules
|
||||
CC2500_Reset();
|
||||
#ifdef CC2500_INSTALLED
|
||||
CC2500_Reset();
|
||||
#endif
|
||||
#ifdef A7105_INSTALLED
|
||||
A7105_Reset();
|
||||
#endif
|
||||
#ifdef CYRF6936_INSTALLED
|
||||
CYRF_Reset();
|
||||
#endif
|
||||
#ifdef NFR24L01_INSTALLED
|
||||
NRF24L01_Reset();
|
||||
#endif
|
||||
|
||||
//Protocol and interrupts initialization
|
||||
if(mode_select != MODE_SERIAL)
|
||||
@@ -173,9 +245,12 @@ void setup()
|
||||
|
||||
protocol_init();
|
||||
|
||||
#ifndef XMEGA
|
||||
//Configure PPM interrupt
|
||||
EICRA |=(1<<ISC11); // The rising edge of INT1 pin D3 generates an interrupt request
|
||||
EIMSK |= (1<<INT1); // INT1 interrupt enable
|
||||
#endif
|
||||
|
||||
#if defined(TELEMETRY)
|
||||
PPM_Telemetry_serial_init(); // Configure serial for telemetry
|
||||
#endif
|
||||
@@ -217,7 +292,7 @@ void loop()
|
||||
}
|
||||
update_led_status();
|
||||
#if defined(TELEMETRY)
|
||||
if( ((cur_protocol[0]&0x1F)==MODE_FRSKY) || ((cur_protocol[0]&0x1F)==MODE_HUBSAN) || ((cur_protocol[0]&0x1F)==MODE_FRSKYX) )
|
||||
if( ((cur_protocol[0]&0x1F)==MODE_FRSKY) || ((cur_protocol[0]&0x1F)==MODE_HUBSAN) || ((cur_protocol[0]&0x1F)==MODE_FRSKYX) || ((cur_protocol[0]&0x1F)==MODE_DSM2) )
|
||||
frskyUpdate();
|
||||
#endif
|
||||
if (remote_callback != 0)
|
||||
@@ -260,8 +335,17 @@ static void update_led_status(void)
|
||||
// Protocol scheduler
|
||||
static void CheckTimer(uint16_t (*cb)(void))
|
||||
{
|
||||
uint16_t next_callback;
|
||||
uint32_t prev;
|
||||
uint16_t next_callback,diff;
|
||||
#ifdef XMEGA
|
||||
if( (TCC1.INTFLAGS & TC1_CCAIF_bm) != 0)
|
||||
{
|
||||
cli(); // disable global int
|
||||
TCC1.CCA = TCC1.CNT ; // Callback should already have been called... Use "now" as new sync point.
|
||||
sei(); // enable global int
|
||||
}
|
||||
else
|
||||
while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait before callback
|
||||
#else
|
||||
if( (TIFR1 & (1<<OCF1A)) != 0)
|
||||
{
|
||||
cli(); // disable global int
|
||||
@@ -270,25 +354,42 @@ static void CheckTimer(uint16_t (*cb)(void))
|
||||
}
|
||||
else
|
||||
while((TIFR1 & (1<<OCF1A)) == 0); // wait before callback
|
||||
prev=micros();
|
||||
next_callback=cb();
|
||||
if(prev+next_callback+50 > micros())
|
||||
{ // Callback did not took more than requested time for next callback
|
||||
if(next_callback>32000)
|
||||
{ // next_callback should not be more than 32767 so we will wait here...
|
||||
delayMicroseconds(next_callback-2000);
|
||||
cli(); // disable global int
|
||||
OCR1A=TCNT1+4000;
|
||||
sei(); // enable global int
|
||||
#endif
|
||||
do
|
||||
{
|
||||
next_callback=cb();
|
||||
while(next_callback>4000)
|
||||
{ // start to wait here as much as we can...
|
||||
next_callback=next_callback-2000;
|
||||
cli(); // disable global int
|
||||
#ifdef XMEGA
|
||||
TCC1.CCA +=2000*2; // set compare A for callback
|
||||
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag
|
||||
sei(); // enable global int
|
||||
while((TCC1.INTFLAGS & TC1_CCAIF_bm) == 0); // wait 2ms...
|
||||
#else
|
||||
OCR1A+=2000*2; // set compare A for callback
|
||||
TIFR1=(1<<OCF1A); // clear compare A=callback flag
|
||||
sei(); // enable global int
|
||||
while((TIFR1 & (1<<OCF1A)) == 0); // wait 2ms...
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
cli(); // disable global int
|
||||
OCR1A+=next_callback*2; // set compare A for callback
|
||||
sei(); // enable global int
|
||||
}
|
||||
TIFR1=(1<<OCF1A); // clear compare A=callback flag
|
||||
// at this point we have between 2ms and 4ms in next_callback
|
||||
cli(); // disable global int
|
||||
#ifdef XMEGA
|
||||
TCC1.CCA +=next_callback*2; // set compare A for callback
|
||||
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A=callback flag
|
||||
diff=TCC1.CCA-TCC1.CNT; // compare timer and comparator
|
||||
sei(); // enable global int
|
||||
#else
|
||||
OCR1A+=next_callback*2; // set compare A for callback
|
||||
TIFR1=(1<<OCF1A); // clear compare A=callback flag
|
||||
diff=OCR1A-TCNT1; // compare timer and comparator
|
||||
sei(); // enable global int
|
||||
#endif
|
||||
}
|
||||
while(diff&0x8000); // Callback did not took more than requested time for next callback
|
||||
// so we can let main do its stuff before next callback
|
||||
}
|
||||
|
||||
// Protocol start
|
||||
@@ -342,6 +443,14 @@ static void protocol_init()
|
||||
remote_callback = ReadFrSkyX;
|
||||
break;
|
||||
#endif
|
||||
#if defined(SFHSS_CC2500_INO)
|
||||
case MODE_SFHSS:
|
||||
CTRL1_off; //antenna RF2
|
||||
CTRL2_on;
|
||||
next_callback = initSFHSS();
|
||||
remote_callback = ReadSFHSS;
|
||||
break;
|
||||
#endif
|
||||
#if defined(DSM2_CYRF6936_INO)
|
||||
case MODE_DSM2:
|
||||
CTRL2_on; //antenna RF4
|
||||
@@ -357,6 +466,13 @@ static void protocol_init()
|
||||
remote_callback = devo_callback;
|
||||
break;
|
||||
#endif
|
||||
#if defined(J6PRO_CYRF6936_INO)
|
||||
case MODE_J6PRO:
|
||||
CTRL2_on; //antenna RF4
|
||||
next_callback = initJ6Pro();
|
||||
remote_callback = ReadJ6Pro;
|
||||
break;
|
||||
#endif
|
||||
#if defined(HISKY_NRF24L01_INO)
|
||||
case MODE_HISKY:
|
||||
next_callback=initHiSky();
|
||||
@@ -428,6 +544,24 @@ static void protocol_init()
|
||||
next_callback=initMJXQ();
|
||||
remote_callback = MJXQ_callback;
|
||||
break;
|
||||
#endif
|
||||
#if defined(SHENQI_NRF24L01_INO)
|
||||
case MODE_SHENQI:
|
||||
next_callback=initSHENQI();
|
||||
remote_callback = SHENQI_callback;
|
||||
break;
|
||||
#endif
|
||||
#if defined(FY326_NRF24L01_INO)
|
||||
case MODE_FY326:
|
||||
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
|
||||
}
|
||||
|
||||
@@ -437,9 +571,15 @@ static void protocol_init()
|
||||
next_callback=2000;
|
||||
}
|
||||
cli(); // disable global int
|
||||
#ifdef XMEGA
|
||||
TCC1.CCA = TCC1.CNT + next_callback*2; // set compare A for callback
|
||||
sei(); // enable global int
|
||||
TCC1.INTFLAGS = TC1_CCAIF_bm ; // clear compare A flag
|
||||
#else
|
||||
OCR1A=TCNT1+next_callback*2; // set compare A for callback
|
||||
sei(); // enable global int
|
||||
TIFR1=(1<<OCF1A); // clear compare A flag
|
||||
#endif
|
||||
BIND_BUTTON_FLAG_off; // do not bind/reset id anymore even if protocol change
|
||||
}
|
||||
|
||||
@@ -504,19 +644,32 @@ static void module_reset()
|
||||
break;
|
||||
case MODE_FRSKY:
|
||||
case MODE_FRSKYX:
|
||||
case MODE_SFHSS:
|
||||
CC2500_Reset();
|
||||
break;
|
||||
case MODE_DSM2:
|
||||
case MODE_DEVO:
|
||||
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
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max)
|
||||
{
|
||||
// return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
long y ;
|
||||
x -= in_min ;
|
||||
y = out_max - out_min ;
|
||||
y *= x ;
|
||||
x = y / (in_max - in_min) ;
|
||||
return x + out_min ;
|
||||
}
|
||||
|
||||
// Channel value is converted to 8bit values full scale
|
||||
uint8_t convert_channel_8b(uint8_t num)
|
||||
{
|
||||
@@ -575,35 +728,68 @@ void Serial_write(uint8_t data)
|
||||
if(++tx_head>=TXBUFFER_SIZE)
|
||||
tx_head=0;
|
||||
tx_buff[tx_head]=data;
|
||||
sei(); // enable global int
|
||||
#ifdef XMEGA
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ;
|
||||
#else
|
||||
UCSR0B |= (1<<UDRIE0);//enable UDRE interrupt
|
||||
#endif
|
||||
sei(); // enable global int
|
||||
}
|
||||
#endif
|
||||
|
||||
static void Mprotocol_serial_init()
|
||||
{
|
||||
#define BAUD 100000
|
||||
#ifdef XMEGA
|
||||
|
||||
PORTC.OUTSET = 0x08 ;
|
||||
PORTC.DIRSET = 0x08 ;
|
||||
|
||||
USARTC0.BAUDCTRLA = 19 ;
|
||||
USARTC0.BAUDCTRLB = 0 ;
|
||||
|
||||
USARTC0.CTRLB = 0x18 ;
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
|
||||
USARTC0.CTRLC = 0x2B ;
|
||||
USARTC0.DATA ;
|
||||
#else
|
||||
|
||||
#include <util/setbaud.h>
|
||||
UBRR0H = UBRRH_VALUE;
|
||||
UBRR0L = UBRRL_VALUE;
|
||||
UCSR0A = 0 ; // Clear X2 bit
|
||||
//Set frame format to 8 data bits, even parity, 2 stop bits
|
||||
UCSR0C |= (1<<UPM01)|(1<<USBS0)|(1<<UCSZ01)|(1<<UCSZ00);
|
||||
UCSR0C = (1<<UPM01)|(1<<USBS0)|(1<<UCSZ01)|(1<<UCSZ00);
|
||||
while ( UCSR0A & (1 << RXC0) )//flush receive buffer
|
||||
UDR0;
|
||||
//enable reception and RC complete interrupt
|
||||
UCSR0B |= (1<<RXEN0)|(1<<RXCIE0);//rx enable and interrupt
|
||||
UCSR0B = (1<<RXEN0)|(1<<RXCIE0);//rx enable and interrupt
|
||||
#ifdef DEBUG_TX
|
||||
TX_SET_OUTPUT;
|
||||
#else
|
||||
UCSR0B |= (1<<TXEN0);//tx enable
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(TELEMETRY)
|
||||
static void PPM_Telemetry_serial_init()
|
||||
{
|
||||
#ifdef XMEGA
|
||||
USARTC0.BAUDCTRLA = 207 ;
|
||||
USARTC0.BAUDCTRLB = 0 ;
|
||||
|
||||
USARTC0.CTRLB = 0x18 ;
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
|
||||
USARTC0.CTRLC = 0x03 ;
|
||||
#else
|
||||
//9600 bauds
|
||||
UBRR0H = 0x00;
|
||||
UBRR0L = 0x67;
|
||||
UCSR0A = 0 ; // Clear X2 bit
|
||||
//Set frame format to 8 data bits, none, 1 stop bit
|
||||
UCSR0C |= (1<<UCSZ01)|(1<<UCSZ00);
|
||||
UCSR0B |= (1<<TXEN0);//tx enable
|
||||
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
|
||||
UCSR0B = (1<<TXEN0);//tx enable
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -642,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 **/
|
||||
@@ -649,13 +995,21 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
/**************************/
|
||||
|
||||
//PPM
|
||||
#ifdef XMEGA
|
||||
ISR(PORTD_INT0_vect)
|
||||
#else
|
||||
ISR(INT1_vect)
|
||||
#endif
|
||||
{ // Interrupt on PPM pin
|
||||
static int8_t chan=-1;
|
||||
static uint16_t Prev_TCNT1=0;
|
||||
uint16_t Cur_TCNT1;
|
||||
|
||||
#ifdef XMEGA
|
||||
Cur_TCNT1 = TCC1.CNT - Prev_TCNT1 ; // Capture current Timer1 value
|
||||
#else
|
||||
Cur_TCNT1=TCNT1-Prev_TCNT1; // Capture current Timer1 value
|
||||
#endif
|
||||
if(Cur_TCNT1<1000)
|
||||
chan=-1; // bad frame
|
||||
else
|
||||
@@ -678,62 +1032,107 @@ ISR(INT1_vect)
|
||||
}
|
||||
|
||||
//Serial RX
|
||||
#ifdef XMEGA
|
||||
ISR(USARTC0_RXC_vect)
|
||||
#else
|
||||
ISR(USART_RX_vect)
|
||||
#endif
|
||||
{ // RX interrupt
|
||||
#ifdef XMEGA
|
||||
if((USARTC0.STATUS & 0x1C)==0) // Check frame error, data overrun and parity error
|
||||
#else
|
||||
if((UCSR0A&0x1C)==0) // Check frame error, data overrun and parity error
|
||||
#endif
|
||||
{ // received byte is ok to process
|
||||
if(idx==0)
|
||||
{ // Let's try to sync at this point
|
||||
#ifdef XMEGA
|
||||
if(USARTC0.DATA==0x55) // If 1st byte is 0x55 it looks ok
|
||||
#else
|
||||
if(UDR0==0x55) // If 1st byte is 0x55 it looks ok
|
||||
#endif
|
||||
{
|
||||
idx++;
|
||||
#ifdef XMEGA
|
||||
TCC1.CCB = TCC1.CNT+(6500L) ; // Full message should be received within timer of 3250us
|
||||
TCC1.INTFLAGS = TC1_CCBIF_bm ; // clear OCR1B match flag
|
||||
TCC1.INTCTRLB = (TCC1.INTCTRLB & 0xF3) | 0x04 ; // enable interrupt on compare B match
|
||||
#else
|
||||
OCR1B=TCNT1+6500L; // Full message should be received within timer of 3250us
|
||||
TIFR1=(1<<OCF1B); // clear OCR1B match flag
|
||||
TIMSK1 |=(1<<OCIE1B); // enable interrupt on compare B match
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
rx_buff[(idx++)-1]=UDR0; // Store received byte
|
||||
#ifdef XMEGA
|
||||
rx_buff[(idx++)-1]=USARTC0.DATA; // Store received byte
|
||||
#else
|
||||
rx_buff[(idx++)-1]=UDR0; // Store received byte
|
||||
#endif
|
||||
if(idx>RXBUFFER_SIZE)
|
||||
{ // A full frame has been received
|
||||
TIMSK1 &=~(1<<OCIE1B); // disable interrupt on compare B match
|
||||
#ifdef XMEGA
|
||||
TCC1.INTCTRLB &=0xF3; // disable interrupt on compare B match
|
||||
#else
|
||||
TIMSK1 &=~(1<<OCIE1B); // disable interrupt on compare B match
|
||||
#endif
|
||||
if(!IS_RX_FLAG_on)
|
||||
{ //Good frame received and main has finished with previous buffer
|
||||
for(idx=0;idx<RXBUFFER_SIZE;idx++)
|
||||
rx_ok_buff[idx]=rx_buff[idx]; // Duplicate the buffer
|
||||
RX_FLAG_on; //flag for main to process servo data
|
||||
RX_FLAG_on; // flag for main to process servo data
|
||||
}
|
||||
idx=0; // start again
|
||||
idx=0; // start again
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef XMEGA
|
||||
idx = USARTC0.DATA ; // Dummy read
|
||||
#else
|
||||
idx=UDR0; // Dummy read
|
||||
#endif
|
||||
idx=0; // Error encountered discard full frame...
|
||||
}
|
||||
}
|
||||
|
||||
//Serial timer
|
||||
#ifdef XMEGA
|
||||
ISR(TCC1_CCB_vect)
|
||||
#else
|
||||
ISR(TIMER1_COMPB_vect)
|
||||
#endif
|
||||
{ // Timer1 compare B interrupt
|
||||
idx=0;
|
||||
}
|
||||
|
||||
#if defined(TELEMETRY)
|
||||
//Serial TX
|
||||
|
||||
#ifdef XMEGA
|
||||
ISR(USARTC0_DRE_vect)
|
||||
#else
|
||||
ISR(USART_UDRE_vect)
|
||||
#endif
|
||||
{ // Transmit interrupt
|
||||
uint8_t t = tx_tail;
|
||||
if(tx_head!=t)
|
||||
if(tx_head!=tx_tail)
|
||||
{
|
||||
if(++t>=TXBUFFER_SIZE)//head
|
||||
t=0;
|
||||
UDR0=tx_buff[t];
|
||||
tx_tail=t;
|
||||
if(++tx_tail>=TXBUFFER_SIZE)//head
|
||||
tx_tail=0;
|
||||
#ifdef XMEGA
|
||||
USARTC0.DATA = tx_buff[tx_tail] ;
|
||||
#else
|
||||
UDR0=tx_buff[tx_tail];
|
||||
#endif
|
||||
}
|
||||
if (t == tx_head)
|
||||
if (tx_tail == tx_head)
|
||||
#ifdef XMEGA
|
||||
USARTC0.CTRLA &= ~0x03 ;
|
||||
#else
|
||||
UCSR0B &= ~(1<<UDRIE0); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
@@ -154,7 +115,7 @@ void NRF24L01_SetBitrate(uint8_t bitrate)
|
||||
// Note that bitrate 250kbps (and bit RF_DR_LOW) is valid only
|
||||
// for nRF24L01+. There is no way to programmatically tell it from
|
||||
// older version, nRF24L01, but the older is practically phased out
|
||||
// by Nordic, so we assume that we deal with with modern version.
|
||||
// by Nordic, so we assume that we deal with modern version.
|
||||
|
||||
// Bit 0 goes to RF_DR_HIGH, bit 1 - to RF_DR_LOW
|
||||
rf_setup = (rf_setup & 0xD7) | ((bitrate & 0x02) << 4) | ((bitrate & 0x01) << 3);
|
||||
@@ -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,12 +202,13 @@ void NRF24L01_Reset()
|
||||
NRF24L01_Strobe(0xff); // NOP
|
||||
NRF24L01_ReadReg(0x07);
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
_delay_us(100);
|
||||
delayMicroseconds(100);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_packet_ack()
|
||||
{
|
||||
switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))) {
|
||||
switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT)))
|
||||
{
|
||||
case BV(NRF24L01_07_TX_DS):
|
||||
return PKT_ACKED;
|
||||
case BV(NRF24L01_07_MAX_RT):
|
||||
@@ -257,7 +219,7 @@ uint8_t NRF24L01_packet_ack()
|
||||
|
||||
///////////////
|
||||
// XN297 emulation layer
|
||||
uint8_t xn297_scramble_enabled;
|
||||
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];
|
||||
@@ -270,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,
|
||||
@@ -284,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;
|
||||
@@ -295,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)
|
||||
@@ -344,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];
|
||||
@@ -409,3 +374,197 @@ void XN297_ReadPayload(uint8_t* msg, uint8_t len)
|
||||
}
|
||||
|
||||
// End of XN297 emulation
|
||||
|
||||
///////////////
|
||||
// LT8900 emulation layer
|
||||
uint8_t LT8900_buffer[64];
|
||||
uint8_t LT8900_buffer_start;
|
||||
uint16_t LT8900_buffer_overhead_bits;
|
||||
uint8_t LT8900_addr[8];
|
||||
uint8_t LT8900_addr_size;
|
||||
uint8_t LT8900_Preamble_Len;
|
||||
uint8_t LT8900_Tailer_Len;
|
||||
uint8_t LT8900_CRC_Initial_Data;
|
||||
uint8_t LT8900_Flags;
|
||||
#define LT8900_CRC_ON 6
|
||||
#define LT8900_SCRAMBLE_ON 5
|
||||
#define LT8900_PACKET_LENGTH_EN 4
|
||||
#define LT8900_DATA_PACKET_TYPE_1 3
|
||||
#define LT8900_DATA_PACKET_TYPE_0 2
|
||||
#define LT8900_FEC_TYPE_1 1
|
||||
#define LT8900_FEC_TYPE_0 0
|
||||
|
||||
void LT8900_Config(uint8_t preamble_len, uint8_t trailer_len, uint8_t flags, uint8_t crc_init)
|
||||
{
|
||||
//Preamble 1 to 8 bytes
|
||||
LT8900_Preamble_Len=preamble_len;
|
||||
//Trailer 4 to 18 bits
|
||||
LT8900_Tailer_Len=trailer_len;
|
||||
//Flags
|
||||
// CRC_ON: 1 on, 0 off
|
||||
// SCRAMBLE_ON: 1 on, 0 off
|
||||
// PACKET_LENGTH_EN: 1 1st byte of payload is payload size
|
||||
// DATA_PACKET_TYPE: 00 NRZ, 01 Manchester, 10 8bit/10bit line code, 11 interleave data type
|
||||
// FEC_TYPE: 00 No FEC, 01 FEC13, 10 FEC23, 11 reserved
|
||||
LT8900_Flags=flags;
|
||||
//CRC init constant
|
||||
LT8900_CRC_Initial_Data=crc_init;
|
||||
}
|
||||
|
||||
void LT8900_SetChannel(uint8_t channel)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, channel +2); //NRF24L01 is 2400+channel but LT8900 is 2402+channel
|
||||
}
|
||||
|
||||
void LT8900_SetTxRxMode(enum TXRX_State mode)
|
||||
{
|
||||
if(mode == TX_EN)
|
||||
{
|
||||
//Switch to TX
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
//Disable CRC
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP));
|
||||
}
|
||||
else
|
||||
if (mode == RX_EN)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
|
||||
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 32);
|
||||
//Switch to RX
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
NRF24L01_FlushRx();
|
||||
NRF24L01_SetTxRxMode(RX_EN);
|
||||
// Disable CRC
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP) | (1 << NRF24L01_00_PRIM_RX) );
|
||||
}
|
||||
else
|
||||
NRF24L01_SetTxRxMode(TXRX_OFF);
|
||||
}
|
||||
|
||||
void LT8900_BuildOverhead()
|
||||
{
|
||||
uint8_t pos;
|
||||
|
||||
//Build overhead
|
||||
//preamble
|
||||
memset(LT8900_buffer,LT8900_addr[0]&0x01?0xAA:0x55,LT8900_Preamble_Len-1);
|
||||
pos=LT8900_Preamble_Len-1;
|
||||
//address
|
||||
for(uint8_t i=0;i<LT8900_addr_size;i++)
|
||||
{
|
||||
LT8900_buffer[pos]=bit_reverse(LT8900_addr[i]);
|
||||
pos++;
|
||||
}
|
||||
//trailer
|
||||
memset(LT8900_buffer+pos,(LT8900_buffer[pos-1]&0x01)==0?0xAA:0x55,3);
|
||||
LT8900_buffer_overhead_bits=pos*8+LT8900_Tailer_Len;
|
||||
//nrf address length max is 5
|
||||
pos+=LT8900_Tailer_Len/8;
|
||||
LT8900_buffer_start=pos>5?5:pos;
|
||||
}
|
||||
|
||||
void LT8900_SetAddress(uint8_t *address,uint8_t addr_size)
|
||||
{
|
||||
uint8_t addr[5];
|
||||
|
||||
//Address size (SyncWord) 2 to 8 bytes, 16/32/48/64 bits
|
||||
LT8900_addr_size=addr_size;
|
||||
for (uint8_t i = 0; i < addr_size; i++)
|
||||
LT8900_addr[i] = address[addr_size-1-i];
|
||||
|
||||
//Build overhead
|
||||
LT8900_BuildOverhead();
|
||||
|
||||
//Set NRF RX&TX address based on overhead content
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, LT8900_buffer_start-2);
|
||||
for(uint8_t i=0;i<LT8900_buffer_start;i++) // reverse bytes order
|
||||
addr[i]=LT8900_buffer[LT8900_buffer_start-i-1];
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, addr,LT8900_buffer_start);
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, addr,LT8900_buffer_start);
|
||||
}
|
||||
|
||||
uint8_t LT8900_ReadPayload(uint8_t* msg, uint8_t len)
|
||||
{
|
||||
uint8_t i,pos=0,shift,end,buffer[32];
|
||||
unsigned int crc=LT8900_CRC_Initial_Data,a;
|
||||
pos=LT8900_buffer_overhead_bits/8-LT8900_buffer_start;
|
||||
end=pos+len+(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN)?1:0)+(LT8900_Flags&_BV(LT8900_CRC_ON)?2:0);
|
||||
//Read payload
|
||||
NRF24L01_ReadPayload(buffer,end+1);
|
||||
//Check address + trail
|
||||
for(i=0;i<pos;i++)
|
||||
if(LT8900_buffer[LT8900_buffer_start+i]!=buffer[i])
|
||||
return 0; // wrong address...
|
||||
//Shift buffer to remove trail bits
|
||||
shift=LT8900_buffer_overhead_bits&0x7;
|
||||
for(i=pos;i<end;i++)
|
||||
{
|
||||
a=(buffer[i]<<8)+buffer[i+1];
|
||||
a<<=shift;
|
||||
buffer[i]=(a>>8)&0xFF;
|
||||
}
|
||||
//Check len
|
||||
if(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN))
|
||||
{
|
||||
crc=crc16_update(crc,buffer[pos]);
|
||||
if(bit_reverse(len)!=buffer[pos++])
|
||||
return 0; // wrong len...
|
||||
}
|
||||
//Decode message
|
||||
for(i=0;i<len;i++)
|
||||
{
|
||||
crc=crc16_update(crc,buffer[pos]);
|
||||
msg[i]=bit_reverse(buffer[pos++]);
|
||||
}
|
||||
//Check CRC
|
||||
if(LT8900_Flags&_BV(LT8900_CRC_ON))
|
||||
{
|
||||
if(buffer[pos++]!=((crc>>8)&0xFF)) return 0; // wrong CRC...
|
||||
if(buffer[pos]!=(crc&0xFF)) return 0; // wrong CRC...
|
||||
}
|
||||
//Everything ok
|
||||
return 1;
|
||||
}
|
||||
|
||||
void LT8900_WritePayload(uint8_t* msg, uint8_t len)
|
||||
{
|
||||
unsigned int crc=LT8900_CRC_Initial_Data,a,mask;
|
||||
uint8_t i, pos=0,tmp, buffer[64], pos_final,shift;
|
||||
//Add packet len
|
||||
if(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN))
|
||||
{
|
||||
tmp=bit_reverse(len);
|
||||
buffer[pos++]=tmp;
|
||||
crc=crc16_update(crc,tmp);
|
||||
}
|
||||
//Add payload
|
||||
for(i=0;i<len;i++)
|
||||
{
|
||||
tmp=bit_reverse(msg[i]);
|
||||
buffer[pos++]=tmp;
|
||||
crc=crc16_update(crc,tmp);
|
||||
}
|
||||
//Add CRC
|
||||
if(LT8900_Flags&_BV(LT8900_CRC_ON))
|
||||
{
|
||||
buffer[pos++]=crc>>8;
|
||||
buffer[pos++]=crc;
|
||||
}
|
||||
//Shift everything to fit behind the trailer (4 to 18 bits)
|
||||
shift=LT8900_buffer_overhead_bits&0x7;
|
||||
pos_final=LT8900_buffer_overhead_bits/8;
|
||||
mask=~(0xFF<<(8-shift));
|
||||
LT8900_buffer[pos_final+pos]=0xFF;
|
||||
for(i=pos-1;i!=0xFF;i--)
|
||||
{
|
||||
a=buffer[i]<<(8-shift);
|
||||
LT8900_buffer[pos_final+i]=(LT8900_buffer[pos_final+i]&mask>>8)|a>>8;
|
||||
LT8900_buffer[pos_final+i+1]=(LT8900_buffer[pos_final+i+1]&mask)|a;
|
||||
}
|
||||
if(shift)
|
||||
pos++;
|
||||
//Send everything
|
||||
NRF24L01_WritePayload(LT8900_buffer+LT8900_buffer_start,pos_final+pos-LT8900_buffer_start);
|
||||
}
|
||||
// End of LT8900 emulation
|
||||
|
||||
269
Multiprotocol/SFHSS_cc2500.ino
Normal file
269
Multiprotocol/SFHSS_cc2500.ino
Normal file
@@ -0,0 +1,269 @@
|
||||
/*
|
||||
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 main deviation/sfhss_cc2500.c dated 2016-03-23
|
||||
|
||||
#if defined(SFHSS_CC2500_INO)
|
||||
|
||||
#include "iface_cc2500.h"
|
||||
|
||||
#define SFHSS_USE_TUNE_FREQ
|
||||
#define SFHSS_COARSE 0
|
||||
|
||||
#define SFHSS_PACKET_LEN 13
|
||||
#define SFHSS_TX_ID_LEN 2
|
||||
|
||||
uint8_t fhss_code; // 0-27
|
||||
|
||||
enum {
|
||||
SFHSS_START = 0x101,
|
||||
SFHSS_CAL = 0x102,
|
||||
SFHSS_TUNE = 0x103,
|
||||
SFHSS_DATA1 = 0x02,
|
||||
SFHSS_DATA2 = 0x0b
|
||||
};
|
||||
|
||||
#define SFHSS_FREQ0_VAL 0xC4
|
||||
|
||||
// Some important initialization parameters, all others are either default,
|
||||
// or not important in the context of transmitter
|
||||
// IOCFG2 2F - GDO2_INV=0 GDO2_CFG=2F - HW0
|
||||
// IOCFG1 2E - GDO1_INV=0 GDO1_CFG=2E - High Impedance
|
||||
// IOCFG0 2F - GDO0 same as GDO2, TEMP_SENSOR_ENABLE=off
|
||||
// FIFOTHR 07 - 33 decimal TX threshold
|
||||
// SYNC1 D3
|
||||
// SYNC0 91
|
||||
// PKTLEN 0D - Packet length, 0D bytes
|
||||
// PKTCTRL1 04 - APPEND_STATUS on, all other are receive parameters - irrelevant
|
||||
// PKTCTRL0 0C - No whitening, use FIFO, CC2400 compatibility on, use CRC, fixed packet length
|
||||
// ADDR 29
|
||||
// CHANNR 10
|
||||
// FSCTRL1 06 - IF 152343.75Hz, see page 65
|
||||
// FSCTRL0 00 - zero freq offset
|
||||
// FREQ2 5C - synthesizer frequency 2399999633Hz for 26MHz crystal, ibid
|
||||
// FREQ1 4E
|
||||
// FREQ0 C4
|
||||
// MDMCFG4 7C - CHANBW_E - 01, CHANBW_M - 03, DRATE_E - 0C. Filter bandwidth = 232142Hz
|
||||
// MDMCFG3 43 - DRATE_M - 43. Data rate = 128143bps
|
||||
// MDMCFG2 83 - disable DC blocking, 2-FSK, no Manchester code, 15/16 sync bits detected (irrelevant for TX)
|
||||
// MDMCFG1 23 - no FEC, 4 preamble bytes, CHANSPC_E - 03
|
||||
// MDMCFG0 3B - CHANSPC_M - 3B. Channel spacing = 249938Hz (each 6th channel used, resulting in spacing of 1499628Hz)
|
||||
// DEVIATN 44 - DEVIATION_E - 04, DEVIATION_M - 04. Deviation = 38085.9Hz
|
||||
// MCSM2 07 - receive parameters, default, irrelevant
|
||||
// MCSM1 0C - no CCA (transmit always), when packet received stay in RX, when sent go to IDLE
|
||||
// MCSM0 08 - no autocalibration, PO_TIMEOUT - 64, no pin radio control, no forcing XTAL to stay in SLEEP
|
||||
// FOCCFG 1D - not interesting, Frequency Offset Compensation
|
||||
// FREND0 10 - PA_POWER = 0
|
||||
const PROGMEM uint8_t SFHSS_init_values[] = {
|
||||
/* 00 */ 0x2F, 0x2E, 0x2F, 0x07, 0xD3, 0x91, 0x0D, 0x04,
|
||||
/* 08 */ 0x0C, 0x29, 0x10, 0x06, 0x00, 0x5C, 0x4E, SFHSS_FREQ0_VAL + SFHSS_COARSE,
|
||||
/* 10 */ 0x7C, 0x43, 0x83, 0x23, 0x3B, 0x44, 0x07, 0x0C,
|
||||
/* 18 */ 0x08, 0x1D, 0x1C, 0x43, 0x40, 0x91, 0x57, 0x6B,
|
||||
/* 20 */ 0xF8, 0xB6, 0x10, 0xEA, 0x0A, 0x11, 0x11
|
||||
};
|
||||
|
||||
static void __attribute__((unused)) SFHSS_tune_chan()
|
||||
{
|
||||
CC2500_Strobe(CC2500_SIDLE);
|
||||
CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16);
|
||||
CC2500_Strobe(CC2500_SCAL);
|
||||
}
|
||||
|
||||
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);
|
||||
delayMicroseconds(6);
|
||||
}
|
||||
|
||||
#ifdef SFHSS_USE_TUNE_FREQ
|
||||
static void __attribute__((unused)) SFHSS_tune_freq() {
|
||||
// May be we'll need this tuning routine - some receivers are more sensitive to
|
||||
// frequency impreciseness, and though CC2500 has a procedure to handle it it
|
||||
// may not be applied in receivers, so we need to compensate for it on TX
|
||||
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
|
||||
CC2500_WriteReg(CC2500_0F_FREQ0, SFHSS_FREQ0_VAL + SFHSS_COARSE);
|
||||
}
|
||||
#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;
|
||||
if (rf_ch_num > 29)
|
||||
{
|
||||
if (rf_ch_num < 31)
|
||||
rf_ch_num += fhss_code + 2;
|
||||
rf_ch_num -= 31;
|
||||
}
|
||||
}
|
||||
|
||||
// Channel values are 10-bit values between 86 and 906, 496 is the middle.
|
||||
static uint16_t __attribute__((unused)) SFHSS_convert_channel(uint8_t num)
|
||||
{
|
||||
return (uint16_t) (map(limit_channel_100(num),PPM_MIN_100,PPM_MAX_100,86,906));
|
||||
}
|
||||
|
||||
|
||||
static void __attribute__((unused)) SFHSS_build_data_packet()
|
||||
{
|
||||
#define spacer1 0x02 //0b10
|
||||
#define spacer2 (spacer1 << 4)
|
||||
uint8_t ch_offset = state == SFHSS_DATA1 ? 0 : 4;
|
||||
uint16_t ch1 = SFHSS_convert_channel(CH_AETR[ch_offset+0]);
|
||||
uint16_t ch2 = SFHSS_convert_channel(CH_AETR[ch_offset+1]);
|
||||
uint16_t ch3 = SFHSS_convert_channel(CH_AETR[ch_offset+2]);
|
||||
uint16_t ch4 = SFHSS_convert_channel(CH_AETR[ch_offset+3]);
|
||||
|
||||
packet[0] = 0x81; // can be 80, 81, 81 for Orange, only 81 for XK
|
||||
packet[1] = rx_tx_addr[0];
|
||||
packet[2] = rx_tx_addr[1];
|
||||
packet[3] = 0;
|
||||
packet[4] = 0;
|
||||
packet[5] = (rf_ch_num << 3) | spacer1 | ((ch1 >> 9) & 0x01);
|
||||
packet[6] = (ch1 >> 1);
|
||||
packet[7] = (ch1 << 7) | spacer2 | ((ch2 >> 5) & 0x1F /*0b11111*/);
|
||||
packet[8] = (ch2 << 3) | spacer1 | ((ch3 >> 9) & 0x01);
|
||||
packet[9] = (ch3 >> 1);
|
||||
packet[10] = (ch3 << 7) | spacer2 | ((ch4 >> 5) & 0x1F /*0b11111*/);
|
||||
packet[11] = (ch4 << 3) | ((fhss_code >> 2) & 0x07 /*0b111 */);
|
||||
packet[12] = (fhss_code << 6) | state;
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) SFHSS_send_packet()
|
||||
{
|
||||
SFHSS_tune_chan_fast();
|
||||
CC2500_WriteData(packet, SFHSS_PACKET_LEN);
|
||||
}
|
||||
|
||||
uint16_t ReadSFHSS()
|
||||
{
|
||||
switch(state)
|
||||
{
|
||||
case SFHSS_START:
|
||||
rf_ch_num = 0;
|
||||
SFHSS_tune_chan();
|
||||
state = SFHSS_CAL;
|
||||
return 2000;
|
||||
case SFHSS_CAL:
|
||||
CC2500_ReadRegisterMulti(CC2500_23_FSCAL3, calData[rf_ch_num], 3);
|
||||
if (++rf_ch_num < 30)
|
||||
SFHSS_tune_chan();
|
||||
else
|
||||
{
|
||||
rf_ch_num = 0;
|
||||
state = SFHSS_DATA1;
|
||||
}
|
||||
return 2000;
|
||||
|
||||
/* Work cycle, 6.8ms, second packet 1.65ms after first */
|
||||
case SFHSS_DATA1:
|
||||
SFHSS_build_data_packet();
|
||||
SFHSS_send_packet();
|
||||
state = SFHSS_DATA2;
|
||||
return 1650;
|
||||
case SFHSS_DATA2:
|
||||
SFHSS_build_data_packet();
|
||||
SFHSS_send_packet();
|
||||
SFHSS_calc_next_chan();
|
||||
state = SFHSS_TUNE;
|
||||
return 2000;
|
||||
case SFHSS_TUNE:
|
||||
#ifdef SFHSS_USE_TUNE_FREQ
|
||||
SFHSS_tune_freq();
|
||||
#endif
|
||||
CC2500_SetPower();
|
||||
state = SFHSS_DATA1;
|
||||
return 3150;
|
||||
/*
|
||||
case SFHSS_DATA1:
|
||||
SFHSS_build_data_packet();
|
||||
SFHSS_send_packet();
|
||||
state = SFHSS_DATA2;
|
||||
return 1650;
|
||||
case SFHSS_DATA2:
|
||||
SFHSS_build_data_packet();
|
||||
SFHSS_send_packet();
|
||||
state = SFHSS_CAL2;
|
||||
return 500;
|
||||
case SFHSS_CAL2:
|
||||
SFHSS_tune_freq();
|
||||
// CC2500_SetPower();
|
||||
SFHSS_calc_next_chan();
|
||||
SFHSS_tune_chan();
|
||||
state = SFHSS_DATA1;
|
||||
return 4650;
|
||||
*/
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Generate internal id
|
||||
static void __attribute__((unused)) SFHSS_get_tx_id()
|
||||
{
|
||||
uint32_t fixed_id;
|
||||
// Some receivers (Orange) behaves better if they tuned to id that has
|
||||
// no more than 6 consecutive zeros and ones
|
||||
uint8_t run_count = 0;
|
||||
// add guard for bit count
|
||||
fixed_id = 1 ^ (MProtocol_id & 1);
|
||||
for (uint8_t i = 0; i < 16; ++i)
|
||||
{
|
||||
fixed_id = (fixed_id << 1) | (MProtocol_id & 1);
|
||||
MProtocol_id >>= 1;
|
||||
// If two LS bits are the same
|
||||
if ((fixed_id & 3) == 0 || (fixed_id & 3) == 3)
|
||||
{
|
||||
if (++run_count > 6)
|
||||
{
|
||||
fixed_id ^= 1;
|
||||
run_count = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
run_count = 0;
|
||||
}
|
||||
// fixed_id = 0xBC11;
|
||||
rx_tx_addr[0] = fixed_id >> 8;
|
||||
rx_tx_addr[1] = fixed_id;
|
||||
}
|
||||
|
||||
uint16_t initSFHSS()
|
||||
{
|
||||
BIND_DONE; // No bind protocol
|
||||
SFHSS_get_tx_id();
|
||||
|
||||
fhss_code=rx_tx_addr[2]%28; // Initialize it to random 0-27 inclusive
|
||||
|
||||
SFHSS_rf_init();
|
||||
state = SFHSS_START;
|
||||
|
||||
return 10000;
|
||||
}
|
||||
|
||||
#endif
|
||||
108
Multiprotocol/SHENQI_nrf24l01.ino
Normal file
108
Multiprotocol/SHENQI_nrf24l01.ino
Normal file
@@ -0,0 +1,108 @@
|
||||
#if defined(SHENQI_NRF24L01_INO)
|
||||
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
const uint8_t PROGMEM SHENQI_Freq[] = {
|
||||
50,50,20,60,30,40,
|
||||
10,30,40,20,60,10,
|
||||
50,20,50,40,10,60,
|
||||
30,30,60,10,40,50,
|
||||
20,10,60,20,50,30,
|
||||
40,40,30,50,20,60,
|
||||
10,10,20,30,40,50,
|
||||
60,60,50,40,30,20,
|
||||
10,60,10,50,30,40,
|
||||
20,10,40,30,60,20 };
|
||||
|
||||
void SHENQI_init()
|
||||
{
|
||||
NRF24L01_Initialize();
|
||||
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_SetBitrate(NRF24L01_BR_1M); // 1Mbps
|
||||
NRF24L01_SetPower();
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes rx/tx address
|
||||
|
||||
LT8900_Config(4, 8, _BV(LT8900_CRC_ON)|_BV(LT8900_PACKET_LENGTH_EN), 0xAA);
|
||||
LT8900_SetChannel(2);
|
||||
LT8900_SetAddress((uint8_t *)"\x9A\x9A\x9A\x9A",4);
|
||||
LT8900_SetTxRxMode(RX_EN);
|
||||
}
|
||||
|
||||
void SHENQI_send_packet()
|
||||
{
|
||||
packet[0]=0x00;
|
||||
if(packet_count==0)
|
||||
{
|
||||
uint8_t bind_addr[4];
|
||||
bind_addr[0]=rx_tx_addr[0];
|
||||
bind_addr[1]=rx_tx_addr[1];
|
||||
bind_addr[2]=0x9A;
|
||||
bind_addr[3]=0x9A;
|
||||
LT8900_SetAddress(bind_addr,4);
|
||||
LT8900_SetChannel(2);
|
||||
packet[1]=rx_tx_addr[2];
|
||||
packet[2]=rx_tx_addr[3];
|
||||
packet_period=2508;
|
||||
}
|
||||
else
|
||||
{
|
||||
LT8900_SetAddress(rx_tx_addr,4);
|
||||
packet[1]=255-convert_channel_8b(RUDDER);
|
||||
packet[2]=255-convert_channel_8b_scale(THROTTLE,0x60,0xA0);
|
||||
uint8_t freq=pgm_read_byte_near(&SHENQI_Freq[hopping_frequency_no])+(rx_tx_addr[2]&0x0F);
|
||||
LT8900_SetChannel(freq);
|
||||
hopping_frequency_no++;
|
||||
if(hopping_frequency_no==60)
|
||||
hopping_frequency_no=0;
|
||||
packet_period=1750;
|
||||
}
|
||||
// Send packet + 1 retransmit - not sure why but needed (not present on original TX...)
|
||||
LT8900_WritePayload(packet,3);
|
||||
while(NRF24L01_packet_ack()!=PKT_ACKED);
|
||||
LT8900_WritePayload(packet,3);
|
||||
|
||||
packet_count++;
|
||||
if(packet_count==7)
|
||||
{
|
||||
packet_count=0;
|
||||
packet_period=3000;
|
||||
}
|
||||
// Set power
|
||||
NRF24L01_SetPower();
|
||||
}
|
||||
|
||||
uint16_t SHENQI_callback()
|
||||
{
|
||||
if(IS_BIND_DONE_on)
|
||||
SHENQI_send_packet();
|
||||
else
|
||||
{
|
||||
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
|
||||
{
|
||||
if(LT8900_ReadPayload(packet, 3))
|
||||
{
|
||||
BIND_DONE;
|
||||
rx_tx_addr[0]=packet[1];
|
||||
rx_tx_addr[1]=packet[2];
|
||||
LT8900_SetTxRxMode(TX_EN);
|
||||
packet_period=14000;
|
||||
}
|
||||
NRF24L01_FlushRx();
|
||||
}
|
||||
}
|
||||
return packet_period;
|
||||
}
|
||||
|
||||
uint16_t initSHENQI()
|
||||
{
|
||||
BIND_IN_PROGRESS; // autobind protocol
|
||||
SHENQI_init();
|
||||
hopping_frequency_no = 0;
|
||||
packet_count=0;
|
||||
packet_period=100;
|
||||
return 1000;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -111,9 +111,8 @@ static void __attribute__((unused)) 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
|
||||
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER};
|
||||
for (uint8_t i = 0; i < 4; ++i) {
|
||||
uint16_t v = convert_channel_10b(ch[i]);
|
||||
uint16_t v = convert_channel_10b(CH_AETR[i]);
|
||||
packet[i] = v;
|
||||
e = (e >> 2) | (uint8_t) ((v >> 2) & 0xC0);
|
||||
}
|
||||
|
||||
@@ -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();
|
||||
|
||||
@@ -4,173 +4,207 @@
|
||||
//*************************************
|
||||
|
||||
#if defined TELEMETRY
|
||||
#if defined FRSKYX_CC2500_INO
|
||||
#define SPORT_TELEMETRY
|
||||
#endif
|
||||
#if defined FRSKY_CC2500_INO
|
||||
#define HUB_TELEMETRY
|
||||
#endif
|
||||
#if defined SPORT_TELEMETRY
|
||||
#define SPORT_TELEMETRY
|
||||
#define SPORT_TIME 12000
|
||||
uint32_t last=0;
|
||||
uint8_t sport_counter=0;
|
||||
uint8_t RxBt=0;
|
||||
uint8_t rssi;
|
||||
uint8_t ADC2;
|
||||
#endif
|
||||
#if defined HUB_TELEMETRY
|
||||
#define MAX_PKTX 10
|
||||
uint8_t pktx[MAX_PKTX];
|
||||
uint8_t index;
|
||||
uint8_t prev_index;
|
||||
uint8_t pass = 0;
|
||||
#endif
|
||||
|
||||
#if defined SPORT_TELEMETRY
|
||||
#define SPORT_TIME 12000
|
||||
#define FRSKY_SPORT_PACKET_SIZE 8
|
||||
uint32_t last = 0;
|
||||
uint8_t sport_counter=0;
|
||||
uint8_t RxBt = 0;
|
||||
uint8_t rssi;
|
||||
uint8_t sport = 0;
|
||||
#endif
|
||||
#if defined HUB_TELEMETRY
|
||||
#define USER_MAX_BYTES 6
|
||||
uint8_t frame[18];
|
||||
|
||||
void frskySendStuffed()
|
||||
uint8_t prev_index;
|
||||
#endif
|
||||
|
||||
#define START_STOP 0x7e
|
||||
#define BYTESTUFF 0x7d
|
||||
#define STUFF_MASK 0x20
|
||||
#define MAX_PKTX 10
|
||||
uint8_t pktx[MAX_PKTX];
|
||||
uint8_t index;
|
||||
uint8_t pass = 0;
|
||||
uint8_t frame[18];
|
||||
|
||||
#if defined DSM_TELEMETRY
|
||||
void DSM2_frame()
|
||||
{
|
||||
Serial_write(0xAA); // Start
|
||||
for (uint8_t i = 0; i < 17; i++) // RSSI value followed by 16 bytes of telemetry data
|
||||
Serial_write(pkt[i]);
|
||||
}
|
||||
#endif
|
||||
|
||||
void frskySendStuffed()
|
||||
{
|
||||
Serial_write(START_STOP);
|
||||
for (uint8_t i = 0; i < 9; i++)
|
||||
{
|
||||
Serial_write(0x7E);
|
||||
for (uint8_t i = 0; i < 9; i++)
|
||||
if ((frame[i] == START_STOP) || (frame[i] == BYTESTUFF))
|
||||
{
|
||||
if ((frame[i] == 0x7e) || (frame[i] == 0x7d))
|
||||
{
|
||||
Serial_write(0x7D);
|
||||
frame[i] ^= 0x20;
|
||||
}
|
||||
Serial_write(frame[i]);
|
||||
Serial_write(BYTESTUFF);
|
||||
frame[i] ^= STUFF_MASK;
|
||||
}
|
||||
Serial_write(0x7E);
|
||||
Serial_write(frame[i]);
|
||||
}
|
||||
Serial_write(START_STOP);
|
||||
}
|
||||
|
||||
void compute_RSSIdbm()
|
||||
{
|
||||
|
||||
void compute_RSSIdbm(){
|
||||
|
||||
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5);
|
||||
if(pktt[len-2] >=128)
|
||||
RSSI_dBm -= 82;
|
||||
else
|
||||
RSSI_dBm += 65;
|
||||
}
|
||||
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>4);
|
||||
if(pktt[len-2] >=128)
|
||||
RSSI_dBm -= 164;
|
||||
else
|
||||
RSSI_dBm += 130;
|
||||
}
|
||||
|
||||
void frsky_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
|
||||
for(uint8_t i=3;i<6;i++)
|
||||
pktt[i]=0;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
for (uint8_t i=3;i<len;i++)
|
||||
pktt[i]=pkt[i];
|
||||
telemetry_link=1;
|
||||
if(pktt[6]>0)
|
||||
telemetry_counter=(telemetry_counter+1)%32;
|
||||
}
|
||||
}
|
||||
|
||||
void frsky_link_frame()
|
||||
{
|
||||
frame[0] = 0xFE;
|
||||
if ((cur_protocol[0]&0x1F)==MODE_FRSKY)
|
||||
{
|
||||
compute_RSSIdbm();
|
||||
frame[1] = pktt[3];
|
||||
frame[2] = pktt[4];
|
||||
frame[3] = (uint8_t)RSSI_dBm;
|
||||
frame[4] = pktt[5]*2;
|
||||
}
|
||||
else
|
||||
if ((cur_protocol[0]&0x1F)==MODE_HUBSAN)
|
||||
{
|
||||
frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V
|
||||
frame[2] = frame[1];
|
||||
frame[3] = 0x00;
|
||||
frame[4] = (uint8_t)RSSI_dBm;
|
||||
void frsky_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))
|
||||
{
|
||||
for (uint8_t i=3;i<len;i++)
|
||||
pktt[i]=pkt[i];
|
||||
telemetry_link=1;
|
||||
if(pktt[6])
|
||||
telemetry_counter=(telemetry_counter+1)%32;
|
||||
//
|
||||
#if defined FRSKYX_CC2500_INO
|
||||
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
|
||||
{
|
||||
if ((pktt[5] >> 4 & 0x0f) == 0x08)
|
||||
{
|
||||
seq_last_sent = 8;
|
||||
seq_last_rcvd = 0;
|
||||
pass=0;
|
||||
}
|
||||
else
|
||||
{
|
||||
if ((pktt[5] >> 4 & 0x03) == (seq_last_rcvd + 1) % 4)
|
||||
seq_last_rcvd = (seq_last_rcvd + 1) % 4;
|
||||
else
|
||||
pass=0;//reset if sequence wrong
|
||||
}
|
||||
frame[5] = frame[6] = frame[7] = frame[8] = 0;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void frsky_link_frame()
|
||||
{
|
||||
frame[0] = 0xFE;
|
||||
if ((cur_protocol[0]&0x1F)==MODE_FRSKY)
|
||||
{
|
||||
compute_RSSIdbm();
|
||||
frame[1] = pktt[3];
|
||||
frame[2] = pktt[4];
|
||||
frame[3] = pktt[5];
|
||||
frame[4] = (uint8_t)RSSI_dBm;
|
||||
}
|
||||
else
|
||||
if ((cur_protocol[0]&0x1F)==MODE_HUBSAN)
|
||||
{
|
||||
frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V
|
||||
frame[2] = frame[1];
|
||||
frame[3] = 0x00;
|
||||
frame[4] = (uint8_t)RSSI_dBm;
|
||||
}
|
||||
frame[5] = frame[6] = frame[7] = frame[8] = 0;
|
||||
frskySendStuffed();
|
||||
}
|
||||
|
||||
#if defined HUB_TELEMETRY
|
||||
void frsky_user_frame()
|
||||
{
|
||||
uint8_t indexx = 0, c=0, j=8, n=0, i;
|
||||
|
||||
if(pktt[6]>0 && pktt[6]<=10)
|
||||
{//only valid hub frames
|
||||
frame[0] = 0xFD;
|
||||
frame[2] = pktt[7];
|
||||
switch(pass)
|
||||
{
|
||||
case 0:
|
||||
indexx=pktt[6];
|
||||
for(i=0;i<indexx;i++)
|
||||
{
|
||||
if(pktt[j]==0x5E)
|
||||
{
|
||||
if(c++)
|
||||
{
|
||||
c=0;
|
||||
n++;
|
||||
j++;
|
||||
}
|
||||
}
|
||||
pktx[i]=pktt[j++];
|
||||
}
|
||||
indexx = indexx-n;
|
||||
pass=1;
|
||||
|
||||
case 1:
|
||||
index=indexx;
|
||||
prev_index = indexx;
|
||||
if(index<USER_MAX_BYTES)
|
||||
{
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[i];
|
||||
pktt[6]=0;
|
||||
pass=0;
|
||||
}
|
||||
else
|
||||
{
|
||||
index = USER_MAX_BYTES;
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[i];
|
||||
pass=2;
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
index = prev_index - index;
|
||||
prev_index=0;
|
||||
if(index<(MAX_PKTX-USER_MAX_BYTES)) //10-6=4
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[USER_MAX_BYTES+i];
|
||||
pass=0;
|
||||
pktt[6]=0;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(!index)
|
||||
return;
|
||||
frame[1] = index;
|
||||
frskySendStuffed();
|
||||
}
|
||||
|
||||
#if defined HUB_TELEMETRY
|
||||
void frsky_user_frame()
|
||||
{
|
||||
uint8_t indexx = 0, c=0, j=8, n=0, i;
|
||||
|
||||
if(pktt[6]>0 && pktt[6]<=MAX_PKTX)
|
||||
{//only valid hub frames
|
||||
frame[0] = 0xFD;
|
||||
frame[1] = 0;
|
||||
frame[2] = pktt[7];
|
||||
|
||||
switch(pass)
|
||||
{
|
||||
case 0:
|
||||
indexx=pktt[6];
|
||||
for(i=0;i<indexx;i++)
|
||||
{
|
||||
if(pktt[j]==0x5E)
|
||||
{
|
||||
if(c++)
|
||||
{
|
||||
c=0;
|
||||
n++;
|
||||
j++;
|
||||
}
|
||||
}
|
||||
pktx[i]=pktt[j++];
|
||||
}
|
||||
indexx = indexx-n;
|
||||
pass=1;
|
||||
|
||||
case 1:
|
||||
index=indexx;
|
||||
prev_index = indexx;
|
||||
if(index<USER_MAX_BYTES)
|
||||
{
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[i];
|
||||
pktt[6]=0;
|
||||
pass=0;
|
||||
}
|
||||
else
|
||||
{
|
||||
index = USER_MAX_BYTES;
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[i];
|
||||
pass=2;
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
index = prev_index - index;
|
||||
prev_index=0;
|
||||
if(index<MAX_PKTX-USER_MAX_BYTES) //10-6=4
|
||||
for(i=0;i<index;i++)
|
||||
frame[i+3]=pktx[USER_MAX_BYTES+i];
|
||||
pass=0;
|
||||
pktt[6]=0;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(!index)
|
||||
return;
|
||||
frame[1] = index;
|
||||
frskySendStuffed();
|
||||
}
|
||||
else
|
||||
pass=0;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined SPORT_TELEMETRY
|
||||
|
||||
/* SPORT details serial
|
||||
else
|
||||
pass=0;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
HuB RX packets.
|
||||
pkt[6]|(counter++)|00 01 02 03 04 05 06 07 08 09
|
||||
%32
|
||||
01 08 5E 28 12 00 5E 5E 3A 06 00 5E
|
||||
0A 09 28 12 00 5E 5E 3A 06 00 5E 5E
|
||||
09 0A 3B 09 00 5E 5E 06 36 7D 5E 5E
|
||||
03 0B 5E 28 11 00 5E 5E 06 06 6C 5E
|
||||
0A 0C 00 5E 5E 3A 06 00 5E 5E 3B 09
|
||||
07 0D 00 5E 5E 06 06 6C 5E 16 72 5E
|
||||
05 0E 5E 28 11 00 5E 5E 3A 06 00 5E
|
||||
0A 0F 5E 3A 06 00 5E 5E 3B 09 00 5E
|
||||
05 10 5E 06 16 72 5E 5E 3A 06 00 5E
|
||||
*/
|
||||
|
||||
#if defined SPORT_TELEMETRY
|
||||
/* SPORT details serial
|
||||
100K 8E2 normal-multiprotocol
|
||||
-every 12ms-
|
||||
1 2 3 4 5 6 7 8 9 CRC DESCR
|
||||
-every 12ms-or multiple of 12; %36
|
||||
1 2 3 4 5 6 7 8 9 CRC DESCR
|
||||
7E 98 10 05 F1 20 23 0F 00 A6 SWR_ID
|
||||
7E 98 10 01 F1 33 00 00 00 C9 RSSI_ID
|
||||
7E 98 10 04 F1 58 00 00 00 A1 BATT_ID
|
||||
@@ -182,14 +216,15 @@
|
||||
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
|
||||
|
||||
|
||||
Telemetry frames(RF) SPORT info 15 bytes
|
||||
SPORT frame 6+3 bytes
|
||||
Telemetry frames(RF) SPORT info
|
||||
15 bytes payload
|
||||
SPORT frame valid 6+3 bytes
|
||||
[00] PKLEN 0E 0E 0E 0E
|
||||
[01] TXID1 DD DD DD DD
|
||||
[02] TXID2 6D 6D 6D 6D
|
||||
[03] CONST 02 02 02 02
|
||||
[04] RS/RB 2C D0 2C CE //D0;CE=2*RSSI;....2C = RX battery voltage(5V from Bec)
|
||||
[05] ????? 03 10 21 32 //TX/RX telemetry hand-shake bytes
|
||||
[05] HD-SK 03 10 21 32 //TX/RX telemetry hand-shake bytes
|
||||
[06] NO.BT 00 00 06 03 //No.of valid SPORT frame bytes in the frame
|
||||
[07] STRM1 00 00 7E 00
|
||||
[08] STRM2 00 00 1A 00
|
||||
@@ -197,141 +232,179 @@
|
||||
[10] STRM4 03 03 03 03
|
||||
[11] STRM5 F1 F1 F1 F1
|
||||
[12] STRM6 D1 D1 D0 D0
|
||||
[13] CHKSUM1
|
||||
[14] CHKSUM2
|
||||
*/
|
||||
|
||||
|
||||
void sportSend(uint8_t *p)
|
||||
{
|
||||
uint16_t crc_s = 0;
|
||||
Serial_write(0x7e);//+9
|
||||
for (uint8_t i = 0; i < 9; i++)
|
||||
{
|
||||
if (i == 8)
|
||||
p[i] = 0xff - crc_s;
|
||||
if ((p[i] == 0x7e) || (p[i] == 0x7d))
|
||||
{
|
||||
Serial_write(0x7d);
|
||||
Serial_write(0x20 ^ p[i]);
|
||||
}
|
||||
else
|
||||
Serial_write(p[i]);
|
||||
if (i>0)
|
||||
{
|
||||
crc_s += p[i]; //0-1FF
|
||||
crc_s += crc_s >> 8; //0-100
|
||||
crc_s &= 0x00ff;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void sportIdle()
|
||||
{
|
||||
Serial_write(0x7e);
|
||||
}
|
||||
[13] CHKSUM1 --|2 CRC bytes sent by RX (calculated on RX side crc16/table)
|
||||
[14] CHKSUM2 --|
|
||||
+2 appended bytes automatically RSSI and LQI/CRC bytes(len=0x0E+3);
|
||||
|
||||
0x06 0x06 0x06 0x06 0x06
|
||||
|
||||
void sportSendFrame()
|
||||
{
|
||||
//at the moment only SWR RSSI,RxBt and A2.
|
||||
sport_counter = (sport_counter + 1) %9;
|
||||
|
||||
for (uint8_t i=5;i<8;i++)
|
||||
frame[i]=0;
|
||||
|
||||
switch (sport_counter)
|
||||
{
|
||||
case 0: // SWR
|
||||
frame[0] = 0x98;
|
||||
frame[1] = 0x10;
|
||||
frame[2] = 0x05;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = 0x20;//dummy values if swr 20230f00
|
||||
frame[5] = 0x23;
|
||||
frame[6] = 0x0F;
|
||||
frame[7] = 0x00;
|
||||
break;
|
||||
case 1: // RSSI
|
||||
frame[0] = 0x98;
|
||||
frame[1] = 0x10;
|
||||
frame[2] = 0x01;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = rssi;
|
||||
break;
|
||||
case 2: //BATT
|
||||
frame[0] = 0x98;
|
||||
frame[1] = 0x10;
|
||||
frame[2] = 0x04;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = RxBt;//a1;
|
||||
break;
|
||||
case 3: //ADC2(A2)
|
||||
frame[0] = 0x1A;
|
||||
frame[1] = 0x10;
|
||||
frame[2] = 0x03;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = ADC2;//a2;;
|
||||
break;
|
||||
default:
|
||||
sportIdle();
|
||||
return;
|
||||
}
|
||||
sportSend(frame);
|
||||
}
|
||||
0x7E 0x00 0x03 0x7E 0x00
|
||||
0x1A 0x00 0xF1 0x1A 0x00
|
||||
0x10 0x00 0xD7 0x10 0x00
|
||||
0x03 0x7E 0x00 0x03 0x7E
|
||||
0xF1 0x1A 0x00 0xF1 0x1A
|
||||
0xD7 0x10 0x00 0xD7 0x10
|
||||
|
||||
0xE1 0x1C 0xD0 0xEE 0x33
|
||||
0x34 0x0A 0xC3 0x56 0xF3
|
||||
|
||||
*/
|
||||
void sportSend(uint8_t *p)
|
||||
{
|
||||
uint16_t crc_s = 0;
|
||||
Serial_write(START_STOP);//+9
|
||||
for (uint8_t i = 0; i < 9; i++)
|
||||
{
|
||||
if (i == 8)
|
||||
p[i] = 0xff - crc_s;
|
||||
|
||||
void process_sport_data()//only for ADC2
|
||||
{
|
||||
uint8_t j=7;
|
||||
if(pktt[6]>0 && pktt[6]<=USER_MAX_BYTES)
|
||||
{
|
||||
for(uint8_t i=0;i<6;i++)
|
||||
if(pktt[j++]==0x03)
|
||||
if(pktt[j]==0xF1)
|
||||
{
|
||||
ADC2=pktt[j+1];
|
||||
break;
|
||||
}
|
||||
pktt[6]=0;//new frame
|
||||
}
|
||||
if ((p[i] == START_STOP) || (p[i] == BYTESTUFF))
|
||||
{
|
||||
Serial_write(BYTESTUFF);//stuff again
|
||||
Serial_write(STUFF_MASK ^ p[i]);
|
||||
}
|
||||
else
|
||||
Serial_write(p[i]);
|
||||
|
||||
if (i>0)
|
||||
{
|
||||
crc_s += p[i]; //0-1FF
|
||||
crc_s += crc_s >> 8; //0-100
|
||||
crc_s &= 0x00ff;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
void frskyUpdate()
|
||||
{
|
||||
if(telemetry_link && (cur_protocol[0]&0x1F) != MODE_FRSKYX )
|
||||
{
|
||||
frsky_link_frame();
|
||||
telemetry_link=0;
|
||||
return;
|
||||
}
|
||||
#if defined HUB_TELEMETRY
|
||||
if(!telemetry_link && (cur_protocol[0]&0x1F) != MODE_HUBSAN && (cur_protocol[0]&0x1F) != MODE_FRSKYX)
|
||||
{
|
||||
frsky_user_frame();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if defined SPORT_TELEMETRY
|
||||
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
|
||||
{
|
||||
if(telemetry_link)
|
||||
{
|
||||
process_sport_data();
|
||||
if(pktt[4]>0x36)
|
||||
rssi=pktt[4]/2;
|
||||
else
|
||||
RxBt=pktt[4];
|
||||
telemetry_link=0;
|
||||
}
|
||||
uint32_t now = micros();
|
||||
if ((now - last) > SPORT_TIME)
|
||||
{
|
||||
sportSendFrame();
|
||||
last = now;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void sportIdle()
|
||||
{
|
||||
Serial_write(START_STOP);
|
||||
}
|
||||
|
||||
void sportSendFrame()
|
||||
{
|
||||
uint8_t i;
|
||||
sport_counter = (sport_counter + 1) %36;
|
||||
|
||||
if(sport_counter<3)
|
||||
{
|
||||
frame[0] = 0x98;
|
||||
frame[1] = 0x10;
|
||||
for (i=5;i<8;i++)
|
||||
frame[i]=0;
|
||||
}
|
||||
switch (sport_counter)
|
||||
{
|
||||
case 0:
|
||||
frame[2] = 0x05;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = 0x20;//dummy values if swr 20230f00
|
||||
frame[5] = 0x23;
|
||||
frame[6] = 0x0F;
|
||||
break;
|
||||
case 1: // RSSI
|
||||
frame[2] = 0x01;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = rssi;
|
||||
break;
|
||||
case 2: //BATT
|
||||
frame[2] = 0x04;
|
||||
frame[3] = 0xf1;
|
||||
frame[4] = RxBt;//a1;
|
||||
break;
|
||||
default:
|
||||
if(sport)
|
||||
{
|
||||
for (i=0;i<FRSKY_SPORT_PACKET_SIZE;i++)
|
||||
frame[i]=pktx[i];
|
||||
sport=0;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
sportIdle();
|
||||
return;
|
||||
}
|
||||
}
|
||||
sportSend(frame);
|
||||
}
|
||||
|
||||
void proces_sport_data(uint8_t data)
|
||||
{
|
||||
switch (pass)
|
||||
{
|
||||
case 0:
|
||||
if (data == START_STOP)
|
||||
{//waiting for 0x7e
|
||||
index = 0;
|
||||
pass = 1;
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
if(data == BYTESTUFF)//if they are stuffed
|
||||
pass=2;
|
||||
else
|
||||
if (index < MAX_PKTX)
|
||||
pktx[index++] = data;
|
||||
break;
|
||||
case 2:
|
||||
if (index < MAX_PKTX)
|
||||
pktx[index++] = data ^ STUFF_MASK; //unstuff bytes
|
||||
pass=1;
|
||||
break;
|
||||
} // end switch
|
||||
if (index >= FRSKY_SPORT_PACKET_SIZE)
|
||||
{//8 bytes no crc
|
||||
sport = 1;//ok to send
|
||||
pass = 0;//reset
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void frskyUpdate()
|
||||
{
|
||||
#if defined DSM_TELEMETRY
|
||||
if(telemetry_link && (cur_protocol[0]&0x1F) == MODE_DSM2 )
|
||||
{ // DSM2
|
||||
DSM2_frame();
|
||||
telemetry_link=0;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if(telemetry_link && (cur_protocol[0]&0x1F) != MODE_FRSKYX )
|
||||
{ // FrSky + Hubsan
|
||||
frsky_link_frame();
|
||||
telemetry_link=0;
|
||||
return;
|
||||
}
|
||||
#if defined HUB_TELEMETRY
|
||||
if(!telemetry_link && (cur_protocol[0]&0x1F) == MODE_FRSKY)
|
||||
{ // FrSky
|
||||
frsky_user_frame();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if defined SPORT_TELEMETRY
|
||||
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
|
||||
{ // FrSkyX
|
||||
if(telemetry_link)
|
||||
{
|
||||
if(pktt[4]>0x36)
|
||||
rssi=pktt[4]>>1;
|
||||
else
|
||||
RxBt=pktt[4];
|
||||
for (uint8_t i=0; i < pktt[6]; i++)
|
||||
proces_sport_data(pktt[7+i]);
|
||||
telemetry_link=0;
|
||||
}
|
||||
uint32_t now = micros();
|
||||
if ((now - last) > SPORT_TIME)
|
||||
{
|
||||
sportSendFrame();
|
||||
last = now;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
60
Multiprotocol/WMath.cpp.xmega
Normal file
60
Multiprotocol/WMath.cpp.xmega
Normal file
@@ -0,0 +1,60 @@
|
||||
/* -*- mode: jde; c-basic-offset: 2; indent-tabs-mode: nil -*- */
|
||||
|
||||
/*
|
||||
Part of the Wiring project - http://wiring.org.co
|
||||
Copyright (c) 2004-06 Hernando Barragan
|
||||
Modified 13 August 2006, David A. Mellis for Arduino - http://www.arduino.cc/
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library 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
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General
|
||||
Public License along with this library; if not, write to the
|
||||
Free Software Foundation, Inc., 59 Temple Place, Suite 330,
|
||||
Boston, MA 02111-1307 USA
|
||||
|
||||
$Id$
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include "stdlib.h"
|
||||
}
|
||||
|
||||
void randomSeed(unsigned int seed)
|
||||
{
|
||||
if (seed != 0) {
|
||||
srandom(seed);
|
||||
}
|
||||
}
|
||||
|
||||
long random(long howbig)
|
||||
{
|
||||
if (howbig == 0) {
|
||||
return 0;
|
||||
}
|
||||
return random() % howbig;
|
||||
}
|
||||
|
||||
//long random(long howsmall, long howbig)
|
||||
//{
|
||||
// if (howsmall >= howbig) {
|
||||
// return howsmall;
|
||||
// }
|
||||
// long diff = howbig - howsmall;
|
||||
// return random(diff) + howsmall;
|
||||
//}
|
||||
|
||||
long map(long x, long in_min, long in_max, long out_min, long out_max)
|
||||
{
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
unsigned int makeWord(unsigned int w) { return w; }
|
||||
unsigned int makeWord(unsigned char h, unsigned char l) { return (h << 8) | l; }
|
||||
@@ -16,14 +16,12 @@
|
||||
/** Multiprotocol module configuration file ***/
|
||||
|
||||
//Uncomment your TX type
|
||||
#define TX_ER9X //ER9X AETR (988<->2012µs)
|
||||
#define TX_ER9X_AETR //ER9X AETR (988<->2012µs)
|
||||
//#define TX_ER9X_TAER //ER9X TAER (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)
|
||||
|
||||
//Uncomment to enable telemetry
|
||||
#define TELEMETRY
|
||||
|
||||
//Comment if a module is not installed
|
||||
#define A7105_INSTALLED
|
||||
#define CYRF6936_INSTALLED
|
||||
@@ -38,10 +36,12 @@
|
||||
#ifdef CYRF6936_INSTALLED
|
||||
#define DEVO_CYRF6936_INO
|
||||
#define DSM2_CYRF6936_INO
|
||||
#define J6PRO_CYRF6936_INO
|
||||
#endif
|
||||
#ifdef CC2500_INSTALLED
|
||||
#define FRSKY_CC2500_INO
|
||||
#define FRSKYX_CC2500_INO
|
||||
#define SFHSS_CC2500_INO
|
||||
#endif
|
||||
#ifdef NFR24L01_INSTALLED
|
||||
#define BAYANG_NRF24L01_INO
|
||||
@@ -56,27 +56,45 @@
|
||||
#define YD717_NRF24L01_INO
|
||||
#define MT99XX_NRF24L01_INO
|
||||
#define MJXQ_NRF24L01_INO
|
||||
#define SHENQI_NRF24L01_INO
|
||||
#define FY326_NRF24L01_INO
|
||||
#define FQ777_NRF24L01_INO
|
||||
#endif
|
||||
|
||||
//Uncomment to enable telemetry
|
||||
#define TELEMETRY
|
||||
|
||||
//Comment to disable a specific telemetry
|
||||
#if defined(TELEMETRY)
|
||||
#if defined DSM2_CYRF6936_INO
|
||||
#define DSM_TELEMETRY
|
||||
#endif
|
||||
#if defined FRSKYX_CC2500_INO
|
||||
#define SPORT_TELEMETRY
|
||||
#endif
|
||||
#if defined FRSKY_CC2500_INO
|
||||
#define HUB_TELEMETRY
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//Update this table to set which protocol and all associated settings are called for the corresponding dial number
|
||||
static const PPM_Parameters PPM_prot[15]=
|
||||
{
|
||||
// Protocol Sub protocol RX_Num Power Auto Bind Option
|
||||
{MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=1
|
||||
{MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2
|
||||
{MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=3
|
||||
{MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4
|
||||
{MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5
|
||||
{MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6
|
||||
{MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7
|
||||
{MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8
|
||||
{MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9
|
||||
{MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10
|
||||
{MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11
|
||||
{MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12
|
||||
{MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13
|
||||
{MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14
|
||||
{MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 } //Dial=15
|
||||
const PPM_Parameters PPM_prot[15]= {
|
||||
// Dial Protocol Sub protocol RX_Num Power Auto Bind Option
|
||||
/* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 3 */ {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, // D7 fine tuning
|
||||
/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 6 */ {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 6 }, // 6 channels @ 11ms
|
||||
/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 10 */ {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 11 */ {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 12 */ {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 13 */ {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 14 */ {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
|
||||
/* 15 */ {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 }
|
||||
};
|
||||
/* Available protocols and associated sub protocols:
|
||||
MODE_FLYSKY
|
||||
@@ -128,18 +146,30 @@ static const PPM_Parameters PPM_prot[15]=
|
||||
MODE_BAYANG
|
||||
NONE
|
||||
MODE_FRSKYX
|
||||
NONE
|
||||
CH_16
|
||||
CH_8
|
||||
MODE_ESKY
|
||||
NONE
|
||||
MODE_MT99XX
|
||||
MT99
|
||||
H7
|
||||
YZ
|
||||
LS
|
||||
MODE_MJXQ
|
||||
WLH08
|
||||
X600
|
||||
X800
|
||||
H26D
|
||||
MODE_SHENQI
|
||||
NONE
|
||||
MODE_FY326
|
||||
NONE
|
||||
MODE_SFHSS
|
||||
NONE
|
||||
MODE_J6PRO
|
||||
NONE
|
||||
MODE_FQ777
|
||||
NONE
|
||||
|
||||
RX_Num value between 0 and 15
|
||||
|
||||
@@ -154,11 +184,11 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning.
|
||||
//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
|
||||
#if defined(TX_ER9X_AETR)
|
||||
#define PPM_MAX 2140 // 125%
|
||||
#define PPM_MIN 860 // 125%
|
||||
#define PPM_MAX_100 2012 // 100%
|
||||
#define PPM_MIN_100 988 // 100%
|
||||
enum chan_order{
|
||||
AILERON =0,
|
||||
ELEVATOR,
|
||||
@@ -176,12 +206,35 @@ enum chan_order{
|
||||
};
|
||||
#endif
|
||||
|
||||
// Turnigy PPM and channels
|
||||
#if defined(TX_ER9X_TAER)
|
||||
#define PPM_MAX 2140 // 125%
|
||||
#define PPM_MIN 860 // 125%
|
||||
#define PPM_MAX_100 2012 // 100%
|
||||
#define PPM_MIN_100 988 // 100%
|
||||
enum chan_order{
|
||||
THROTTLE =0,
|
||||
AILERON,
|
||||
ELEVATOR,
|
||||
RUDDER,
|
||||
AUX1,
|
||||
AUX2,
|
||||
AUX3,
|
||||
AUX4,
|
||||
AUX5,
|
||||
AUX6,
|
||||
AUX7,
|
||||
AUX8,
|
||||
AUX9
|
||||
};
|
||||
#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
|
||||
#define PPM_MAX 2100 // 125%
|
||||
#define PPM_MIN 900 // 125%
|
||||
#define PPM_MAX_100 1920 // 100%
|
||||
#define PPM_MIN_100 1120 // 100%
|
||||
enum chan_order{
|
||||
ELEVATOR=0,
|
||||
AILERON,
|
||||
@@ -201,10 +254,10 @@ enum chan_order{
|
||||
|
||||
// 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
|
||||
#define PPM_MAX 2000 // 125%
|
||||
#define PPM_MIN 1000 // 125%
|
||||
#define PPM_MAX_100 1900 // 100%
|
||||
#define PPM_MIN_100 1100 // 100%
|
||||
enum chan_order{
|
||||
THROTTLE=0,
|
||||
AILERON,
|
||||
@@ -224,10 +277,10 @@ enum chan_order{
|
||||
|
||||
// HISKY
|
||||
#if defined(TX_HISKY)
|
||||
#define PPM_MAX 2000
|
||||
#define PPM_MIN 1000
|
||||
#define PPM_MAX_100 1900
|
||||
#define PPM_MIN_100 1100
|
||||
#define PPM_MAX 2000 // 125%
|
||||
#define PPM_MIN 1000 // 125%
|
||||
#define PPM_MAX_100 1900 // 100%
|
||||
#define PPM_MIN_100 1100 // 100%
|
||||
enum chan_order{
|
||||
AILERON =0,
|
||||
ELEVATOR,
|
||||
@@ -248,3 +301,7 @@ enum chan_order{
|
||||
#define PPM_MIN_COMMAND 1250
|
||||
#define PPM_SWITCH 1550
|
||||
#define PPM_MAX_COMMAND 1750
|
||||
|
||||
//Uncoment the desired serial speed
|
||||
#define BAUD 100000
|
||||
//#define BAUD 125000
|
||||
|
||||
@@ -156,4 +156,43 @@ enum {
|
||||
//void CC2500_WriteData(u8 *packet, u8 length);
|
||||
//void CC2500_ReadData(u8 *dpbuffer, int len);
|
||||
//void CC2500_SetTxRxMode(enum TXRX_State);
|
||||
|
||||
const PROGMEM uint8_t cc2500_conf[][2]={
|
||||
{ CC2500_02_IOCFG0, 0x06 },
|
||||
{ CC2500_00_IOCFG2, 0x06 },
|
||||
{ CC2500_17_MCSM1, 0x0c },
|
||||
{ CC2500_18_MCSM0, 0x18 },
|
||||
{ CC2500_06_PKTLEN, 0x19 },
|
||||
{ CC2500_07_PKTCTRL1, 0x04 },
|
||||
{ CC2500_08_PKTCTRL0, 0x05 },
|
||||
{ CC2500_3E_PATABLE, 0xff },
|
||||
{ CC2500_0B_FSCTRL1, 0x08 },
|
||||
{ CC2500_0C_FSCTRL0, 0x00 }, // option
|
||||
{ CC2500_0D_FREQ2, 0x5c },
|
||||
{ CC2500_0E_FREQ1, 0x76 },
|
||||
{ CC2500_0F_FREQ0, 0x27 },
|
||||
{ CC2500_10_MDMCFG4, 0xAA },
|
||||
{ CC2500_11_MDMCFG3, 0x39 },
|
||||
{ CC2500_12_MDMCFG2, 0x11 },
|
||||
{ CC2500_13_MDMCFG1, 0x23 },
|
||||
{ CC2500_14_MDMCFG0, 0x7a },
|
||||
{ CC2500_15_DEVIATN, 0x42 },
|
||||
{ CC2500_19_FOCCFG, 0x16 },
|
||||
{ CC2500_1A_BSCFG, 0x6c },
|
||||
{ CC2500_1B_AGCCTRL2, 0x43 }, // bind ? 0x43 : 0x03
|
||||
{ CC2500_1C_AGCCTRL1,0x40 },
|
||||
{ CC2500_1D_AGCCTRL0,0x91 },
|
||||
{ CC2500_21_FREND1, 0x56 },
|
||||
{ CC2500_22_FREND0, 0x10 },
|
||||
{ CC2500_23_FSCAL3, 0xa9 },
|
||||
{ CC2500_24_FSCAL2, 0x0A },
|
||||
{ CC2500_25_FSCAL1, 0x00 },
|
||||
{ CC2500_26_FSCAL0, 0x11 },
|
||||
{ CC2500_29_FSTEST, 0x59 },
|
||||
{ CC2500_2C_TEST2, 0x88 },
|
||||
{ CC2500_2D_TEST1, 0x31 },
|
||||
{ CC2500_2E_TEST0, 0x0B },
|
||||
{ CC2500_03_FIFOTHR, 0x07 },
|
||||
{ CC2500_09_ADDR, 0x00 }
|
||||
};
|
||||
#endif
|
||||
|
||||
@@ -103,6 +103,8 @@ enum {
|
||||
//#define NOP 0xFF
|
||||
|
||||
// XN297 emulation layer
|
||||
#define XN297_UNSCRAMBLED 8
|
||||
|
||||
enum {
|
||||
XN297_UNSCRAMBLED = 0,
|
||||
XN297_SCRAMBLED
|
||||
};
|
||||
#endif
|
||||
412
PCB v2.3d/Multipro-txV2-3d-cache.lib
Normal file
412
PCB v2.3d/Multipro-txV2-3d-cache.lib
Normal file
@@ -0,0 +1,412 @@
|
||||
EESchema-LIBRARY Version 2.3 Date: 05/02/2016 16:56:43
|
||||
#encoding utf-8
|
||||
#
|
||||
# +5V
|
||||
#
|
||||
DEF +5V #PWR 0 40 Y Y 1 F P
|
||||
F0 "#PWR" 0 90 20 H I C CNN
|
||||
F1 "+5V" 0 90 30 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
X +5V 1 0 0 0 U 20 20 0 0 W N
|
||||
C 0 50 20 0 1 0 N
|
||||
P 4 0 1 0 0 0 0 30 0 30 0 30 N
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# +BATT
|
||||
#
|
||||
DEF +BATT #PWR 0 0 Y Y 1 F P
|
||||
F0 "#PWR" 0 -50 20 H I C CNN
|
||||
F1 "+BATT" 0 100 30 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
X +BATT 1 0 0 0 U 20 20 0 0 w N
|
||||
C 0 60 20 0 1 0 N
|
||||
P 3 0 1 0 0 0 0 40 0 40 N
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# 3V3
|
||||
#
|
||||
DEF 3V3 #PWR 0 0 Y Y 1 F P
|
||||
F0 "#PWR" 0 100 40 H I C CNN
|
||||
F1 "3V3" 0 125 40 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
X 3V3 1 0 0 0 U 30 30 0 0 W N
|
||||
P 2 0 1 0 0 60 0 0 N
|
||||
P 6 0 1 0 0 60 20 40 0 90 -20 40 0 60 0 60 N
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# A7105
|
||||
#
|
||||
DEF A7105 U 0 40 Y Y 1 F N
|
||||
F0 "U" 500 650 60 H V C CNN
|
||||
F1 "A7105" 0 800 60 H V C CNN
|
||||
F2 "~" 0 -400 60 H V C CNN
|
||||
F3 "~" 0 -400 60 H V C CNN
|
||||
DRAW
|
||||
S 400 -800 -350 700 0 1 0 N
|
||||
X 3V3 1 -650 550 300 R 70 70 1 1 I
|
||||
X SCS 2 -650 400 300 R 70 70 1 1 I
|
||||
X GND 3 -650 250 300 R 70 70 1 1 I
|
||||
X SCK 4 -650 100 300 R 70 70 1 1 I
|
||||
X SDIO 5 -650 -50 300 R 70 70 1 1 I
|
||||
X GIO1 6 -650 -200 300 R 70 70 1 1 I
|
||||
X GIO2 7 -650 -350 300 R 70 70 1 1 O
|
||||
X RXEN 8 -650 -500 300 R 70 70 1 1 I
|
||||
X TXEN 9 -650 -650 300 R 70 70 1 1 O
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# ATMEGA168A-A
|
||||
#
|
||||
DEF ATMEGA168A-A IC 0 40 Y Y 1 F N
|
||||
F0 "IC" -750 1250 40 H V L BNN
|
||||
F1 "ATMEGA168A-A" 400 -1400 40 H V L BNN
|
||||
F2 "TQFP32" 0 0 30 H V C CIN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
ALIAS ATMEGA48A-A ATMEGA48PA-A ATMEGA88A-A ATMEGA88PA-A ATMEGA168PA-A ATMEGA328-A ATMEGA328P-A
|
||||
DRAW
|
||||
S -750 1200 850 -1300 0 1 10 f
|
||||
X (PCINT19/OC2B/INT1)PD3 1 1000 -800 150 L 40 40 1 1 B
|
||||
X (PCINT20/XCK/T0)PD4 2 1000 -900 150 L 40 40 1 1 B
|
||||
X GND 3 -900 -1200 150 R 40 40 1 1 W
|
||||
X VCC 4 -900 1100 150 R 40 40 1 1 W
|
||||
X GND 5 -900 -1100 150 R 40 40 1 1 W
|
||||
X VCC 6 -900 1000 150 R 40 40 1 1 W
|
||||
X (PCINT6/XTAL1/TOSC1)PB6 7 1000 500 150 L 40 40 1 1 B
|
||||
X (PCINT7/XTAL2/TOSC2)PB7 8 1000 400 150 L 40 40 1 1 B
|
||||
X (PCINT21/OC0B/T1)PD5 9 1000 -1000 150 L 40 40 1 1 B
|
||||
X (PCINT22/OC0A/AIN0)PD6 10 1000 -1100 150 L 40 40 1 1 B
|
||||
X AREF 20 -900 500 150 R 40 40 1 1 B
|
||||
X (PCINT16/RXD)PD0 30 1000 -500 150 L 40 40 1 1 B
|
||||
X (PCINT23/AIN1)PD7 11 1000 -1200 150 L 40 40 1 1 B
|
||||
X GND 21 -900 -1000 150 R 40 40 1 1 W
|
||||
X (PCINT17/TXD)PD1 31 1000 -600 150 L 40 40 1 1 B
|
||||
X (PCINT0/CLKO/ICP1)PB0 12 1000 1100 150 L 40 40 1 1 B
|
||||
X ADC7 22 -900 -350 150 R 40 40 1 1 N
|
||||
X (PCINT18/INT0)PD2 32 1000 -700 150 L 40 40 1 1 B
|
||||
X (PCINT1/OC1A)PB1 13 1000 1000 150 L 40 40 1 1 B
|
||||
X (PCINT8/ADC0)PC0 23 1000 250 150 L 40 40 1 1 B
|
||||
X (PCINT2/OC1B/~SS~)PB2 14 1000 900 150 L 40 40 1 1 B
|
||||
X (PCINT9/ADC1)PC1 24 1000 150 150 L 40 40 1 1 B
|
||||
X (PCINT3/OC2A/MOSI)PB3 15 1000 800 150 L 40 40 1 1 B
|
||||
X (PCINT10/ADC2)PC2 25 1000 50 150 L 40 40 1 1 B
|
||||
X (PCINT4/MISO)PB4 16 1000 700 150 L 40 40 1 1 B
|
||||
X (PCINT11/ADC3)PC3 26 1000 -50 150 L 40 40 1 1 B
|
||||
X (PCINT5/SCK)PB5 17 1000 600 150 L 40 40 1 1 B
|
||||
X (PCINT12/SDA/ADC4)PC4 27 1000 -150 150 L 40 40 1 1 B
|
||||
X AVCC 18 -900 800 150 R 40 40 1 1 W
|
||||
X (PCINT14/SCL/ADC5)PC5 28 1000 -250 150 L 40 40 1 1 B
|
||||
X ADC6 19 -900 -250 150 R 40 40 1 1 N
|
||||
X (PCINT14/~RESET~)PC6 29 1000 -350 150 L 40 40 1 1 B
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# C
|
||||
#
|
||||
DEF C C 0 10 N Y 1 F N
|
||||
F0 "C" 0 100 40 H V L CNN
|
||||
F1 "C" 6 -85 40 H V L CNN
|
||||
F2 "~" 38 -150 30 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
$FPLIST
|
||||
SM*
|
||||
C?
|
||||
C1-1
|
||||
$ENDFPLIST
|
||||
DRAW
|
||||
P 2 0 1 20 -80 -30 80 -30 N
|
||||
P 2 0 1 20 -80 30 80 30 N
|
||||
X ~ 1 0 200 170 D 40 40 1 1 P
|
||||
X ~ 2 0 -200 170 U 40 40 1 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CC2500
|
||||
#
|
||||
DEF CC2500 U 0 40 Y Y 1 F N
|
||||
F0 "U" 500 600 60 H V C CNN
|
||||
F1 "CC2500" 0 700 60 H V C CNN
|
||||
F2 "~" 0 -400 60 H V C CNN
|
||||
F3 "~" 0 -400 60 H V C CNN
|
||||
DRAW
|
||||
S 400 -900 -350 650 0 1 0 N
|
||||
X 3V3 1 -650 550 300 R 70 70 1 1 I
|
||||
X SI 2 -650 400 300 R 70 70 1 1 I
|
||||
X SCLK 3 -650 250 300 R 70 70 1 1 I
|
||||
X SO 4 -650 100 300 R 70 70 1 1 I
|
||||
X GDO2 5 -650 -50 300 R 70 70 1 1 I
|
||||
X GND 6 -650 -200 300 R 70 70 1 1 I
|
||||
X GDOo 7 -650 -350 300 R 70 70 1 1 I
|
||||
X CSn 8 -650 -500 300 R 70 70 1 1 I
|
||||
X PA_EN 9 -650 -650 300 R 70 70 1 1 I
|
||||
X LNA_EN 10 -650 -800 300 R 70 70 1 1 I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CONN_2
|
||||
#
|
||||
DEF CONN_2 P 0 40 Y N 1 F N
|
||||
F0 "P" -50 0 40 V V C CNN
|
||||
F1 "CONN_2" 50 0 40 V V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
S -100 150 100 -150 0 1 0 N
|
||||
X P1 1 -350 100 250 R 60 60 1 1 P I
|
||||
X PM 2 -350 -100 250 R 60 60 1 1 P I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CONN_3X2
|
||||
#
|
||||
DEF CONN_3X2 P 0 40 Y N 1 F N
|
||||
F0 "P" 0 250 50 H V C CNN
|
||||
F1 "CONN_3X2" 0 50 40 V V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
S -100 200 100 -100 0 1 0 N
|
||||
X 1 1 -400 150 300 R 60 60 1 1 P I
|
||||
X 2 2 400 150 300 L 60 60 1 1 P I
|
||||
X 3 3 -400 50 300 R 60 60 1 1 P I
|
||||
X 4 4 400 50 300 L 60 60 1 1 P I
|
||||
X 5 5 -400 -50 300 R 60 60 1 1 P I
|
||||
X 6 6 400 -50 300 L 60 60 1 1 P I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CONN_5
|
||||
#
|
||||
DEF CONN_5 P 0 40 Y Y 1 F N
|
||||
F0 "P" -50 0 50 V V C CNN
|
||||
F1 "CONN_5" 50 0 50 V V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
S -100 250 100 -250 0 1 0 f
|
||||
X ~ 1 -400 200 300 R 60 60 1 1 P I
|
||||
X ~ 2 -400 100 300 R 60 60 1 1 P I
|
||||
X ~ 3 -400 0 300 R 60 60 1 1 P I
|
||||
X ~ 4 -400 -100 300 R 60 60 1 1 P I
|
||||
X ~ 5 -400 -200 300 R 60 60 1 1 P I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CP1
|
||||
#
|
||||
DEF CP1 C 0 10 N N 1 F N
|
||||
F0 "C" 50 100 50 H V L CNN
|
||||
F1 "CP1" 50 -100 50 H V L CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
$FPLIST
|
||||
CP*
|
||||
SM*
|
||||
$ENDFPLIST
|
||||
DRAW
|
||||
T 0 -50 100 80 0 0 0 + Normal 0 C C
|
||||
A 0 -200 180 563 1236 0 1 15 N 100 -50 -100 -50
|
||||
P 4 0 1 15 -100 50 100 50 50 50 50 50 N
|
||||
X ~ 1 0 200 150 D 40 40 1 1 P
|
||||
X ~ 2 0 -200 180 U 40 40 1 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CRYSTAL
|
||||
#
|
||||
DEF CRYSTAL X 0 40 N N 1 F N
|
||||
F0 "X" 0 150 60 H V C CNN
|
||||
F1 "CRYSTAL" 0 -150 60 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
P 2 0 1 16 -100 100 -100 -100 N
|
||||
P 2 0 1 16 100 100 100 -100 N
|
||||
P 5 0 1 12 -50 50 50 50 50 -50 -50 -50 -50 50 f
|
||||
X 1 1 -300 -50 200 R 40 40 1 1 P
|
||||
X 2 2 -300 50 200 R 40 40 1 1 P
|
||||
X 3 3 300 50 200 L 40 40 1 1 P
|
||||
X 4 4 300 -50 200 L 40 40 1 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# CYRF6936
|
||||
#
|
||||
DEF CYRF6936 U 0 40 Y Y 1 F N
|
||||
F0 "U" 0 1000 60 H V C CNN
|
||||
F1 "CYRF6936" 0 800 60 H V C CNN
|
||||
F2 "~" 0 -400 60 H V C CNN
|
||||
F3 "~" 0 -400 60 H V C CNN
|
||||
DRAW
|
||||
S 400 -800 -350 700 0 1 0 N
|
||||
X 5.0V 1 -650 500 300 R 70 70 1 1 I
|
||||
X NCS 2 -650 350 300 R 70 70 1 1 I
|
||||
X SCK 4 -650 200 300 R 70 70 1 1 I
|
||||
X GND 5 -650 50 300 R 70 70 1 1 I
|
||||
X GND 6 -650 -100 300 R 70 70 1 1 I
|
||||
X MOSI 8 -650 -250 300 R 70 70 1 1 I
|
||||
X RST 9 -650 -400 300 R 70 70 1 1 I
|
||||
X MISO 10 -650 -600 300 R 70 70 1 1 I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# GND
|
||||
#
|
||||
DEF ~GND #PWR 0 0 Y Y 1 F P
|
||||
F0 "#PWR" 0 0 30 H I C CNN
|
||||
F1 "GND" 0 -70 30 H I C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
P 4 0 1 0 -50 0 0 -50 50 0 -50 0 N
|
||||
X GND 1 0 0 0 U 30 30 1 1 W N
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# HEX_DIP
|
||||
#
|
||||
DEF HEX_DIP SW 0 40 Y Y 1 F N
|
||||
F0 "SW" 0 -350 60 H V C CNN
|
||||
F1 "HEX_DIP" 0 350 60 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
S -200 250 200 -250 0 1 0 N
|
||||
P 4 0 1 0 50 50 -50 0 50 -100 50 50 F
|
||||
X 1 1 500 -150 300 L 50 50 1 1 O
|
||||
X C 2 500 0 300 L 50 50 1 1 P
|
||||
X 4 3 500 150 300 L 50 50 1 1 O
|
||||
X 2 4 -500 150 300 R 50 50 1 1 O
|
||||
X C 5 -500 0 300 R 50 50 1 1 P
|
||||
X 8 6 -500 -150 300 R 50 50 1 1 O
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# JUMPER
|
||||
#
|
||||
DEF JUMPER JP 0 30 Y N 1 F N
|
||||
F0 "JP" 0 150 60 H V C CNN
|
||||
F1 "JUMPER" 0 -80 40 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
A 0 -26 125 1426 373 0 1 0 N -98 50 99 50
|
||||
C -100 0 35 0 1 0 N
|
||||
C 100 0 35 0 1 0 N
|
||||
X 1 1 -300 0 165 R 60 60 0 1 P
|
||||
X 2 2 300 0 165 L 60 60 0 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# LED
|
||||
#
|
||||
DEF LED D 0 40 Y N 1 F N
|
||||
F0 "D" 0 100 50 H V C CNN
|
||||
F1 "LED" 0 -100 50 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
$FPLIST
|
||||
LED-3MM
|
||||
LED-5MM
|
||||
LED-10MM
|
||||
LED-0603
|
||||
LED-0805
|
||||
LED-1206
|
||||
LEDV
|
||||
$ENDFPLIST
|
||||
DRAW
|
||||
P 2 0 1 0 50 50 50 -50 N
|
||||
P 3 0 1 0 -50 50 50 0 -50 -50 F
|
||||
P 3 0 1 0 65 -40 110 -80 105 -55 N
|
||||
P 3 0 1 0 80 -25 125 -65 120 -40 N
|
||||
X A 1 -200 0 150 R 40 40 1 1 P
|
||||
X K 2 200 0 150 L 40 40 1 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# NCP1117ST50T3G
|
||||
#
|
||||
DEF NCP1117ST50T3G U 0 30 Y Y 1 F N
|
||||
F0 "U" 150 -196 40 H V C CNN
|
||||
F1 "NCP1117ST50T3G" 0 200 40 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
ALIAS NCP1117ST12T3G NCP1117ST15T3G NCP1117ST18T3G NCP1117ST20T3G NCP1117ST25T3G NCP1117ST285T3G NCP1117ST33T3G
|
||||
$FPLIST
|
||||
SOT223
|
||||
$ENDFPLIST
|
||||
DRAW
|
||||
S -250 -150 250 150 0 1 10 f
|
||||
X GND 1 0 -250 100 U 40 40 1 1 W
|
||||
X VO 2 400 50 150 L 40 40 1 1 w
|
||||
X VI 3 -400 50 150 R 40 40 1 1 W
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# NRF24L01
|
||||
#
|
||||
DEF NRF24L01 U 0 40 Y Y 1 F N
|
||||
F0 "U" 500 650 60 H V C CNN
|
||||
F1 "NRF24L01" 0 800 60 H V C CNN
|
||||
F2 "~" 0 -400 60 H V C CNN
|
||||
F3 "~" 0 -400 60 H V C CNN
|
||||
DRAW
|
||||
S 400 -650 -350 700 0 1 0 N
|
||||
X GND 1 -650 550 300 R 70 70 1 1 I
|
||||
X 3V3 2 -650 400 300 R 70 70 1 1 I
|
||||
X CE 3 -650 250 300 R 70 70 1 1 I
|
||||
X CSN 4 -650 100 300 R 70 70 1 1 I
|
||||
X SCK 5 -650 -50 300 R 70 70 1 1 I
|
||||
X MOSI 6 -650 -200 300 R 70 70 1 1 I
|
||||
X MISO 7 -650 -350 300 R 70 70 1 1 I
|
||||
X IRQ 8 -650 -500 300 R 70 70 1 1 N
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# R
|
||||
#
|
||||
DEF R R 0 0 N Y 1 F N
|
||||
F0 "R" 80 0 40 V V C CNN
|
||||
F1 "R" 7 1 40 V V C CNN
|
||||
F2 "~" -70 0 30 V V C CNN
|
||||
F3 "~" 0 0 30 H V C CNN
|
||||
$FPLIST
|
||||
R?
|
||||
SM0603
|
||||
SM0805
|
||||
R?-*
|
||||
SM1206
|
||||
$ENDFPLIST
|
||||
DRAW
|
||||
S -40 150 40 -150 0 1 12 N
|
||||
X ~ 1 0 250 100 D 60 60 1 1 P
|
||||
X ~ 2 0 -250 100 U 60 60 1 1 P
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
# SW_PUSH_4_Pin
|
||||
#
|
||||
DEF SW_PUSH_4_Pin SW 0 40 N N 1 F N
|
||||
F0 "SW" 150 110 50 H V C CNN
|
||||
F1 "SW_PUSH_4_Pin" 0 -200 50 H V C CNN
|
||||
F2 "~" 0 0 60 H V C CNN
|
||||
F3 "~" 0 0 60 H V C CNN
|
||||
DRAW
|
||||
S -170 50 170 60 0 1 0 N
|
||||
P 4 0 1 0 -40 60 -30 90 30 90 40 60 N
|
||||
X 1 1 -300 0 200 R 60 60 0 1 P I
|
||||
X 3 3 300 0 200 L 60 60 0 1 P I
|
||||
X 2 2 -300 -100 200 R 50 50 1 1 I I
|
||||
X 4 4 300 -100 200 L 50 50 1 1 I I
|
||||
ENDDRAW
|
||||
ENDDEF
|
||||
#
|
||||
#End Library
|
||||
248
PCB v2.3d/Multipro-txV2-3d.cmp
Normal file
248
PCB v2.3d/Multipro-txV2-3d.cmp
Normal file
@@ -0,0 +1,248 @@
|
||||
Cmp-Mod V01 Created by CvPcb (2013-07-07 BZR 4022)-stable date = 05/02/2016 14:40:56
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2AE5B;
|
||||
Reference = C1;
|
||||
ValeurCmp = 22uF;
|
||||
IdModule = c_tant_B;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC5DA8;
|
||||
Reference = C2;
|
||||
ValeurCmp = 0.1uF;
|
||||
IdModule = SM0603_Capa;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2AE76;
|
||||
Reference = C3;
|
||||
ValeurCmp = 22uF;
|
||||
IdModule = c_tant_B;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC62F4;
|
||||
Reference = C4;
|
||||
ValeurCmp = 18pF;
|
||||
IdModule = SM0603_Capa;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC631E;
|
||||
Reference = C5;
|
||||
ValeurCmp = 18pF;
|
||||
IdModule = SM0603_Capa;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2B150;
|
||||
Reference = C6;
|
||||
ValeurCmp = 22uF;
|
||||
IdModule = c_tant_B;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /54845FE2;
|
||||
Reference = C7;
|
||||
ValeurCmp = 0.1uF;
|
||||
IdModule = SM0603_Capa;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC617C;
|
||||
Reference = D1;
|
||||
ValeurCmp = LED;
|
||||
IdModule = LED-0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2D9F8;
|
||||
Reference = D2;
|
||||
ValeurCmp = LED;
|
||||
IdModule = LED-0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC5C99;
|
||||
Reference = IC1;
|
||||
ValeurCmp = ATMEGA328-A;
|
||||
IdModule = TQFP32;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53FE5887;
|
||||
Reference = JP1;
|
||||
ValeurCmp = JUMPER;
|
||||
IdModule = c_0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53FE5896;
|
||||
Reference = JP2;
|
||||
ValeurCmp = JUMPER;
|
||||
IdModule = c_0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4E4E1;
|
||||
Reference = JP3;
|
||||
ValeurCmp = JUMPER;
|
||||
IdModule = c_0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4EFD5;
|
||||
Reference = JP4;
|
||||
ValeurCmp = JUMPER;
|
||||
IdModule = c_0603;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2DBCC;
|
||||
Reference = P1;
|
||||
ValeurCmp = ISP;
|
||||
IdModule = pin_array_3x2;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53FE5423;
|
||||
Reference = P2;
|
||||
ValeurCmp = CONN_5;
|
||||
IdModule = MOLEX_4455_N2X5;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4E4CA;
|
||||
Reference = P3;
|
||||
ValeurCmp = CONN_2;
|
||||
IdModule = PIN_ARRAY_2X1;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC5FEA;
|
||||
Reference = R1;
|
||||
ValeurCmp = 10K;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2B990;
|
||||
Reference = R2;
|
||||
ValeurCmp = 2K2;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2B99F;
|
||||
Reference = R3;
|
||||
ValeurCmp = 1K;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC6125;
|
||||
Reference = R4;
|
||||
ValeurCmp = 1K;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2B787;
|
||||
Reference = R5;
|
||||
ValeurCmp = 2K2;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2D8C4;
|
||||
Reference = R6;
|
||||
ValeurCmp = 1K;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /54DCE006;
|
||||
Reference = R7;
|
||||
ValeurCmp = 2K2;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4E6D8;
|
||||
Reference = R8;
|
||||
ValeurCmp = 470;
|
||||
IdModule = SM0603_Resistor;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /54394777;
|
||||
Reference = SW1;
|
||||
ValeurCmp = HEX_DIP;
|
||||
IdModule = DIP-6__300;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4EC6E;
|
||||
Reference = SW2;
|
||||
ValeurCmp = BIND;
|
||||
IdModule = SW_PUSH_6x4.5MM;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /56B4EC7B;
|
||||
Reference = SW3;
|
||||
ValeurCmp = RESET;
|
||||
IdModule = Switch_SMT5mm;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2ACE9;
|
||||
Reference = U1;
|
||||
ValeurCmp = NCP1117ST50T3G;
|
||||
IdModule = SOT223;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2AD08;
|
||||
Reference = U2;
|
||||
ValeurCmp = NCP1117ST33T3G;
|
||||
IdModule = SOT223;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2BF57;
|
||||
Reference = U3;
|
||||
ValeurCmp = CYRF6936;
|
||||
IdModule = CYRF6936;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2C184;
|
||||
Reference = U4;
|
||||
ValeurCmp = A7105;
|
||||
IdModule = XL7105-D03B;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2C24E;
|
||||
Reference = U5;
|
||||
ValeurCmp = NRF24L01;
|
||||
IdModule = NRF24L01;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53C2C3F4;
|
||||
Reference = U6;
|
||||
ValeurCmp = CC2500;
|
||||
IdModule = header_10_2mm;
|
||||
EndCmp
|
||||
|
||||
BeginCmp
|
||||
TimeStamp = /53BC62D3;
|
||||
Reference = X1;
|
||||
ValeurCmp = 16MHz;
|
||||
IdModule = crystal_FA238-TSX3225;
|
||||
EndCmp
|
||||
|
||||
EndListe
|
||||
3253
PCB v2.3d/Multipro-txV2-3d.kicad_pcb
Normal file
3253
PCB v2.3d/Multipro-txV2-3d.kicad_pcb
Normal file
File diff suppressed because it is too large
Load Diff
644
PCB v2.3d/Multipro-txV2-3d.net
Normal file
644
PCB v2.3d/Multipro-txV2-3d.net
Normal file
@@ -0,0 +1,644 @@
|
||||
(export (version D)
|
||||
(design
|
||||
(source "C:\\Documents and Settings\\Steve\\My Documents\\Multipro-tx\\MultiproV2.3d\\Multipro-txV2-3d.sch")
|
||||
(date "05/02/2016 16:35:59")
|
||||
(tool "eeschema (2013-07-07 BZR 4022)-stable"))
|
||||
(components
|
||||
(comp (ref IC1)
|
||||
(value ATMEGA328-A)
|
||||
(footprint TQFP32)
|
||||
(libsource (lib atmel) (part ATMEGA328-A))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC5C99))
|
||||
(comp (ref C2)
|
||||
(value 0.1uF)
|
||||
(libsource (lib device) (part C))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC5DA8))
|
||||
(comp (ref R1)
|
||||
(value 10K)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC5FEA))
|
||||
(comp (ref R4)
|
||||
(value 1K)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC6125))
|
||||
(comp (ref D1)
|
||||
(value LED)
|
||||
(libsource (lib device) (part LED))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC617C))
|
||||
(comp (ref X1)
|
||||
(value 16MHz)
|
||||
(libsource (lib device) (part CRYSTAL))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC62D3))
|
||||
(comp (ref C4)
|
||||
(value 18pF)
|
||||
(libsource (lib device) (part C))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC62F4))
|
||||
(comp (ref C5)
|
||||
(value 18pF)
|
||||
(libsource (lib device) (part C))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53BC631E))
|
||||
(comp (ref U1)
|
||||
(value NCP1117ST50T3G)
|
||||
(libsource (lib regul) (part NCP1117ST50T3G))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2ACE9))
|
||||
(comp (ref U2)
|
||||
(value NCP1117ST33T3G)
|
||||
(libsource (lib regul) (part NCP1117ST50T3G))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2AD08))
|
||||
(comp (ref C1)
|
||||
(value 22uF)
|
||||
(libsource (lib device) (part CP1))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2AE5B))
|
||||
(comp (ref C3)
|
||||
(value 22uF)
|
||||
(libsource (lib device) (part CP1))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2AE76))
|
||||
(comp (ref C6)
|
||||
(value 22uF)
|
||||
(libsource (lib device) (part CP1))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2B150))
|
||||
(comp (ref R5)
|
||||
(value 2K2)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2B787))
|
||||
(comp (ref R2)
|
||||
(value 2K2)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2B990))
|
||||
(comp (ref R3)
|
||||
(value 1K)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2B99F))
|
||||
(comp (ref U3)
|
||||
(value CYRF6936)
|
||||
(libsource (lib device) (part CYRF6936))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2BF57))
|
||||
(comp (ref U4)
|
||||
(value A7105)
|
||||
(libsource (lib device) (part A7105))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2C184))
|
||||
(comp (ref U5)
|
||||
(value NRF24L01)
|
||||
(libsource (lib device) (part NRF24L01))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2C24E))
|
||||
(comp (ref U6)
|
||||
(value CC2500)
|
||||
(libsource (lib device) (part CC2500))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2C3F4))
|
||||
(comp (ref R6)
|
||||
(value 1K)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2D8C4))
|
||||
(comp (ref D2)
|
||||
(value LED)
|
||||
(libsource (lib device) (part LED))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2D9F8))
|
||||
(comp (ref P1)
|
||||
(value ISP)
|
||||
(libsource (lib conn) (part CONN_3X2))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53C2DBCC))
|
||||
(comp (ref P2)
|
||||
(value CONN_5)
|
||||
(libsource (lib conn) (part CONN_5))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53FE5423))
|
||||
(comp (ref JP2)
|
||||
(value JUMPER)
|
||||
(libsource (lib device) (part JUMPER))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53FE5887))
|
||||
(comp (ref JP4)
|
||||
(value JUMPER)
|
||||
(libsource (lib device) (part JUMPER))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 53FE5896))
|
||||
(comp (ref SW1)
|
||||
(value HEX_DIP)
|
||||
(libsource (lib device) (part HEX_DIP))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 54394777))
|
||||
(comp (ref C7)
|
||||
(value 0.1uF)
|
||||
(libsource (lib device) (part C))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 54845FE2))
|
||||
(comp (ref R7)
|
||||
(value 2K2)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 54DCE006))
|
||||
(comp (ref P3)
|
||||
(value CONN_2)
|
||||
(libsource (lib conn) (part CONN_2))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4E4CA))
|
||||
(comp (ref JP3)
|
||||
(value JUMPER)
|
||||
(libsource (lib device) (part JUMPER))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4E4E1))
|
||||
(comp (ref R8)
|
||||
(value 470)
|
||||
(libsource (lib device) (part R))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4E6D8))
|
||||
(comp (ref SW2)
|
||||
(value BIND)
|
||||
(libsource (lib device) (part SW_PUSH_4_PIN))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4EC6E))
|
||||
(comp (ref SW3)
|
||||
(value RESET)
|
||||
(libsource (lib device) (part SW_PUSH_4_PIN))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4EC7B))
|
||||
(comp (ref JP1)
|
||||
(value JUMPER)
|
||||
(libsource (lib device) (part JUMPER))
|
||||
(sheetpath (names /) (tstamps /))
|
||||
(tstamp 56B4EFD5)))
|
||||
(libparts
|
||||
(libpart (lib device) (part A7105)
|
||||
(fields
|
||||
(field (name Reference) U)
|
||||
(field (name Value) A7105)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 3V3) (type input))
|
||||
(pin (num 2) (name SCS) (type input))
|
||||
(pin (num 3) (name GND) (type input))
|
||||
(pin (num 4) (name SCK) (type input))
|
||||
(pin (num 5) (name SDIO) (type input))
|
||||
(pin (num 6) (name GIO1) (type input))
|
||||
(pin (num 7) (name GIO2) (type output))
|
||||
(pin (num 8) (name RXEN) (type input))
|
||||
(pin (num 9) (name TXEN) (type output))))
|
||||
(libpart (lib device) (part C)
|
||||
(description "Condensateur non polarise")
|
||||
(footprints
|
||||
(fp SM*)
|
||||
(fp C?)
|
||||
(fp C1-1))
|
||||
(fields
|
||||
(field (name Reference) C)
|
||||
(field (name Value) C)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name ~) (type passive))
|
||||
(pin (num 2) (name ~) (type passive))))
|
||||
(libpart (lib device) (part CC2500)
|
||||
(fields
|
||||
(field (name Reference) U)
|
||||
(field (name Value) CC2500)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 3V3) (type input))
|
||||
(pin (num 2) (name SI) (type input))
|
||||
(pin (num 3) (name SCLK) (type input))
|
||||
(pin (num 4) (name SO) (type input))
|
||||
(pin (num 5) (name GDO2) (type input))
|
||||
(pin (num 6) (name GND) (type input))
|
||||
(pin (num 7) (name GDOo) (type input))
|
||||
(pin (num 8) (name CSn) (type input))
|
||||
(pin (num 9) (name PA_EN) (type input))
|
||||
(pin (num 10) (name LNA_EN) (type input))))
|
||||
(libpart (lib device) (part CP1)
|
||||
(description "Condensateur polarise")
|
||||
(footprints
|
||||
(fp CP*)
|
||||
(fp SM*))
|
||||
(fields
|
||||
(field (name Reference) C)
|
||||
(field (name Value) CP1)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name ~) (type passive))
|
||||
(pin (num 2) (name ~) (type passive))))
|
||||
(libpart (lib device) (part CRYSTAL)
|
||||
(fields
|
||||
(field (name Reference) X)
|
||||
(field (name Value) CRYSTAL)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 1) (type passive))
|
||||
(pin (num 2) (name 2) (type passive))
|
||||
(pin (num 3) (name 3) (type passive))
|
||||
(pin (num 4) (name 4) (type passive))))
|
||||
(libpart (lib device) (part CYRF6936)
|
||||
(fields
|
||||
(field (name Reference) U)
|
||||
(field (name Value) CYRF6936)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 5.0V) (type input))
|
||||
(pin (num 2) (name NCS) (type input))
|
||||
(pin (num 4) (name SCK) (type input))
|
||||
(pin (num 5) (name GND) (type input))
|
||||
(pin (num 6) (name GND) (type input))
|
||||
(pin (num 8) (name MOSI) (type input))
|
||||
(pin (num 9) (name RST) (type input))
|
||||
(pin (num 10) (name MISO) (type input))))
|
||||
(libpart (lib device) (part HEX_DIP)
|
||||
(fields
|
||||
(field (name Reference) SW)
|
||||
(field (name Value) HEX_DIP)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 1) (type output))
|
||||
(pin (num 2) (name C) (type passive))
|
||||
(pin (num 3) (name 4) (type output))
|
||||
(pin (num 4) (name 2) (type output))
|
||||
(pin (num 5) (name C) (type passive))
|
||||
(pin (num 6) (name 8) (type output))))
|
||||
(libpart (lib device) (part JUMPER)
|
||||
(fields
|
||||
(field (name Reference) JP)
|
||||
(field (name Value) JUMPER)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 1) (type passive))
|
||||
(pin (num 2) (name 2) (type passive))))
|
||||
(libpart (lib device) (part LED)
|
||||
(footprints
|
||||
(fp LED-3MM)
|
||||
(fp LED-5MM)
|
||||
(fp LED-10MM)
|
||||
(fp LED-0603)
|
||||
(fp LED-0805)
|
||||
(fp LED-1206)
|
||||
(fp LEDV))
|
||||
(fields
|
||||
(field (name Reference) D)
|
||||
(field (name Value) LED)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name A) (type passive))
|
||||
(pin (num 2) (name K) (type passive))))
|
||||
(libpart (lib device) (part NRF24L01)
|
||||
(fields
|
||||
(field (name Reference) U)
|
||||
(field (name Value) NRF24L01)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name GND) (type input))
|
||||
(pin (num 2) (name 3V3) (type input))
|
||||
(pin (num 3) (name CE) (type input))
|
||||
(pin (num 4) (name CSN) (type input))
|
||||
(pin (num 5) (name SCK) (type input))
|
||||
(pin (num 6) (name MOSI) (type input))
|
||||
(pin (num 7) (name MISO) (type input))
|
||||
(pin (num 8) (name IRQ) (type NotConnected))))
|
||||
(libpart (lib device) (part R)
|
||||
(description Resistance)
|
||||
(footprints
|
||||
(fp R?)
|
||||
(fp SM0603)
|
||||
(fp SM0805)
|
||||
(fp R?-*)
|
||||
(fp SM1206))
|
||||
(fields
|
||||
(field (name Reference) R)
|
||||
(field (name Value) R)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name ~) (type passive))
|
||||
(pin (num 2) (name ~) (type passive))))
|
||||
(libpart (lib device) (part SW_PUSH_4_Pin)
|
||||
(description "Push Button 4 Pin")
|
||||
(fields
|
||||
(field (name Reference) SW)
|
||||
(field (name Value) SW_PUSH_4_Pin)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 1) (type passive))
|
||||
(pin (num 2) (name 2) (type input))
|
||||
(pin (num 3) (name 3) (type passive))
|
||||
(pin (num 4) (name 4) (type input))))
|
||||
(libpart (lib conn) (part CONN_2)
|
||||
(description "Symbole general de connecteur")
|
||||
(fields
|
||||
(field (name Reference) P)
|
||||
(field (name Value) CONN_2)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name P1) (type passive))
|
||||
(pin (num 2) (name PM) (type passive))))
|
||||
(libpart (lib conn) (part CONN_3X2)
|
||||
(description "Symbole general de connecteur")
|
||||
(fields
|
||||
(field (name Reference) P)
|
||||
(field (name Value) CONN_3X2)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name 1) (type passive))
|
||||
(pin (num 2) (name 2) (type passive))
|
||||
(pin (num 3) (name 3) (type passive))
|
||||
(pin (num 4) (name 4) (type passive))
|
||||
(pin (num 5) (name 5) (type passive))
|
||||
(pin (num 6) (name 6) (type passive))))
|
||||
(libpart (lib conn) (part CONN_5)
|
||||
(description "Symbole general de connecteur")
|
||||
(fields
|
||||
(field (name Reference) P)
|
||||
(field (name Value) CONN_5)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name ~) (type passive))
|
||||
(pin (num 2) (name ~) (type passive))
|
||||
(pin (num 3) (name ~) (type passive))
|
||||
(pin (num 4) (name ~) (type passive))
|
||||
(pin (num 5) (name ~) (type passive))))
|
||||
(libpart (lib regul) (part NCP1117ST50T3G)
|
||||
(description "NCP1117ST50T3G, 1A Low drop-out regulator, Fixed Output 5V, SOT223")
|
||||
(docs http://www.onsemi.com/pub_link/Collateral/NCP1117-D.PDF)
|
||||
(footprints
|
||||
(fp SOT223))
|
||||
(fields
|
||||
(field (name Reference) U)
|
||||
(field (name Value) NCP1117ST50T3G)
|
||||
(field (name Footprint) ~)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name GND) (type power_in))
|
||||
(pin (num 2) (name VO) (type power_out))
|
||||
(pin (num 3) (name VI) (type power_in))))
|
||||
(libpart (lib atmel) (part ATMEGA168A-A)
|
||||
(description "ATMEGA168A, TQFP32, 16k Flash, 1kB SRAM, 512B EEPROM")
|
||||
(docs http://www.atmel.com/dyn/resources/prod_documents/doc8271.pdf)
|
||||
(fields
|
||||
(field (name Reference) IC)
|
||||
(field (name Value) ATMEGA168A-A)
|
||||
(field (name Footprint) TQFP32)
|
||||
(field (name Datasheet) ~))
|
||||
(pins
|
||||
(pin (num 1) (name "(PCINT19/OC2B/INT1)PD3") (type BiDi))
|
||||
(pin (num 2) (name "(PCINT20/XCK/T0)PD4") (type BiDi))
|
||||
(pin (num 3) (name GND) (type power_in))
|
||||
(pin (num 4) (name VCC) (type power_in))
|
||||
(pin (num 5) (name GND) (type power_in))
|
||||
(pin (num 6) (name VCC) (type power_in))
|
||||
(pin (num 7) (name "(PCINT6/XTAL1/TOSC1)PB6") (type BiDi))
|
||||
(pin (num 8) (name "(PCINT7/XTAL2/TOSC2)PB7") (type BiDi))
|
||||
(pin (num 9) (name "(PCINT21/OC0B/T1)PD5") (type BiDi))
|
||||
(pin (num 10) (name "(PCINT22/OC0A/AIN0)PD6") (type BiDi))
|
||||
(pin (num 11) (name "(PCINT23/AIN1)PD7") (type BiDi))
|
||||
(pin (num 12) (name "(PCINT0/CLKO/ICP1)PB0") (type BiDi))
|
||||
(pin (num 13) (name "(PCINT1/OC1A)PB1") (type BiDi))
|
||||
(pin (num 14) (name "(PCINT2/OC1B/~SS~)PB2") (type BiDi))
|
||||
(pin (num 15) (name "(PCINT3/OC2A/MOSI)PB3") (type BiDi))
|
||||
(pin (num 16) (name "(PCINT4/MISO)PB4") (type BiDi))
|
||||
(pin (num 17) (name "(PCINT5/SCK)PB5") (type BiDi))
|
||||
(pin (num 18) (name AVCC) (type power_in))
|
||||
(pin (num 19) (name ADC6) (type NotConnected))
|
||||
(pin (num 20) (name AREF) (type BiDi))
|
||||
(pin (num 21) (name GND) (type power_in))
|
||||
(pin (num 22) (name ADC7) (type NotConnected))
|
||||
(pin (num 23) (name "(PCINT8/ADC0)PC0") (type BiDi))
|
||||
(pin (num 24) (name "(PCINT9/ADC1)PC1") (type BiDi))
|
||||
(pin (num 25) (name "(PCINT10/ADC2)PC2") (type BiDi))
|
||||
(pin (num 26) (name "(PCINT11/ADC3)PC3") (type BiDi))
|
||||
(pin (num 27) (name "(PCINT12/SDA/ADC4)PC4") (type BiDi))
|
||||
(pin (num 28) (name "(PCINT14/SCL/ADC5)PC5") (type BiDi))
|
||||
(pin (num 29) (name "(PCINT14/~RESET~)PC6") (type BiDi))
|
||||
(pin (num 30) (name "(PCINT16/RXD)PD0") (type BiDi))
|
||||
(pin (num 31) (name "(PCINT17/TXD)PD1") (type BiDi))
|
||||
(pin (num 32) (name "(PCINT18/INT0)PD2") (type BiDi)))))
|
||||
(libraries
|
||||
(library (logical device)
|
||||
(uri "C:\\Program Files\\KiCad\\share\\library\\device.lib"))
|
||||
(library (logical conn)
|
||||
(uri "C:\\Program Files\\KiCad\\share\\library\\conn.lib"))
|
||||
(library (logical regul)
|
||||
(uri "C:\\Program Files\\KiCad\\share\\library\\regul.lib"))
|
||||
(library (logical atmel)
|
||||
(uri "C:\\Program Files\\KiCad\\share\\library\\atmel.lib")))
|
||||
(nets
|
||||
(net (code 1) (name GND)
|
||||
(node (ref P2) (pin 4))
|
||||
(node (ref C7) (pin 2))
|
||||
(node (ref SW1) (pin 5))
|
||||
(node (ref SW1) (pin 2))
|
||||
(node (ref C5) (pin 2))
|
||||
(node (ref C4) (pin 1))
|
||||
(node (ref X1) (pin 4))
|
||||
(node (ref SW3) (pin 4))
|
||||
(node (ref SW3) (pin 3))
|
||||
(node (ref SW2) (pin 4))
|
||||
(node (ref SW2) (pin 3))
|
||||
(node (ref D1) (pin 2))
|
||||
(node (ref R3) (pin 2))
|
||||
(node (ref U6) (pin 6))
|
||||
(node (ref U5) (pin 1))
|
||||
(node (ref U4) (pin 3))
|
||||
(node (ref U3) (pin 6))
|
||||
(node (ref U3) (pin 5))
|
||||
(node (ref C3) (pin 2))
|
||||
(node (ref C1) (pin 2))
|
||||
(node (ref U2) (pin 1))
|
||||
(node (ref U1) (pin 1))
|
||||
(node (ref C6) (pin 2))
|
||||
(node (ref IC1) (pin 21))
|
||||
(node (ref IC1) (pin 5))
|
||||
(node (ref IC1) (pin 3))
|
||||
(node (ref X1) (pin 2))
|
||||
(node (ref C2) (pin 2))
|
||||
(node (ref D2) (pin 2))
|
||||
(node (ref P1) (pin 6)))
|
||||
(net (code 2) (name "")
|
||||
(node (ref D2) (pin 1))
|
||||
(node (ref R6) (pin 2)))
|
||||
(net (code 3) (name 3V3)
|
||||
(node (ref R5) (pin 2))
|
||||
(node (ref U6) (pin 1))
|
||||
(node (ref U5) (pin 2))
|
||||
(node (ref C7) (pin 1))
|
||||
(node (ref U4) (pin 1))
|
||||
(node (ref U2) (pin 2))
|
||||
(node (ref IC1) (pin 18))
|
||||
(node (ref IC1) (pin 6))
|
||||
(node (ref P1) (pin 2))
|
||||
(node (ref IC1) (pin 4))
|
||||
(node (ref R1) (pin 1))
|
||||
(node (ref C6) (pin 1)))
|
||||
(net (code 4) (name /CC25_CSN)
|
||||
(node (ref IC1) (pin 11))
|
||||
(node (ref U6) (pin 8)))
|
||||
(net (code 5) (name /MISO)
|
||||
(node (ref U3) (pin 10))
|
||||
(node (ref IC1) (pin 10))
|
||||
(node (ref U5) (pin 7))
|
||||
(node (ref U6) (pin 4)))
|
||||
(net (code 6) (name /SCK)
|
||||
(node (ref IC1) (pin 2))
|
||||
(node (ref U4) (pin 4))
|
||||
(node (ref U6) (pin 3))
|
||||
(node (ref U3) (pin 4))
|
||||
(node (ref U5) (pin 5)))
|
||||
(net (code 7) (name /MOSI)
|
||||
(node (ref U5) (pin 6))
|
||||
(node (ref IC1) (pin 9))
|
||||
(node (ref U6) (pin 2))
|
||||
(node (ref U4) (pin 5))
|
||||
(node (ref U3) (pin 8)))
|
||||
(net (code 8) (name +5V)
|
||||
(node (ref U2) (pin 3))
|
||||
(node (ref U1) (pin 2))
|
||||
(node (ref C3) (pin 1))
|
||||
(node (ref U3) (pin 1))
|
||||
(node (ref R6) (pin 1)))
|
||||
(net (code 9) (name /D11)
|
||||
(node (ref P1) (pin 4))
|
||||
(node (ref SW1) (pin 4))
|
||||
(node (ref IC1) (pin 15)))
|
||||
(net (code 10) (name /RESET)
|
||||
(node (ref IC1) (pin 29))
|
||||
(node (ref SW3) (pin 1))
|
||||
(node (ref P1) (pin 5))
|
||||
(node (ref R1) (pin 2))
|
||||
(node (ref SW3) (pin 2)))
|
||||
(net (code 11) (name /D12)
|
||||
(node (ref P1) (pin 1))
|
||||
(node (ref IC1) (pin 16))
|
||||
(node (ref SW1) (pin 3)))
|
||||
(net (code 12) (name "")
|
||||
(node (ref U4) (pin 7))
|
||||
(node (ref U4) (pin 8)))
|
||||
(net (code 13) (name "")
|
||||
(node (ref U4) (pin 6))
|
||||
(node (ref U4) (pin 9)))
|
||||
(net (code 14) (name /A7105_CSN)
|
||||
(node (ref IC1) (pin 32))
|
||||
(node (ref U4) (pin 2)))
|
||||
(net (code 15) (name /CC25_LANEN)
|
||||
(node (ref U6) (pin 5))
|
||||
(node (ref U6) (pin 10)))
|
||||
(net (code 16) (name /CC25_PAEN)
|
||||
(node (ref U6) (pin 9))
|
||||
(node (ref U6) (pin 7)))
|
||||
(net (code 17) (name /NRF_CE)
|
||||
(node (ref R5) (pin 1))
|
||||
(node (ref U5) (pin 3)))
|
||||
(net (code 18) (name /NRF_CSN)
|
||||
(node (ref U5) (pin 4))
|
||||
(node (ref IC1) (pin 12)))
|
||||
(net (code 19) (name "")
|
||||
(node (ref R8) (pin 1))
|
||||
(node (ref P3) (pin 2))
|
||||
(node (ref JP3) (pin 2)))
|
||||
(net (code 20) (name /PPM_IN)
|
||||
(node (ref JP2) (pin 1))
|
||||
(node (ref P2) (pin 1))
|
||||
(node (ref R2) (pin 2)))
|
||||
(net (code 21) (name "")
|
||||
(node (ref JP3) (pin 1))
|
||||
(node (ref P2) (pin 5)))
|
||||
(net (code 22) (name "")
|
||||
(node (ref JP4) (pin 2))
|
||||
(node (ref P3) (pin 1)))
|
||||
(net (code 23) (name "")
|
||||
(node (ref JP2) (pin 2))
|
||||
(node (ref R7) (pin 1)))
|
||||
(net (code 24) (name "")
|
||||
(node (ref R3) (pin 1))
|
||||
(node (ref JP1) (pin 2)))
|
||||
(net (code 25) (name /RX)
|
||||
(node (ref IC1) (pin 30))
|
||||
(node (ref R7) (pin 2)))
|
||||
(net (code 26) (name "")
|
||||
(node (ref P2) (pin 2))
|
||||
(node (ref JP4) (pin 1)))
|
||||
(net (code 27) (name /TX)
|
||||
(node (ref IC1) (pin 31))
|
||||
(node (ref R8) (pin 2)))
|
||||
(net (code 28) (name /CYRF_RST)
|
||||
(node (ref IC1) (pin 28))
|
||||
(node (ref U3) (pin 9)))
|
||||
(net (code 29) (name /CYRF_CSN)
|
||||
(node (ref U3) (pin 2))
|
||||
(node (ref IC1) (pin 13)))
|
||||
(net (code 30) (name /A0)
|
||||
(node (ref IC1) (pin 23))
|
||||
(node (ref SW1) (pin 6)))
|
||||
(net (code 31) (name /D10)
|
||||
(node (ref SW1) (pin 1))
|
||||
(node (ref IC1) (pin 14)))
|
||||
(net (code 32) (name /xtl2)
|
||||
(node (ref X1) (pin 1))
|
||||
(node (ref IC1) (pin 8))
|
||||
(node (ref C5) (pin 1)))
|
||||
(net (code 33) (name /xtl1)
|
||||
(node (ref IC1) (pin 7))
|
||||
(node (ref X1) (pin 3))
|
||||
(node (ref C4) (pin 2)))
|
||||
(net (code 34) (name "")
|
||||
(node (ref D1) (pin 1))
|
||||
(node (ref SW2) (pin 1))
|
||||
(node (ref SW2) (pin 2))
|
||||
(node (ref R4) (pin 2)))
|
||||
(net (code 35) (name /A3)
|
||||
(node (ref IC1) (pin 26)))
|
||||
(net (code 36) (name /D3)
|
||||
(node (ref IC1) (pin 1))
|
||||
(node (ref R2) (pin 1))
|
||||
(node (ref JP1) (pin 1)))
|
||||
(net (code 37) (name /A4)
|
||||
(node (ref IC1) (pin 27)))
|
||||
(net (code 38) (name /A2)
|
||||
(node (ref IC1) (pin 25)))
|
||||
(net (code 39) (name /A1)
|
||||
(node (ref IC1) (pin 24)))
|
||||
(net (code 40) (name /A6)
|
||||
(node (ref IC1) (pin 19)))
|
||||
(net (code 41) (name /A7)
|
||||
(node (ref IC1) (pin 22)))
|
||||
(net (code 42) (name /PB5)
|
||||
(node (ref P1) (pin 3))
|
||||
(node (ref IC1) (pin 17))
|
||||
(node (ref R4) (pin 1)))
|
||||
(net (code 43) (name "")
|
||||
(node (ref IC1) (pin 20))
|
||||
(node (ref C2) (pin 1)))
|
||||
(net (code 44) (name "")
|
||||
(node (ref U5) (pin 8)))
|
||||
(net (code 45) (name /BATT)
|
||||
(node (ref C1) (pin 1))
|
||||
(node (ref P2) (pin 3))
|
||||
(node (ref U1) (pin 3)))))
|
||||
41
PCB v2.3d/Multipro-txV2-3d.pro
Normal file
41
PCB v2.3d/Multipro-txV2-3d.pro
Normal file
@@ -0,0 +1,41 @@
|
||||
update=04/02/2016 18:14:57
|
||||
last_client=pcbnew
|
||||
[pcbnew]
|
||||
version=1
|
||||
LastNetListRead=Multipro-txV2-3d.net
|
||||
UseCmpFile=1
|
||||
PadDrill=0.750000000000
|
||||
PadDrillOvalY=0.750000000000
|
||||
PadSizeH=1.250000000000
|
||||
PadSizeV=1.250000000000
|
||||
PcbTextSizeV=1.500000000000
|
||||
PcbTextSizeH=1.500000000000
|
||||
PcbTextThickness=0.300000000000
|
||||
ModuleTextSizeV=1.000000000000
|
||||
ModuleTextSizeH=1.000000000000
|
||||
ModuleTextSizeThickness=0.150000000000
|
||||
SolderMaskClearance=0.000000000000
|
||||
SolderMaskMinWidth=0.000000000000
|
||||
DrawSegmentWidth=0.400000000000
|
||||
BoardOutlineThickness=0.100000000000
|
||||
ModuleOutlineThickness=0.150000000000
|
||||
[pcbnew/libraries]
|
||||
LibDir=../Multipro-txV2
|
||||
LibName1=sockets
|
||||
LibName2=connect
|
||||
LibName3=discret
|
||||
LibName4=pin_array
|
||||
LibName5=divers
|
||||
LibName6=smd_capacitors
|
||||
LibName7=smd_resistors
|
||||
LibName8=smd_crystal&oscillator
|
||||
LibName9=smd_dil
|
||||
LibName10=smd_transistors
|
||||
LibName11=libcms
|
||||
LibName12=display
|
||||
LibName13=led
|
||||
LibName14=dip_sockets
|
||||
LibName15=pga_sockets
|
||||
LibName16=valves
|
||||
LibName17=Logo
|
||||
LibName18=LogoBsilk
|
||||
1452
PCB v2.3d/Multipro-txV2-3d.sch
Normal file
1452
PCB v2.3d/Multipro-txV2-3d.sch
Normal file
File diff suppressed because it is too large
Load Diff
BIN
PCB v2.3d/PCB_v2.3d.jpg
Normal file
BIN
PCB v2.3d/PCB_v2.3d.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 172 KiB |
35
PCB v2.3d/Readme.txt
Normal file
35
PCB v2.3d/Readme.txt
Normal file
@@ -0,0 +1,35 @@
|
||||
These are KiCad files and you are free to do what you will with them. KiCad is a good, free, and fairly
|
||||
easy to learn. Build your own BOM and gerber files.
|
||||
|
||||
This is a variant of the Multipro V2.3c circuit design. It is basicly the same as the 2.3c board as far
|
||||
as component placement goes. What's changed is the added resistors for the serial protocol and also
|
||||
the addition of solder jumpers on the bottom of the board for the various options to connect the TX, RX, and PPM
|
||||
lines through them. See below for more detail.
|
||||
|
||||
The schematic has been updated to reflect the added components and jumper pads as well as cleaned
|
||||
up a little. As it sits now, the .net file loads without any complaints and DRC checks pass.
|
||||
|
||||
The jumpers, and how they are used:
|
||||
|
||||
|
||||
There are four solder type jumpers on the bottom side of the board near the lower left corner when the
|
||||
bottom of the board is facing towards you. The silkscreen shows which jumper is which. These four jumpers
|
||||
enable the board to be configured in several ways as explaned below.
|
||||
|
||||
(J-1) Use (PPM V/V) if the incoming PPM signal is at a higher voltage level, leave open if ~~5V.
|
||||
|
||||
(J-2) Use (Jumper 2) to connect the incomming PPM signal to the RX pin on the processor
|
||||
|
||||
(J-3) Short (TELEM) only if you have done a telemetry mod to your radio, leave open if not needed. When
|
||||
connected, pin 2 of the two pin header (P3) is also connected.
|
||||
|
||||
(J-4) Use (MOD) only to connect the transmitter pin 2 to pin 1 of the two pin header (P3).
|
||||
|
||||
The direction this project is going, it is most likely J-2 will be the only one needing to be shorted for
|
||||
the serial method of sending model protocols.
|
||||
|
||||
|
||||
These files are submitted without any guarentee of accureacy or suitability for any intended use. I am strictly
|
||||
an amature with time on his hands. Although I have done all I know to make it correct, things outside of my
|
||||
knowledge base are beyond my control. Do not use untested equipment around persons not familiar with the hazards
|
||||
of remote controlled vehicals.
|
||||
BIN
PCB v2.3d/Schematic_v2.3d.jpg
Normal file
BIN
PCB v2.3d/Schematic_v2.3d.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 224 KiB |
365
Protocols_Details.md
Normal file
365
Protocols_Details.md
Normal file
@@ -0,0 +1,365 @@
|
||||
#Protocols details
|
||||
**You'll find below a detailed description of every supported protocols sorted by RF modules.**
|
||||
|
||||
Legend:
|
||||
- Extended limits supported: -125%..+125% can be used and will be transmitted. Otherwise the default is -100%..+100% only.
|
||||
- Autobind protocol: you do not need to press the bind button at power up to bind, this is done automatically.
|
||||
|
||||
***
|
||||
#A7105 RF Module
|
||||
|
||||
##FLYSKY
|
||||
Extended limits supported
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|CH5|CH6|CH7|CH8
|
||||
|
||||
###Sub_protocol V9X9
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|LIGHT|PICTURE|VIDEO
|
||||
|
||||
###Sub_protocol V6X6
|
||||
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---
|
||||
FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
|
||||
|
||||
###Sub_protocol V912
|
||||
CH5|CH6
|
||||
---|---
|
||||
BTMBTN|TOPBTN
|
||||
|
||||
##HUBSAN
|
||||
Models: Hubsan H102D, H107/L/C/D and Hubsan H107P/C+/D+
|
||||
|
||||
Autobind protocol
|
||||
|
||||
Telemetry enabled for battery voltage and TX RSSI
|
||||
|
||||
Option=vTX frequency (H107D) 5645 - 5900 MHz
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
***
|
||||
#CC2500 RF Module
|
||||
|
||||
##FRSKY
|
||||
Extended limits supported
|
||||
|
||||
Telemetry enabled for A0, A1, RSSI, TSSI and Hub
|
||||
|
||||
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
|
||||
##FRSKYX
|
||||
Models: FrSky receivers X4R, X6R and X8R.
|
||||
|
||||
Extended limits supported
|
||||
|
||||
Telemetry enabled for A1 (RxBatt), A2, RSSI, TSSI and Hub
|
||||
|
||||
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
|
||||
|
||||
###Sub_protocol CH_16
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
|
||||
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
|
||||
|
||||
###Sub_protocol CH_8
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
|
||||
##SFHSS
|
||||
Models: Futaba RXs and XK models.
|
||||
|
||||
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|CH5|CH6|CH7|CH8
|
||||
|
||||
***
|
||||
#CYRF6936 RF Module
|
||||
|
||||
##DEVO
|
||||
Extended limits supported
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
|
||||
##DSM2
|
||||
Extended limits supported
|
||||
|
||||
Telemetry enabled for TSSI and plugins
|
||||
|
||||
option=number of channels and frame rate:
|
||||
- 0 : 4 channels @22ms
|
||||
- 1 : 5 channels @22ms
|
||||
- 2 : 6 channels @22ms
|
||||
- 3 : 7 channels @22ms
|
||||
|
||||
- 4 : 4 channels @11ms
|
||||
- 5 : 5 channels @11ms
|
||||
- 6 : 6 channels @11ms
|
||||
- 7 : 7 channels @11ms
|
||||
|
||||
- 8 : 8 channels @22ms
|
||||
- 9 : 9 channels @22ms
|
||||
- 10 : 10 channels @22ms
|
||||
- 11 : 11 channels @22ms
|
||||
- 12 : 12 channels @22ms
|
||||
|
||||
Value 6 is usually giving the best results with most of the RX.
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---|---|----|----|----
|
||||
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
|
||||
###Sub_protocol DSMX
|
||||
Same as above
|
||||
|
||||
##J6Pro
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---|---|----|----|----
|
||||
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
|
||||
***
|
||||
#NRF24L01 RF Module
|
||||
|
||||
##BAYANG
|
||||
Models: EAchine H8(C) mini, BayangToys X6/X7/X9, JJRC JJ850, Floureon H101 ...
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
|
||||
---|---|---|---|---|---|---|---|---|----
|
||||
A|E|T|R|FLIP|RTH|PICTURE|VIDEO|HEADLESS|INVERTED
|
||||
|
||||
##CG023
|
||||
Models: EAchine CG023/CG031/3D X4
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol YD829
|
||||
Models: Attop YD-822/YD-829/YD-829C ...
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP||PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol H8_3D
|
||||
Models: EAchine H8 mini 3D, JJRC H20/H22
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP|LIGTH|OPT1|OPT2|CAL
|
||||
|
||||
JJRC H20: OPT1=Headless, OPT2=RTH
|
||||
|
||||
JJRC H22: OPT1=RTH, OPT2=180/360° flip mode
|
||||
|
||||
H8 3D: OPT1=RTH + headless, OPT2=180/360° flip mode
|
||||
|
||||
CAL: calibrate accelerometers
|
||||
|
||||
##CX10
|
||||
Extended limits supported
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|RATE
|
||||
|
||||
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3
|
||||
|
||||
###Sub_protocol GREEN
|
||||
Models: Cheerson CX-10 green pcb
|
||||
|
||||
Same channels assignement as above.
|
||||
|
||||
###Sub_protocol BLUE
|
||||
Models: Cheerson CX-10 blue pcb & some newer red pcb, CX-10A, CX-10C, CX11, CX12, Floureon FX10, JJRC DHD D1
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|RATE|PICTURE|VIDEO
|
||||
|
||||
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 or headless for CX-10A
|
||||
|
||||
###Sub_protocol DM007
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol Q282 and Q242
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---
|
||||
FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
|
||||
|
||||
Model: JXD 509 is using Q282 with CH12=Start/Stop motors
|
||||
|
||||
###Sub_protocol JC3015_1
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO
|
||||
|
||||
###Sub_protocol JC3015_2
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|MODE|LED|DFLIP
|
||||
|
||||
###Sub_protocol MK33041
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9|CH10
|
||||
---|---|---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
|
||||
|
||||
##ESKY
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|GYRO|PITCH
|
||||
|
||||
##FY326
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|RTH|HEADLESS|EXPERT|CALIBRATE
|
||||
|
||||
##FQ777
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|RTH|HEADLESS|EXPERT
|
||||
|
||||
##HISKY
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|GEAR|PITCH|GYRO|CH8
|
||||
|
||||
GYRO: -100%=6G, +100%=3G
|
||||
|
||||
###HK310
|
||||
Models: RX HK-3000, HK3100 and XY3000 (TX are HK-300, HK-310 and TL-3C)
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
|||T|R|AUX|T_FSAFE|R_FSAFE|AUX_FSAFE
|
||||
|
||||
##KN
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
|
||||
---|---|---|---|---|---|---|---|---|----|----
|
||||
A|E|T|R|DR|THOLD|IDLEUP|GYRO|Ttrim|Atrim|Etrim
|
||||
|
||||
Dual Rate: +100%=full range, Throttle Hold: +100%=hold, Idle Up: +100%=3D, GYRO: -100%=6G, +100%=3G
|
||||
|
||||
###Sub_protocol WLTOYS
|
||||
###Sub_protocol FEILUN
|
||||
Same channels assignement as above.
|
||||
|
||||
##MJXQ
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13
|
||||
---|---|---|---|---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|AUTOFLIP|PAN|TILT
|
||||
|
||||
###Sub_protocol WLH08
|
||||
###Sub_protocol X600
|
||||
###Sub_protocol X800
|
||||
###Sub_protocol H26D
|
||||
|
||||
##MT99XX
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol MT
|
||||
Models: MT99xx
|
||||
###Sub_protocol H7
|
||||
Models: Eachine H7, Cheerson CX023
|
||||
###Sub_protocol YZ
|
||||
Model: Yi Zhan i6S
|
||||
Only one model can be flown at the same time since the ID is hardcoded.
|
||||
###Sub_protocol LS
|
||||
Models: LS114, 124, 215
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|INVERT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
##Shenqi
|
||||
Autobind protocol
|
||||
|
||||
Model: Shenqiwei 1/20 Mini Motorcycle
|
||||
|
||||
CH1|CH2|CH3|CH4
|
||||
---|---|---|---
|
||||
| |T|R
|
||||
|
||||
Throttle +100%=full forward,0%=stop,-100%=full backward.
|
||||
|
||||
##SLT
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|GEAR|PITCH
|
||||
|
||||
##Symax
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP||PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol SYMAX
|
||||
Models: Syma X5C-1/X11/X11C/X12
|
||||
|
||||
###Sub_protocol SYMAX5C
|
||||
Model: Syma X5C (original) and X2
|
||||
|
||||
##V2X2
|
||||
Models: WLToys V202/252/272, JXD 385/388, JJRC H6C, Yizhan Tarantula X6 ...
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
|
||||
---|---|---|---|---|---|---|---|---|----|----
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|MAG_CAL_X|MAG_CAL_Y
|
||||
|
||||
PICTURE: also automatic Missile Launcher and Hoist in one direction
|
||||
|
||||
VIDEO: also Sprayer, Bubbler, Missile Launcher(1), and Hoist in the other dir
|
||||
|
||||
##YD717
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
###Sub_protocol YD717
|
||||
###Sub_protocol SKYWLKR
|
||||
###Sub_protocol SYMAX4
|
||||
###Sub_protocol XINXUN
|
||||
###Sub_protocol NIHUI
|
||||
Same channels assignement as above.
|
||||
427
README.md
427
README.md
@@ -44,7 +44,7 @@ Settings per selection are located in _Config.h:
|
||||
- Autobind: Yes or No. At the model selection (or power applied to the TX) a bind sequence will be initiated
|
||||
|
||||
###Using a serial output
|
||||
The multiprotocol TX module takes full advantage of being used on a Turnigy 9X, 9XR, 9XR Pro, Taranis, 9Xtreme, AR9X, ... running [er9x or ersky9X](https://github.com/MikeBland/mbtx/tree/next). (A version for OpenTX is being looked at)
|
||||
The multiprotocol TX module takes full advantage of being used on a Turnigy 9X, 9XR, 9XR Pro, Taranis, 9Xtreme, AR9X, ... running [er9x](http://openrcforums.com/forum/viewtopic.php?f=5&t=4598) or [ersky9X](http://openrcforums.com/forum/viewtopic.php?f=7&t=4676). An OpenTX version for Taranis is available [here](http://plaisthos.de/opentx/).
|
||||
|
||||
This enables full integration using the radio GUI to setup models with all the available protocols options.
|
||||
|
||||
@@ -66,25 +66,29 @@ Notes:
|
||||
|
||||
###Telemetry
|
||||
|
||||
There are 3 protocols supporting telemetry: Hubsan, FrSky and FrSkyX.
|
||||
There are 4 protocols supporting telemetry: Hubsan, DSM, FrSky and FrSkyX.
|
||||
|
||||
Hubsan displays the battery voltage and TX RSSI.
|
||||
|
||||
DSM displays TX RSSI and full telemetry.
|
||||
|
||||
FrSky displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub).
|
||||
|
||||
FrSkyX displays basic telemetry (A1, A2 and RX RSSI).
|
||||
FrSkyX displays full telemetry (A1, A2, RX RSSI, TX RSSI and Hub).
|
||||
|
||||
### If used in PPM mode
|
||||
|
||||
Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FRSky hub format.
|
||||
Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FRSky hub format for Hubsan, FrSky, FrSkyX and DSM format for DSM2/X.
|
||||
|
||||
You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter (HC05/HC06) along with an app on your phone/tablet ([app example](https://play.google.com/store/apps/details?id=biz.onomato.frskydash&hl=fr)) to display telemetry information and setup alerts.
|
||||
|
||||
### If used in Serial mode
|
||||
Telemetry is built in for er9x and ersky9x TXs.
|
||||
Telemetry is built in for er9x and ersky9x TXs.
|
||||
|
||||
To enable telemetry on a Turnigy 9X or 9XR you need to modify your TX following one of the Frsky mod like this [one](http://blog.oscarliang.net/turnigy-9x-advance-mod/).
|
||||
|
||||
Note: DSM telemetry is not available on er9x due to a lack of flash space.
|
||||
|
||||
Enabling telemetry on a 9XR PRO and may be other TXs does not require any hardware modifications. The additional required serial pin is already available on the TX back module pins.
|
||||
|
||||
Once the TX is telemetry enabled, it just needs to be configured on the model (see er9x/ersky9x documentation).
|
||||
@@ -92,9 +96,11 @@ Once the TX is telemetry enabled, it just needs to be configured on the model (s
|
||||
##Protocols
|
||||
|
||||
###TX ID
|
||||
The multiprotocol TX module is using a 32bits ID generated randomly at first power up. This global ID is used by all protocols.
|
||||
The multiprotocol TX module is using a 32bits ID generated randomly at first power up. This global ID is used by nearly all protocols.
|
||||
There are little chances to get a duplicated ID.
|
||||
|
||||
For DSM2/X and Devo the CYRF6936 unique manufacturer ID is used.
|
||||
|
||||
It's possible to generate a new ID using bind button on the Hubsan protocol during power up.
|
||||
|
||||
###Bind
|
||||
@@ -124,7 +130,7 @@ Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module
|
||||
3|FRSKY|-|0|High|No|-41|CC2500
|
||||
4|HISKY|Hisky|0|High|No|0|NRF24L01
|
||||
5|V2X2|-|0|High|No|0|NRF24L01
|
||||
6|DSM2|DSM2|0|High|No|0|CYRF6936
|
||||
6|DSM2|DSM2|0|High|No|6|CYRF6936
|
||||
7|DEVO|-|0|High|No|0|CYRF6936
|
||||
8|YD717|YD717|0|High|No|0|NRF24L01
|
||||
9|KN|WLTOYS|0|High|No|0|NRF24L01
|
||||
@@ -141,37 +147,55 @@ Note:
|
||||
####Using serial input with er9x/ersky9x
|
||||
Serial is allowing access to all existing protocols & sub_protocols listed below.
|
||||
|
||||
Protocol|Sub_protocol|RF Module
|
||||
--------|------------|---------
|
||||
Flysky||A7105
|
||||
#####A7105 RF module
|
||||
Protocol|Sub_protocol
|
||||
--------|------------
|
||||
Flysky|
|
||||
|Flysky
|
||||
|V9x9
|
||||
|V6x6
|
||||
|V912
|
||||
Hubsan||A7105
|
||||
Frsky||CC2500
|
||||
Hisky||NRF24L01
|
||||
|Hisky
|
||||
|HK310
|
||||
V2x2||NRF24L01
|
||||
DSM2||CYRF6936
|
||||
Hubsan|
|
||||
|
||||
#####CC2500 RF module
|
||||
Protocol|Sub_protocol
|
||||
--------|------------
|
||||
FrSky|
|
||||
FrSkyX|
|
||||
|CH_16
|
||||
|CH_8
|
||||
SFHSS|
|
||||
|
||||
#####CYRF6936 RF module
|
||||
Protocol|Sub_protocol
|
||||
--------|------------
|
||||
DSM2|
|
||||
|DSM2
|
||||
|DSMX
|
||||
Devo||CYRF6936
|
||||
YD717||NRF24L01
|
||||
Devo|
|
||||
J6Pro|
|
||||
|
||||
#####NRF24L01 RF module
|
||||
Protocol|Sub_protocol
|
||||
--------|------------
|
||||
Hisky|
|
||||
|Hisky
|
||||
|HK310
|
||||
V2x2|
|
||||
YD717|
|
||||
|YD717
|
||||
|SKYWLKR
|
||||
|SYMAX4
|
||||
|XINXUN
|
||||
|NIHUI
|
||||
KN||NRF24L01
|
||||
KN|
|
||||
|WLTOYS
|
||||
|FEILUN
|
||||
SymaX||NRF24L01
|
||||
SymaX|
|
||||
|SYMAX
|
||||
|SYMAX5C
|
||||
SLT||NRF24L01
|
||||
CX10||NRF24L01
|
||||
SLT|
|
||||
CX10|
|
||||
|GREEN
|
||||
|BLUE
|
||||
|DM007
|
||||
@@ -180,307 +204,39 @@ CX10||NRF24L01
|
||||
|JC3015_2
|
||||
|MK33041
|
||||
|Q242
|
||||
CG023||NRF24L01
|
||||
CG023|
|
||||
|CG023
|
||||
|YD829
|
||||
|H8_3D
|
||||
Bayang||NRF24L01
|
||||
Bayang|
|
||||
FrskyX||CC2500
|
||||
ESky||NRF24L01
|
||||
MT99XX||NRF24L01
|
||||
ESky|
|
||||
MT99XX|
|
||||
|MT
|
||||
|H7
|
||||
|YZ
|
||||
MJXQ||NRF24L01
|
||||
|LS
|
||||
MJXQ|
|
||||
|WLH08
|
||||
|X600
|
||||
|X800
|
||||
|H26D
|
||||
Shenqi|
|
||||
FY326|
|
||||
FQ777|
|
||||
|
||||
Note:
|
||||
- The dial should be set to 0 for serial. Which means all protocol selection pins should be left unconnected.
|
||||
|
||||
###Protocol details
|
||||
Extended limits supported: -125%..+125% can be used and will be transmitted. Otherwise the default is -100%..+100% only.
|
||||
|
||||
Autobind protocol: you do not need to press the bind button at power up to bind, this is done automatically.
|
||||
|
||||
####BAYANG
|
||||
Models: EAchine H8(C) mini, BayangToys X6/X7/X9, JJRC JJ850, Floureon H101 ...
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
|
||||
---|---|---|---|---|---|---|---|---|----
|
||||
A|E|T|R|FLIP|RTH|PICTURE|VIDEO|HEADLESS|INVERTED
|
||||
|
||||
####CG023
|
||||
Models: EAchine CG023/CG031/3D X4
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol YD829
|
||||
Models: Attop YD-822/YD-829/YD-829C ...
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP||PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol H8_3D
|
||||
Models: EAchine H8 mini 3D, JJRC H20/H22
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP|LIGTH|OPT1|OPT2|CAL
|
||||
|
||||
JJRC H20: OPT1=Headless, OPT2=RTH
|
||||
|
||||
JJRC H22: OPT1=RTH, OPT2=180/360° flip mode
|
||||
|
||||
H8 3D: OPT1=RTH + headless, OPT2=180/360° flip mode
|
||||
|
||||
CAL: calibrate accelerometers
|
||||
|
||||
####CX10
|
||||
Extended limits supported
|
||||
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|RATE
|
||||
|
||||
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3
|
||||
|
||||
#####Sub_protocol GREEN
|
||||
Models: Cheerson CX-10 green pcb
|
||||
|
||||
Same channels assignement as above.
|
||||
|
||||
#####Sub_protocol BLUE
|
||||
Models: Cheerson CX-10 blue pcb & some newer red pcb, CX-10A, CX-10C, CX11, CX12, Floureon FX10, JJRC DHD D1
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|RATE|PICTURE|VIDEO
|
||||
|
||||
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 or headless for CX-10A
|
||||
|
||||
#####Sub_protocol DM007
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol Q282 and Q242
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---
|
||||
FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
|
||||
|
||||
Model: JXD 509 is using Q282 with CH12=Start/Stop motors
|
||||
|
||||
#####Sub_protocol JC3015_1
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO
|
||||
|
||||
#####Sub_protocol JC3015_2
|
||||
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
FLIP|MODE|LED|DFLIP
|
||||
|
||||
#####Sub_protocol MK33041
|
||||
|
||||
CH5|CH6|CH7|CH8|CH9|CH10
|
||||
---|---|---|---|---|---
|
||||
FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
|
||||
|
||||
####DEVO
|
||||
Extended limits supported
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
|
||||
####DSM2
|
||||
Extended limits supported
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|CH5|CH6|CH7|CH8
|
||||
|
||||
####ESKY
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|GYRO|PITCH
|
||||
|
||||
####FLYSKY
|
||||
Extended limits supported
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|CH5|CH6|CH7|CH8
|
||||
|
||||
#####Sub_protocol V9X9
|
||||
CH5|CH6|CH7|CH8
|
||||
---|---|---|---
|
||||
UNK|LIGHT|PICTURE|VIDEO
|
||||
|
||||
#####Sub_protocol V6X6
|
||||
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||
---|---|---|---|---|---|---|---
|
||||
FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
|
||||
|
||||
#####Sub_protocol V912
|
||||
CH5|CH6
|
||||
---|---
|
||||
BTMBTN|TOPBTN
|
||||
|
||||
####FRSKY
|
||||
Extended limits supported
|
||||
|
||||
Telemetry enabled for A0, A1, RSSI, TSSI and Hub
|
||||
|
||||
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
|
||||
####FRSKYX
|
||||
Extended limits supported
|
||||
|
||||
Telemetry enabled for A1 (RxBatt), A2, RSSI
|
||||
|
||||
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
|
||||
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
|
||||
|
||||
####HISKY
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
A|E|T|R|GEAR|PITCH|GYRO|CH8
|
||||
|
||||
GYRO: -100%=6G, +100%=3G
|
||||
|
||||
#####HK310
|
||||
Models: RX HK-3000, HK3100 and XY3000 (TX are HK-300, HK-310 and TL-3C)
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
|
||||
---|---|---|---|---|---|---|---
|
||||
|||T|R|AUX|T_FSAFE|R_FSAFE|AUX_FSAFE
|
||||
|
||||
####HUBSAN
|
||||
Models: Hubsan H102D, H107/L/C/D and Hubsan H107P/C+/D+
|
||||
|
||||
Autobind protocol
|
||||
|
||||
Telemetry enabled for battery voltage and TX RSSI
|
||||
|
||||
Option=vTX frequency (H107D) 5645 - 5900 MHz
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
####KN
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
|
||||
---|---|---|---|---|---|---|---|---|----|----
|
||||
A|E|T|R|DR|THOLD|IDLEUP|GYRO|Ttrim|Atrim|Etrim
|
||||
|
||||
Dual Rate: +100%=full range, Throttle Hold: +100%=hold, Idle Up: +100%=3D, GYRO: -100%=6G, +100%=3G
|
||||
|
||||
#####Sub_protocol WLTOYS
|
||||
#####Sub_protocol FEILUN
|
||||
Same channels assignement as above.
|
||||
|
||||
####MJXQ
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13
|
||||
---|---|---|---|---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|AUTOFLIP|PAN|TILT
|
||||
|
||||
#####Sub_protocol WLH08
|
||||
#####Sub_protocol X600
|
||||
#####Sub_protocol X800
|
||||
#####Sub_protocol H26D
|
||||
|
||||
####MT99XX
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol MT
|
||||
Models: MT99xx
|
||||
#####Sub_protocol H7
|
||||
Models: Eachine H7
|
||||
#####Sub_protocol YZ
|
||||
Models: Yi Zhan i6S
|
||||
|
||||
####SLT
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6
|
||||
---|---|---|---|---|---
|
||||
A|E|T|R|GEAR|PITCH
|
||||
|
||||
####Symax
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP||PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol SYMAX
|
||||
Models: Syma X5C-1/X11/X11C/X12
|
||||
|
||||
#####Sub_protocol SYMAX5C
|
||||
Model: Syma X5C (original) and X2
|
||||
|
||||
####V2X2
|
||||
Models: WLToys V202/252/272, JXD 385/388, JJRC H6C, Yizhan Tarantula X6 ...
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
|
||||
---|---|---|---|---|---|---|---|---|----|----
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|MAG_CAL_X|MAG_CAL_Y
|
||||
|
||||
PICTURE: also automatic Missile Launcher and Hoist in one direction
|
||||
|
||||
VIDEO: also Sprayer, Bubbler, Missile Launcher(1), and Hoist in the other dir
|
||||
|
||||
####YD717
|
||||
Autobind protocol
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
||||
---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
|
||||
|
||||
#####Sub_protocol YD717
|
||||
#####Sub_protocol SKYWLKR
|
||||
#####Sub_protocol SYMAX4
|
||||
#####Sub_protocol XINXUN
|
||||
#####Sub_protocol NIHUI
|
||||
Same channels assignement as above.
|
||||
###Protocols details
|
||||
**Check the [Protocols_Details.md](./Protocols_Details.md) file for a detailed description of every protocols with channels assignements.**
|
||||
|
||||
##Hardware
|
||||
|
||||
###RF modules
|
||||
Up to 4 RF modules can be installed:
|
||||
- [A7105](http://www.banggood.com/XL7105-D03-A7105-Modification-Module-Support-Deviation-Galee-Flysky-p-922603.html) for Flysky, Hubsan
|
||||
- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for Frsky
|
||||
- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for FrSky, FrSkyX and SFHSS
|
||||
- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM2, DSMX, DEVO, Walkera
|
||||
- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols
|
||||
|
||||
@@ -490,26 +246,51 @@ You also need some [antennas](http://www.banggood.com/2_4GHz-3dBi-RP-SMA-Connect
|
||||
|
||||
###Board
|
||||
The main program is running on an ATMEGA328p running @16MHz and 3.3V.
|
||||
An [Arduino pro mini 16Mhz/5V](http://www.banggood.com/Wholesale-New-Ver-Pro-Mini-ATMEGA328-328p-5V-16MHz-Arduino-Compatible-Nano-Size-p-68534.html) powered at 3.3V (yes it works) can be used to build your own Multimodule.
|
||||
An [Arduino pro mini 16Mhz/5V](http://www.banggood.com/Wholesale-New-Ver-Pro-Mini-ATMEGA328-328p-5V-16MHz-Arduino-Compatible-Nano-Size-p-68534.html) powered at 3.3V (yes it works) can be used to build your own Multimodule. An Arduino Mini based on Atmega328p can also be used.
|
||||
|
||||
Using stripboard:
|
||||
####Using stripboard:
|
||||
|
||||

|
||||

|
||||
|
||||
Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621):
|
||||
####Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621):
|
||||
|
||||

|
||||

|
||||
|
||||
or build your own board using [SMD components](http://www.rcgroups.com/forums/showpost.php?p=31064232&postcount=1020) and an [associated PCB](https://oshpark.com/shared_projects/MaGYDg0y):
|
||||
####Build your own board using [SMD components](http://www.rcgroups.com/forums/showpost.php?p=31064232&postcount=1020) and an [associated PCB v2.3c](https://oshpark.com/shared_projects/MaGYDg0y):
|
||||
|
||||

|
||||

|
||||
 
|
||||
|
||||
**If you build this PCB v2.3c and want to enable serial mode for er9x/ersky9x, you have to do [this mod](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8667856-242-multi.jpg).**
|
||||
If you build this PCB v2.3c and want to enable serial mode for er9x/ersky9x, you have to do [this mod](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8667856-242-multi.jpg).
|
||||
|
||||
**[New PCB v2.3d!](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/tree/master/PCB%20v2.3d) available**
|
||||
|
||||
Repository includes Kicad files of schematic and pcb. This is a variant of the Multipro V2.3c circuit design. It is basicly the same as the 2.3c board as far as component placement goes. What's changed is the added resistors for the serial protocol and also
|
||||
the addition of solder jumpers on the bottom of the board for the various options to connect the TX, RX, and PPM
|
||||
lines through them.
|
||||
|
||||

|
||||

|
||||
|
||||
[OSH Park link](https://oshpark.com/shared_projects/Ztus1ah8) if you want to order.
|
||||
|
||||
####Buy a ready to use and complete Multi module
|
||||

|
||||
|
||||
This module can be purchased [here](http://www.banggood.com/2_4G-CC2500-A7105-Flysky-Frsky-Devo-DSM2-Multiprotocol-TX-Module-With-Antenna-p-1048377.html). All the 4 RF modules are already implemented A7105, NRF24L01, CC2500 and CYRF6936. The board is also equiped with an antenna switcher which means only one antenna for all.
|
||||
|
||||
**It is highly recommended to update the firmware** of this board as it is distributed with a really old and bugged one. For this you have to solder a 6 pin header (top left) and use an USBASP like explained [below](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#upload-the-code-using-isp-in-system-programming).
|
||||
|
||||
If you want to enable serial mode for er9x/ersky9x/Taranis/... and depending on your board revision, you have to do one of these modifications:
|
||||
- 1st revision, add 2 resistors as shown here: 
|
||||
- 2nd revision, solder pads together as shown:
|
||||
|
||||
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206217-177-IMG_5790.jpg" width="350">
|
||||
|
||||
Note: if you have the 1st board revision (check pictures above), sometime bind occures at power up even without pressing the bind button or not having an autobind protocol. To solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
|
||||
|
||||
###Schematic
|
||||

|
||||
@@ -519,19 +300,33 @@ Notes:
|
||||
- For serial, the dial switch is not needed and the bind button optionnal
|
||||
|
||||
###Radio integration
|
||||
You can 3D print your box (details [here](http://www.rcgroups.com/forums/showpost.php?p=33294140&postcount=2034)):
|
||||
If you build your own version of the board you can 3D print this case (details [here](http://www.rcgroups.com/forums/showpost.php?p=33294140&postcount=2034)):
|
||||
|
||||

|
||||

|
||||
|
||||
If you have the Banggood ready to use board you can 3D print this case (details [here](http://www.rcgroups.com/forums/showpost.php?p=35349049&postcount=3)):
|
||||
|
||||
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206211-97-Screen%20Shot%202016-07-27%20at%2011.02.35%20am.png" width="200">
|
||||
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206411-90-IMG_5793.jpeg" width="200">
|
||||
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206445-131-IMG_5796.jpeg" width="200">
|
||||
|
||||
##Compilation and programmation
|
||||
|
||||
###Toolchain
|
||||
Supported Arduino version is [1.6.7](https://www.arduino.cc/download_handler.php?f=/arduino-1.6.7-windows.exe). Make sure to select "Arduino Pro or Pro Mini, ATmega328 (5V,16MHz)" before compiling.
|
||||
Multiprotocol source can be compiled using the Arduino IDE.
|
||||
|
||||
Compilation of the code posted here works. So if it doesn't for you this is a problem with your setup, please double check everything before asking.
|
||||
The currently supported Arduino version is [1.6.10](https://www.arduino.cc/download_handler.php?f=/arduino-1.6.10-windows.exe).
|
||||
|
||||
_Config.h file can be modified to compile with/without some protocols, change protocols/sub_protocols/settings associated with dial for PPM input, different channel orders, different channels timing, Telemetry or not, ...
|
||||
Download the [zip file](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/archive/master.zip) of this repository, unzip it in a folder, navigate to the Multiprotocol directory and then click on Multiprotocol.ino. The Arduino environment will appear and the Multiprotocol project will be loaded.
|
||||
|
||||
**[_Config.h file](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Multiprotocol/_Config.h) must be modified** to select which protocols will be available, change protocols/sub_protocols/settings associated with dial for PPM input, different TX channel orders and timing, Telemetry or not, ...
|
||||
This is mandatory since all available protocols will not fit in the ATmega328. You need to pick and choose what you want.
|
||||
|
||||
Notes:
|
||||
- Make sure to select "Arduino Pro or Pro Mini, ATmega328 (5V,16MHz)" before compiling.
|
||||
- Compilation of the code posted here works. So if it doesn't for you this is a problem with your setup, please double check everything before asking.
|
||||
- If you want to reduce the code size even further, you can modify the file platform.txt located in "C:\Program Files (x86)\Arduino\hardware\arduino\avr". Set the line "compiler.c.elf.extra_flags=" to "compiler.c.elf.extra_flags=-Wl,--relax".
|
||||
|
||||
###Upload the code using ISP (In System Programming)
|
||||
It is recommended to use an external programmer like [USBASP](http://www.banggood.com/USBASP-USBISP-3_3-5V-AVR-Downloader-Programmer-With-ATMEGA8-ATMEGA128-p-934425.html) to upload the code in the Atmega328. The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages.
|
||||
@@ -565,9 +360,9 @@ This will make sure your ATMEGA328 is well configured and the global TX ID is no
|
||||
|
||||
###LED status
|
||||
- off: program not running or a protocol selected with the associated module not installed.
|
||||
- flash: invalid protocol selected (excluded from compilation or invalid protocol number)
|
||||
- slow blink: serial has been selected but no valid signal has been seen on the RX pin.
|
||||
- fast blink: bind in progress.
|
||||
- flash(on=0.1s,off=1s): invalid protocol selected (excluded from compilation or invalid protocol number)
|
||||
- slow blink(on=0.5s,off=0.5s): serial has been selected but no valid signal has been seen on the RX pin.
|
||||
- fast blink(on=0.1s,off=0.1s): bind in progress.
|
||||
- on: normal operation.
|
||||
|
||||
###Protocol selection
|
||||
@@ -576,7 +371,7 @@ This will make sure your ATMEGA328 is well configured and the global TX ID is no
|
||||
- Connect 1 to 4 of the selection protocol pins to GND.
|
||||
|
||||
####Input Mode - Serial
|
||||
- Make sure you have done the mods to the v2.3c PCB by adding the 2.2k and 330 ohm resistors as indicated in the [Board section] (https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#board).
|
||||
- Make sure you have done the mods to the v2.3c PCB by adding the 2.2k and 470 ohm resistors as indicated in the [Board section] (https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#board).
|
||||
- Leave all 4 selection pins unconnected.
|
||||
|
||||
###Bind
|
||||
|
||||
Reference in New Issue
Block a user