Merge remote-tracking branch 'refs/remotes/pascallanger/master'

# Conflicts:
#	Multiprotocol/CX10_nrf24l01.ino
#	Multiprotocol/CYRF6936_SPI.ino
#	Multiprotocol/DSM2_cyrf6936.ino
#	Multiprotocol/Devo_cyrf6936.ino
#	Multiprotocol/FY326_nrf24l01.ino
#	Multiprotocol/FlySky_a7105.ino
#	Multiprotocol/FrSkyX_cc2500.ino
#	Multiprotocol/FrSky_cc2500.ino
#	Multiprotocol/KN_nrf24l01.ino
#	Multiprotocol/MJXQ_nrf24l01.ino
#	Multiprotocol/MT99xx_nrf24l01.ino
#	Multiprotocol/Multiprotocol.ino
#	Multiprotocol/NRF24l01_SPI.ino
#	Multiprotocol/SHENQI_nrf24l01.ino
#	Multiprotocol/Telemetry.ino
#	Multiprotocol/YD717_nrf24l01.ino
#	Multiprotocol/_Config.h
#	Multiprotocol/iface_nrf24l01.h
#	Multiprotocol/multiprotocol.h
#	README.md
This commit is contained in:
tipouic 2016-09-30 13:16:12 +02:00
commit 89bea4c38b
103 changed files with 16583 additions and 918 deletions

View File

@ -12,23 +12,20 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
//-------------------------------
//-------------------------------
//A7105 SPI routines
//-------------------------------
//-------------------------------
/********************/
/** A7105 routines **/
/********************/
#include "iface_a7105.h"
void A7105_WriteData(uint8_t len, uint8_t channel)
{
uint8_t i;
CS_off;
A7105_Write(A7105_RST_WRPTR);
A7105_Write(0x05);
A7105_CSN_off;
SPI_Write(A7105_RST_WRPTR);
SPI_Write(0x05);
for (i = 0; i < len; i++)
A7105_Write(packet[i]);
CS_on;
SPI_Write(packet[i]);
A7105_CSN_on;
A7105_WriteReg(0x0F, channel);
A7105_Strobe(A7105_TX);
}
@ -36,67 +33,30 @@ void A7105_WriteData(uint8_t len, uint8_t channel)
void A7105_ReadData() {
uint8_t i;
A7105_Strobe(0xF0); //A7105_RST_RDPTR
CS_off;
A7105_Write(0x45);
A7105_CSN_off;
SPI_Write(0x45);
for (i=0;i<16;i++)
packet[i]=A7105_Read();
CS_on;
packet[i]=SPI_SDIO_Read();
A7105_CSN_on;
}
void A7105_WriteReg(uint8_t address, uint8_t data) {
CS_off;
A7105_Write(address);
A7105_CSN_off;
SPI_Write(address);
NOP();
A7105_Write(data);
CS_on;
SPI_Write(data);
A7105_CSN_on;
}
uint8_t A7105_ReadReg(uint8_t address) {
uint8_t result;
CS_off;
A7105_Write(address |=0x40); //bit 6 =1 for reading
result = A7105_Read();
CS_on;
A7105_CSN_off;
SPI_Write(address |=0x40); //bit 6 =1 for reading
result = SPI_SDIO_Read();
A7105_CSN_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 i;
SDI_SET_INPUT;
for(i=0;i<8;i++) {
if(SDI_1) ///if SDIO =1
result=(result<<1)|0x01;
else
result=result<<1;
SCK_on;
NOP();
SCK_off;
NOP();
}
SDI_SET_OUTPUT;
return result;
}
//------------------------
void A7105_SetTxRxMode(uint8_t mode)
{
@ -121,9 +81,8 @@ uint8_t A7105_Reset()
{
uint8_t result;
delay(10); //wait 10ms for A7105 wakeup
A7105_WriteReg(0x00, 0x00);
delay(1000);
delayMilliseconds(1);
A7105_SetTxRxMode(TXRX_OFF); //Set both GPIO as output and low
result=A7105_ReadReg(0x10) == 0x9E; //check if is reset.
A7105_Strobe(A7105_STANDBY);
@ -131,13 +90,13 @@ 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
CS_on;
A7105_CSN_off;
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
A7105_CSN_on;
}
/*
@ -175,13 +134,17 @@ void A7105_SetPower()
power=IS_POWER_FLAG_on?A7105_HIGH_POWER:A7105_LOW_POWER;
if(IS_RANGE_FLAG_on)
power=A7105_RANGE_POWER;
A7105_WriteReg(0x28, power);
if(prev_power != power)
{
A7105_WriteReg(0x28, power);
prev_power=power;
}
}
void A7105_Strobe(uint8_t address) {
CS_off;
A7105_Write(address);
CS_on;
A7105_CSN_off;
SPI_Write(address);
A7105_CSN_on;
}
const uint8_t PROGMEM HUBSAN_A7105_regs[] = {

View File

@ -0,0 +1,179 @@
/*
This project is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Multiprotocol is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(ASSAN_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define ASSAN_PACKET_SIZE 20
#define ASSAN_RF_BIND_CHANNEL 0x03
#define ASSAN_ADDRESS_LENGTH 4
enum {
ASSAN_BIND0=0,
ASSAN_BIND1,
ASSAN_BIND2,
ASSAN_DATA0,
ASSAN_DATA1,
ASSAN_DATA2,
ASSAN_DATA3,
ASSAN_DATA4,
ASSAN_DATA5
};
void ASSAN_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4 bytes rx/tx address
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x80\x80\x80\xB8", ASSAN_ADDRESS_LENGTH); // Bind address
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x80\x80\x80\xB8", ASSAN_ADDRESS_LENGTH); // Bind address
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, ASSAN_PACKET_SIZE);
NRF24L01_SetPower();
}
void ASSAN_send_packet()
{
uint16_t temp;
for(uint8_t i=0;i<10;i++)
{
temp=Servo_data[i]<<3;
packet[2*i]=temp>>8;
packet[2*i+1]=temp;
}
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, ASSAN_PACKET_SIZE);
}
uint16_t ASSAN_callback()
{
switch (phase)
{
// Bind
case ASSAN_BIND0:
//Config RX @1M
NRF24L01_WriteReg(NRF24L01_05_RF_CH, ASSAN_RF_BIND_CHANNEL);
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetTxRxMode(RX_EN);
phase++;
case ASSAN_BIND1:
//Wait for receiver to send the frames
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & _BV(NRF24L01_07_RX_DR))
{ //Something has been received
NRF24L01_ReadPayload(packet, ASSAN_PACKET_SIZE);
if(packet[19]==0x13)
{ //Last frame received
phase++;
//Switch to TX
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
//Prepare bind packet
memset(packet,0x05,ASSAN_PACKET_SIZE-5);
packet[15]=0x99;
for(uint8_t i=0;i<4;i++)
packet[16+i]=packet[23-i];
packet_count=0;
delayMilliseconds(260);
return 10000; // Wait 270ms in total...
}
}
return 1000;
case ASSAN_BIND2:
// Send 20 packets
packet_count++;
if(packet_count==20)
packet[15]=0x13; // different value for last packet
NRF24L01_WritePayload(packet, ASSAN_PACKET_SIZE);
if(packet_count==20)
{
phase++;
delayMilliseconds(2165);
}
return 22520;
// Normal operation
case ASSAN_DATA0:
// Bind Done
BIND_DONE;
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250Kbps
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
case ASSAN_DATA1:
case ASSAN_DATA4:
// Change ID and RF channel
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR,packet+20+4*hopping_frequency_no, ASSAN_ADDRESS_LENGTH);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
hopping_frequency_no^=0x01;
NRF24L01_SetPower();
phase=ASSAN_DATA2;
return 2000;
case ASSAN_DATA2:
case ASSAN_DATA3:
ASSAN_send_packet();
phase++; // DATA 3 or 4
return 5000;
}
return 0;
}
static void __attribute__((unused)) ASSAN_initialize_txid()
{
/* //Renaud TXID with Freq=36 and alternate Freq 67 or 68 or 69 or 70 or 71 or 73 or 74 or 75 or 78 and may be more...
packet[23]=0x22;
packet[22]=0x37;
packet[21]=0xFA;
packet[20]=0x53; */
// Using packet[20..23] to store the ID1 and packet[24..27] to store the ID2
uint8_t freq=0,freq2;
for(uint8_t i=0;i<4;i++)
{
uint8_t temp=rx_tx_addr[0];
packet[i+20]=temp;
packet[i+24]=temp+1;
freq+=temp;
}
// Main frequency
freq=((freq%25)+2)<<1;
if(freq&0x02) freq|=0x01;
hopping_frequency[0]=freq;
// Alternate frequency has some random
do
{
freq2=random(0xfefefefe)%9;
freq2+=freq*2-5;
}
while( (freq2>118) || (freq2<freq+1) || (freq2==2*freq) );
hopping_frequency[1]=freq2; // Add some random to the second channel
}
uint16_t initASSAN()
{
ASSAN_initialize_txid();
ASSAN_init();
hopping_frequency_no = 0;
if(IS_AUTOBIND_FLAG_on)
phase=ASSAN_BIND0;
else
phase=ASSAN_DATA0;
return 1000;
}
#endif

133
Multiprotocol/Arduino.ino Normal file
View File

@ -0,0 +1,133 @@
/*
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/>.
*/
/************************************/
/** 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 delayMilliseconds(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;
}
}
}
/* Important notes:
- Max value is 16000µs
- delay is not accurate due to interrupts happening */
void delayMicroseconds(unsigned int us)
{
if (--us == 0)
return;
us <<= 2; // * 4
us -= 2; // - 2
#ifdef XMEGA
__asm__ __volatile__ (
"1: sbiw %0,1" "\n\t" // 2 cycles
"nop \n"
"nop \n"
"nop \n"
"nop \n"
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
);
#else
__asm__ __volatile__ (
"1: sbiw %0,1" "\n\t" // 2 cycles
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
);
#endif
}
#ifndef XMEGA
void init()
{
// this needs to be called before setup() or some functions won't work there
sei();
}
#endif //XMEGA

View File

@ -99,7 +99,7 @@ static void __attribute__((unused)) BAYANG_send_packet(uint8_t bind)
// Power on, TX mode, 2byte CRC
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_05_RF_CH, bind ? BAYANG_RF_BIND_CHANNEL:hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no%=BAYANG_RF_NUM_CHANNELS;

View File

@ -19,125 +19,107 @@
//-------------------------------
#include "iface_cc2500.h"
void cc2500_readFifo(uint8_t *dpbuffer, uint8_t len)
{
ReadRegisterMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
}
//----------------------
static void ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
//----------------------------
void CC2500_WriteReg(uint8_t address, uint8_t data)
{
CC25_CSN_off;
cc2500_spi_write(address);
SPI_Write(address);
NOP();
SPI_Write(data);
CC25_CSN_on;
}
//----------------------
static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
{
CC25_CSN_off;
SPI_Write(CC2500_READ_BURST | address);
for(uint8_t i = 0; i < length; i++)
data[i] = cc2500_spi_read();
data[i] = SPI_Read();
CC25_CSN_on;
}
//--------------------------------------------
static uint8_t CC2500_ReadReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
SPI_Write(CC2500_READ_SINGLE | address);
result = SPI_Read();
CC25_CSN_on;
return(result);
}
//------------------------
void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len)
{
CC2500_ReadRegisterMulti(CC2500_3F_RXFIFO, dpbuffer, len);
}
//*********************************************
void CC2500_Strobe(uint8_t state)
{
CC25_CSN_off;
SPI_Write(state);
CC25_CSN_on;
}
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);
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, dpbuffer, len);
cc2500_strobe(CC2500_STX);//0x35
CC2500_Strobe(CC2500_STX);
}
//--------------------------------------
static void cc2500_spi_write(uint8_t command) {
uint8_t n=8;
SCK_off;//SCK start low
SDI_off;
while(n--)
{
if(command&0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
//----------------------------
void cc2500_writeReg(uint8_t address, uint8_t data) {//same as 7105
CC25_CSN_off;
cc2500_spi_write(address);
NOP();
cc2500_spi_write(data);
CC25_CSN_on;
}
static uint8_t cc2500_spi_read(void)
void CC2500_SetTxRxMode(uint8_t mode)
{
uint8_t result;
uint8_t i;
result=0;
for(i=0;i<8;i++)
{
if(SDO_1) ///
result=(result<<1)|0x01;
if(mode == TX_EN)
{//from deviation firmware
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);
}
else
result=result<<1;
SCK_on;
NOP();
SCK_off;
NOP();
}
return result;
}
//--------------------------------------------
static uint8_t cc2500_readReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
address |=0x80; //bit 7 =1 for reading
cc2500_spi_write(address);
result = cc2500_spi_read();
CC25_CSN_on;
return(result);
}
//------------------------
void cc2500_strobe(uint8_t address)
{
CC25_CSN_off;
cc2500_spi_write(address);
CC25_CSN_on;
{
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
}
}
//------------------------
/*static void cc2500_resetChip(void)
{
// 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);
delayMilliseconds(1);
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 +136,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 +146,10 @@ 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);
if(prev_power != power)
{
CC2500_WriteReg(CC2500_3E_PATABLE, power);
prev_power=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);
}
else
if (mode == RX_EN)
{
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);
}
}

View File

@ -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
@ -171,7 +171,7 @@ static void __attribute__((unused)) CG023_send_packet(uint8_t bind)
// Power on, TX mode, 2byte CRC
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
if (bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, sub_protocol==H8_3D?hopping_frequency[0]:CG023_RF_BIND_CHANNEL);
else

View File

@ -25,7 +25,10 @@
#define Q282_PACKET_SIZE 21
#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec
#define CX10A_PACKET_PERIOD 6000
<<<<<<< HEAD
#define CX10A_BIND_COUNT 400 // 2 seconds
=======
>>>>>>> refs/remotes/pascallanger/master
#define CX10_INITIAL_WAIT 500
@ -149,7 +152,7 @@ static void __attribute__((unused)) CX10_Write_Packet(uint8_t bind)
// Power on, TX mode, 2byte CRC
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
if (bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, CX10_RF_BIND_CHANNEL);
else
@ -182,7 +185,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,6 +201,7 @@ uint16_t CX10_callback() {
}
break;
case CX10_BIND2:
<<<<<<< HEAD
bind_counter--;
if(bind_counter==0)
{ // Needed for some CX-10A to properly finish the bind
@ -204,27 +209,41 @@ uint16_t CX10_callback() {
bind_counter=CX10A_BIND_COUNT;
}
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
=======
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & _BV(NRF24L01_07_RX_DR))
>>>>>>> refs/remotes/pascallanger/master
{ // RX fifo data ready
XN297_ReadPayload(packet, packet_length);
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
if(packet[9] == 1)
{
<<<<<<< HEAD
phase = CX10_BIND1;
bind_counter=0;
=======
BIND_DONE;
phase = CX10_DATA;
>>>>>>> refs/remotes/pascallanger/master
}
}
else
{
// switch to TX mode
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushTx();
NRF24L01_SetTxRxMode(TX_EN);
CX10_Write_Packet(1);
<<<<<<< HEAD
delayMicroseconds(400); // 300µs in deviation but not working so using 400µs instead
=======
delayMicroseconds(400);
>>>>>>> refs/remotes/pascallanger/master
// switch to RX mode
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushRx();
NRF24L01_SetTxRxMode(RX_EN);
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) | BV(NRF24L01_00_PRIM_RX));
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP) | _BV(NRF24L01_00_PRIM_RX));
}
break;
case CX10_DATA:
@ -269,7 +288,10 @@ uint16_t initCX10(void)
packet_period = CX10A_PACKET_PERIOD;
phase = CX10_BIND2;
<<<<<<< HEAD
bind_counter=CX10A_BIND_COUNT;
=======
>>>>>>> refs/remotes/pascallanger/master
for(uint8_t i=0; i<4; i++)
packet[5+i] = 0xff; // clear aircraft id

View File

@ -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;
}
@ -94,17 +58,19 @@ uint8_t CYRF_ReadRegister(uint8_t address)
uint8_t CYRF_Reset()
{
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x01);//software reset
_delay_us(200);//
// RS_HI;
// _delay_us(100);
// RS_LO;
// _delay_us(100);
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0); //Enable XOUT as GPIO
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04); //Enable PACTL as GPIO
#ifdef CYRF_RST_HI
CYRF_RST_HI; //Hardware reset
delayMicroseconds(100);
CYRF_RST_LO;
delayMicroseconds(100);
#endif
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x01); //Software reset
delayMicroseconds(200);
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);
//Verify the CYRD chip is responding
return (CYRF_ReadRegister(CYRF_10_FRAMING_CFG) == 0xa5);//return if reset
//Verify the CYRF chip is responding
return (CYRF_ReadRegister(CYRF_10_FRAMING_CFG) == 0xa5);
}
/*
@ -136,9 +102,15 @@ void CYRF_SetTxRxMode(uint8_t mode)
//Set the post tx/rx state
CYRF_WriteRegister(CYRF_0F_XACT_CFG, mode == TX_EN ? 0x28 : 0x2C); // 4=IDLE, 8=TX, C=RX
if(mode == TX_EN)
#ifdef DSM_BLUE
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL,0x20); // XOUT=1, PACTL=0
else
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL,0x80); // XOUT=0, PACTL=1
#else
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL,0x80); // XOUT=1, PACTL=0
else
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL,0x20); // XOUT=0, PACTL=1
#endif
}
}
/*
@ -164,7 +136,12 @@ void CYRF_SetPower(uint8_t val)
power=IS_POWER_FLAG_on?CYRF_HIGH_POWER:CYRF_LOW_POWER;
if(IS_RANGE_FLAG_on)
power=CYRF_RANGE_POWER;
CYRF_WriteRegister(CYRF_03_TX_CFG, val | power);
power|=val;
if(prev_power != power)
{
CYRF_WriteRegister(CYRF_03_TX_CFG,power);
prev_power=power;
}
}
/*
@ -196,10 +173,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,10 +192,18 @@ static void CYRF_StartReceive()
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, 0x10);
}
*/
<<<<<<< HEAD
static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
=======
void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
>>>>>>> refs/remotes/pascallanger/master
{
ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
}
<<<<<<< HEAD
=======
>>>>>>> refs/remotes/pascallanger/master
static void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len)
{
CYRF_WriteRegister(CYRF_01_TX_LENGTH, len);
@ -261,13 +246,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);
delayMilliseconds(1);
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);
}
@ -286,3 +271,37 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
}
CYRF_SetTxRxMode(TX_EN);
}
#if defined(DEVO_CYRF6936_INO) || defined(J6PRO_CYRF6936_INO)
const uint8_t PROGMEM DEVO_j6pro_sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
{0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91},
{0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F},
{0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A},
{0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50},
{0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44},
{0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46},
{0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C},
{0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74},
{0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49},
{0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72},
#if defined(J6PRO_CYRF6936_INO)
{0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17},
{0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table
{0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above,
{0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped
{0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50},
{0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44},
{0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46},
{0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C},
{0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74},
#endif
};
#endif
static void __attribute__((unused)) CYRF_PROGMEM_ConfigSOPCode(const uint8_t *data)
{
uint8_t code[8];
for(uint8_t i=0;i<8;i++)
code[i]=pgm_read_byte_near(&data[i]);
CYRF_ConfigSOPCode(code);
}

79
Multiprotocol/Convert.ino Normal file
View File

@ -0,0 +1,79 @@
/*
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/>.
*/
/************************/
/** Convert routines **/
/************************/
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)
{
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,0,255));
}
// Channel value is converted to 8bit values to provided values scale
uint8_t convert_channel_8b_scale(uint8_t num,uint8_t min,uint8_t max)
{
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,min,max));
}
// Channel value is converted sign + magnitude 8bit values
uint8_t convert_channel_s8b(uint8_t num)
{
uint8_t ch;
ch = convert_channel_8b(num);
return (ch < 128 ? 127-ch : ch);
}
// Channel value is converted to 10bit values
uint16_t convert_channel_10b(uint8_t num)
{
return (uint16_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,1,1023));
}
// Channel value is multiplied by 1.5
uint16_t convert_channel_frsky(uint8_t num)
{
return Servo_data[num] + Servo_data[num]/2;
}
// Channel value is converted for HK310
void convert_channel_HK310(uint8_t num, uint8_t *low, uint8_t *high)
{
uint16_t temp=0xFFFF-(4*Servo_data[num])/3;
*low=(uint8_t)(temp&0xFF);
*high=(uint8_t)(temp>>8);
}
// Channel value is limited to PPM_100
uint16_t limit_channel_100(uint8_t ch)
{
if(Servo_data[ch]>servo_max_100)
return servo_max_100;
else
if (Servo_data[ch]<servo_min_100)
return servo_min_100;
return Servo_data[ch];
}

View File

@ -0,0 +1,577 @@
/*
This project is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Multiprotocol is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(DSM_CYRF6936_INO)
#include "iface_cyrf6936.h"
#define DSM_BIND_CHANNEL 0x0d //13 This can be any odd channel
//During binding we will send BIND_COUNT/2 packets
//One packet each 10msec
#define DSM_BIND_COUNT 300
enum {
DSM_BIND_WRITE=0,
DSM_BIND_CHECK,
DSM_BIND_READ,
DSM_CHANSEL,
DSM_CH1_WRITE_A,
DSM_CH1_CHECK_A,
DSM_CH2_WRITE_A,
DSM_CH2_CHECK_A,
DSM_CH2_READ_A,
DSM_CH1_WRITE_B,
DSM_CH1_CHECK_B,
DSM_CH2_WRITE_B,
DSM_CH2_CHECK_B,
DSM_CH2_READ_B,
};
//
uint8_t sop_col;
uint8_t DSM_num_ch=0;
uint8_t ch_map[14];
const uint8_t PROGMEM ch_map_progmem[][14] = {
//22+11ms for 4..7 channels
{1, 0, 2, 3, 0xff, 0xff, 0xff, 1, 0, 2, 3, 0xff, 0xff, 0xff}, //4ch - Guess
{1, 0, 2, 3, 4, 0xff, 0xff, 1, 0, 2, 3, 4, 0xff, 0xff}, //5ch - Guess
{1, 5, 2, 3, 0, 4, 0xff, 1, 5, 2, 3, 0, 4, 0xff}, //6ch - HP6DSM
{1, 5, 2, 4, 3, 6, 0, 1, 5, 2, 4, 3, 6, 0 }, //7ch - DX6i
//22ms for 8..12 channels
{1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 0xff, 0xff, 0xff, 0xff}, //8ch - DX8/DX7
{1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 8, 0xff, 0xff, 0xff}, //9ch - Guess
{1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 8, 9, 0xff, 0xff}, //10ch - Guess
{1, 5, 2, 3, 6, 10, 0xff, 4, 0, 7, 8, 9, 0xff, 0xff}, //11ch - Guess
{1, 5, 2, 4, 6, 10, 0xff, 0, 7, 3, 8, 9 , 11 , 0xff}, //12ch - DX18
//11ms for 8..12 channels
{1, 5, 2, 3, 6, 7, 0xff, 1, 5, 2, 4, 0, 0xff, 0xff}, //8ch - DX7
{1, 5, 2, 3, 6, 7, 0xff, 1, 5, 2, 4, 0, 8, 0xff}, //9ch - Guess
{1, 5, 2, 3, 4, 8, 9, 1, 5, 2, 3, 0, 7, 6 }, //10ch - DX18
};
const uint8_t PROGMEM pncodes[5][8][8] = {
/* Note these are in order transmitted (LSB 1st) */
{ /* Row 0 */
/* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8},
/* Col 1 */ {0x88, 0x17, 0x13, 0x3B, 0x2D, 0xBF, 0x06, 0xD6},
/* Col 2 */ {0xF1, 0x94, 0x30, 0x21, 0xA1, 0x1C, 0x88, 0xA9},
/* Col 3 */ {0xD0, 0xD2, 0x8E, 0xBC, 0x82, 0x2F, 0xE3, 0xB4},
/* Col 4 */ {0x8C, 0xFA, 0x47, 0x9B, 0x83, 0xA5, 0x66, 0xD0},
/* Col 5 */ {0x07, 0xBD, 0x9F, 0x26, 0xC8, 0x31, 0x0F, 0xB8},
/* Col 6 */ {0xEF, 0x03, 0x95, 0x89, 0xB4, 0x71, 0x61, 0x9D},
/* Col 7 */ {0x40, 0xBA, 0x97, 0xD5, 0x86, 0x4F, 0xCC, 0xD1},
/* Col 8 {0xD7, 0xA1, 0x54, 0xB1, 0x5E, 0x89, 0xAE, 0x86}*/
},
{ /* Row 1 */
/* Col 0 */ {0x83, 0xF7, 0xA8, 0x2D, 0x7A, 0x44, 0x64, 0xD3},
/* Col 1 */ {0x3F, 0x2C, 0x4E, 0xAA, 0x71, 0x48, 0x7A, 0xC9},
/* Col 2 */ {0x17, 0xFF, 0x9E, 0x21, 0x36, 0x90, 0xC7, 0x82},
/* Col 3 */ {0xBC, 0x5D, 0x9A, 0x5B, 0xEE, 0x7F, 0x42, 0xEB},
/* Col 4 */ {0x24, 0xF5, 0xDD, 0xF8, 0x7A, 0x77, 0x74, 0xE7},
/* Col 5 */ {0x3D, 0x70, 0x7C, 0x94, 0xDC, 0x84, 0xAD, 0x95},
/* Col 6 */ {0x1E, 0x6A, 0xF0, 0x37, 0x52, 0x7B, 0x11, 0xD4},
/* Col 7 */ {0x62, 0xF5, 0x2B, 0xAA, 0xFC, 0x33, 0xBF, 0xAF},
/* Col 8 {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97} */
},
{ /* Row 2 */
/* Col 0 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97},
/* Col 1 */ {0x8E, 0x4A, 0xD0, 0xA9, 0xA7, 0xFF, 0x20, 0xCA},
/* Col 2 */ {0x4C, 0x97, 0x9D, 0xBF, 0xB8, 0x3D, 0xB5, 0xBE},
/* Col 3 */ {0x0C, 0x5D, 0x24, 0x30, 0x9F, 0xCA, 0x6D, 0xBD},
/* Col 4 */ {0x50, 0x14, 0x33, 0xDE, 0xF1, 0x78, 0x95, 0xAD},
/* Col 5 */ {0x0C, 0x3C, 0xFA, 0xF9, 0xF0, 0xF2, 0x10, 0xC9},
/* Col 6 */ {0xF4, 0xDA, 0x06, 0xDB, 0xBF, 0x4E, 0x6F, 0xB3},
/* Col 7 */ {0x9E, 0x08, 0xD1, 0xAE, 0x59, 0x5E, 0xE8, 0xF0},
/* Col 8 {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E} */
},
{ /* Row 3 */
/* Col 0 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E},
/* Col 1 */ {0x80, 0x69, 0x26, 0x80, 0x08, 0xF8, 0x49, 0xE7},
/* Col 2 */ {0x7D, 0x2D, 0x49, 0x54, 0xD0, 0x80, 0x40, 0xC1},
/* Col 3 */ {0xB6, 0xF2, 0xE6, 0x1B, 0x80, 0x5A, 0x36, 0xB4},
/* Col 4 */ {0x42, 0xAE, 0x9C, 0x1C, 0xDA, 0x67, 0x05, 0xF6},
/* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
/* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
/* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
/* Col 8 {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93} */
// Wrong values used by Orange TX/RX
// /* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
},
{ /* Row 4 */
/* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
/* Col 1 */ {0xDC, 0x68, 0x08, 0x99, 0x97, 0xAE, 0xAF, 0x8C},
/* Col 2 */ {0xC3, 0x0E, 0x01, 0x16, 0x0E, 0x32, 0x06, 0xBA},
/* Col 3 */ {0xE0, 0x83, 0x01, 0xFA, 0xAB, 0x3E, 0x8F, 0xAC},
/* Col 4 */ {0x5C, 0xD5, 0x9C, 0xB8, 0x46, 0x9C, 0x7D, 0x84},
/* Col 5 */ {0xF1, 0xC6, 0xFE, 0x5C, 0x9D, 0xA5, 0x4F, 0xB7},
/* Col 6 */ {0x58, 0xB5, 0xB3, 0xDD, 0x0E, 0x28, 0xF1, 0xB0},
/* Col 7 */ {0x5F, 0x30, 0x3B, 0x56, 0x96, 0x45, 0xF4, 0xA1},
/* Col 8 {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8} */
},
};
static void __attribute__((unused)) read_code(uint8_t *buf, uint8_t row, uint8_t col, uint8_t len)
{
for(uint8_t i=0;i<len;i++)
buf[i]=pgm_read_byte_near( &pncodes[row][col][i] );
}
static uint8_t __attribute__((unused)) get_pn_row(uint8_t channel)
{
return ((sub_protocol == DSMX_11 || sub_protocol == DSMX_22 )? (channel - 2) % 5 : channel % 5);
}
const uint8_t PROGMEM init_vals[][2] = {
{CYRF_02_TX_CTRL, 0x03}, // TX interrupt complete and error enabled
//0x00 in deviation but needed to know when transmit is over
{CYRF_05_RX_CTRL, 0x00}, // All RX interrupt disabled
{CYRF_28_CLK_EN, 0x02}, // Force receive clock enable
{CYRF_32_AUTO_CAL_TIME, 0x3c}, // Default init value
{CYRF_35_AUTOCAL_OFFSET, 0x14}, // Default init value
{CYRF_06_RX_CFG, 0x4A}, // LNA enabled, RX override enabled, Fast turn mode enabled, RX is 1MHz below TX
{CYRF_1B_TX_OFFSET_LSB, 0x55}, // Default init value
{CYRF_1C_TX_OFFSET_MSB, 0x05}, // Default init value
{CYRF_39_ANALOG_CTRL, 0x01}, // All slow for synth setting time
{CYRF_01_TX_LENGTH, 0x10}, // 16 bytes packet
{CYRF_14_EOP_CTRL, 0x02}, // Set EOP Symbol Count to 2
{CYRF_12_DATA64_THOLD, 0x0a}, // 64 Chip Data PN corelator threshold, default datasheet value is 0x0E
//Below is for bind only
{CYRF_03_TX_CFG, 0x38 | CYRF_BIND_POWER}, //64 chip codes, SDR mode
{CYRF_10_FRAMING_CFG, 0x4a}, // SOP disabled, no LEN field and SOP correlator of 0x0a but since SOP is disabled...
{CYRF_1F_TX_OVERRIDE, 0x04}, // Disable TX CRC, no ACK, use TX synthesizer
{CYRF_1E_RX_OVERRIDE, 0x14}, // Disable RX CRC, Force receive data rate, use RX synthesizer
};
const uint8_t PROGMEM data_vals[][2] = {
{CYRF_29_RX_ABORT, 0x20}, // Abort RX operation in case we are coming from bind
{CYRF_0F_XACT_CFG, 0x24}, // Force Idle
{CYRF_29_RX_ABORT, 0x00}, // Clear abort RX
{CYRF_03_TX_CFG, 0x28 | CYRF_HIGH_POWER}, // 64 chip codes, 8DR mode
{CYRF_10_FRAMING_CFG, 0xea}, // SOP enabled, SOP_CODE_ADR 64 chips, Packet len enabled, SOP correlator 0x0A
{CYRF_1F_TX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
{CYRF_1E_RX_OVERRIDE, 0x00}, // CRC16 enabled, no ACK
};
static void __attribute__((unused)) cyrf_config()
{
for(uint8_t i = 0; i < sizeof(init_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&init_vals[i][0]), pgm_read_byte_near(&init_vals[i][1]));
CYRF_WritePreamble(0x333304);
CYRF_ConfigRFChannel(0x61);
}
static void __attribute__((unused)) build_bind_packet()
{
uint8_t i;
uint16_t sum = 384 - 0x10;//
packet[0] = 0xff ^ cyrfmfg_id[0];
packet[1] = 0xff ^ cyrfmfg_id[1];
packet[2] = 0xff ^ cyrfmfg_id[2];
packet[3] = 0xff ^ cyrfmfg_id[3];
packet[4] = packet[0];
packet[5] = packet[1];
packet[6] = packet[2];
packet[7] = packet[3];
for(i = 0; i < 8; i++)
sum += packet[i];
packet[8] = sum >> 8;
packet[9] = sum & 0xff;
packet[10] = 0x01; //???
packet[11] = DSM_num_ch;
if (sub_protocol==DSM2_22)
packet[12]=DSM_num_ch<8?0x01:0x02; // DSM2/1024 1 or 2 packets depending on the number of channels
if(sub_protocol==DSM2_11)
packet[12]=0x12; // DSM2/2048 2 packets
if(sub_protocol==DSMX_22)
#if defined DSM_TELEMETRY
packet[12] = 0xb2; // DSMX/2048 2 packets
#else
packet[12] = DSM_num_ch<8? 0xa2 : 0xb2; // DSMX/2048 1 or 2 packets depending on the number of channels
#endif
if(sub_protocol==DSMX_11 || sub_protocol==DSM_AUTO) // Force DSMX/1024 in mode Auto
packet[12]=0xb2; // DSMX/1024 2 packets
packet[13] = 0x00; //???
for(i = 8; i < 14; i++)
sum += packet[i];
packet[14] = sum >> 8;
packet[15] = sum & 0xff;
}
static void __attribute__((unused)) initialize_bind_phase()
{
CYRF_ConfigRFChannel(DSM_BIND_CHANNEL); //This seems to be random?
//64 SDR Mode is configured so only the 8 first values are needed but need to write 16 values...
CYRF_ConfigDataCode((const uint8_t*)"\xD7\xA1\x54\xB1\x5E\x89\xAE\x86\xc6\x94\x22\xfe\x48\xe6\x57\x4e", 16);
build_bind_packet();
}
static void __attribute__((unused)) cyrf_configdata()
{
for(uint8_t i = 0; i < sizeof(data_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte_near(&data_vals[i][0]), pgm_read_byte_near(&data_vals[i][1]));
}
static void __attribute__((unused)) update_channels()
{
prev_option=option;
if(sub_protocol==DSM_AUTO)
DSM_num_ch=12; // Force 12 channels in mode Auto
else
DSM_num_ch=option;
if(DSM_num_ch<4 || DSM_num_ch>12)
DSM_num_ch=6; // Default to 6 channels if invalid choice...
// Create channel map based on number of channels and refresh rate
uint8_t idx=DSM_num_ch-4;
if(DSM_num_ch>7 && DSM_num_ch<11 && (sub_protocol==DSM2_11 || sub_protocol==DSMX_11))
idx+=5; // In 11ms mode change index only for channels 8..10
for(uint8_t i=0;i<14;i++)
ch_map[i]=pgm_read_byte_near(&ch_map_progmem[idx][i]);
}
static void __attribute__((unused)) build_data_packet(uint8_t upper)
{
uint16_t max = 2047;
uint8_t bits = 11;
if(prev_option!=option)
update_channels();
if (sub_protocol==DSMX_11 || sub_protocol==DSMX_22 )
{
packet[0] = cyrfmfg_id[2];
packet[1] = cyrfmfg_id[3];
}
else
{
packet[0] = (0xff ^ cyrfmfg_id[2]);
packet[1] = (0xff ^ cyrfmfg_id[3]);
if(sub_protocol==DSM2_22)
{
max=1023; // Only DSM_22 is using a resolution of 1024
bits=10;
}
}
for (uint8_t i = 0; i < 7; i++)
{
uint8_t idx = ch_map[(upper?7:0) + i];//1,5,2,3,0,4
uint16_t value = 0xffff;;
if (idx != 0xff)
{
if (!IS_BIND_DONE_on)
{ // Failsafe position during binding
value=max/2; //all channels to middle
if(idx==0)
value=1; //except throttle
}
else
value=map(Servo_data[CH_TAER[idx]],servo_min_125,servo_max_125,0,max);
value |= (upper && i==0 ? 0x8000 : 0) | (idx << bits);
}
packet[i*2+2] = (value >> 8) & 0xff;
packet[i*2+3] = (value >> 0) & 0xff;
}
}
static void __attribute__((unused)) set_sop_data_crc()
{
//The crc for channel '1' is NOT(mfgid[0] << 8 + mfgid[1])
//The crc for channel '2' is (mfgid[0] << 8 + mfgid[1])
uint16_t crc = (cyrfmfg_id[0] << 8) + cyrfmfg_id[1];
if(phase==DSM_CH1_CHECK_A||phase==DSM_CH1_CHECK_B)
CYRF_ConfigCRCSeed(crc); //CH2
else
CYRF_ConfigCRCSeed(~crc); //CH1
uint8_t pn_row = get_pn_row(hopping_frequency[hopping_frequency_no]);
uint8_t code[16];
read_code(code,pn_row,sop_col,8); // pn_row between 0 and 4, sop_col between 1 and 7
CYRF_ConfigSOPCode(code);
read_code(code,pn_row,7 - sop_col,8); // 7-sop_col between 0 and 6
read_code(code+8,pn_row,7 - sop_col + 1,8); // 7-sop_col+1 between 1 and 7
CYRF_ConfigDataCode(code, 16);
CYRF_ConfigRFChannel(hopping_frequency[hopping_frequency_no]);
hopping_frequency_no++;
if(sub_protocol == DSMX_11 || sub_protocol == DSMX_22)
hopping_frequency_no %=23;
else
hopping_frequency_no %=2;
}
static void __attribute__((unused)) calc_dsmx_channel()
{
uint8_t idx = 0;
uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0));
uint32_t id_tmp = id;
while(idx < 23)
{
uint8_t i;
uint8_t count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
if ( (next_ch ^ cyrfmfg_id[3]) & 0x01 )
continue;
for (i = 0; i < idx; i++)
{
if(hopping_frequency[i] == next_ch)
break;
if(hopping_frequency[i] <= 27)
count_3_27++;
else
if (hopping_frequency[i] <= 51)
count_28_51++;
else
count_52_76++;
}
if (i != idx)
continue;
if ((next_ch < 28 && count_3_27 < 8)
||(next_ch >= 28 && next_ch < 52 && count_28_51 < 7)
||(next_ch >= 52 && count_52_76 < 8))
hopping_frequency[idx++] = next_ch;
}
}
static uint8_t __attribute__((unused)) DSM_Check_RX_packet()
{
uint8_t result=1; // assume good packet
uint16_t sum = 384 - 0x10;
for(uint8_t i = 1; i < 9; i++)
{
sum += pkt[i];
if(i<5)
if(pkt[i] != (0xff ^ cyrfmfg_id[i-1]))
result=0; // bad packet
}
if( pkt[9] != (sum>>8) && pkt[10] != (uint8_t)sum )
result=0;
return result;
}
uint16_t ReadDsm()
{
#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 phase, and switch channels. Was 400 but 600 seems what the 328p needs to read a packet
uint16_t start;
#if defined DSM_TELEMETRY
uint8_t rx_phase;
uint8_t len;
#endif
switch(phase)
{
case DSM_BIND_WRITE:
if(bind_counter--==0)
#if defined DSM_TELEMETRY
phase=DSM_BIND_CHECK; //Check RX answer
#else
phase=DSM_CHANSEL; //Switch to normal mode
#endif
CYRF_WriteDataPacket(packet);
return 10000;
#if defined DSM_TELEMETRY
case DSM_BIND_CHECK:
//64 SDR Mode is configured so only the 8 first values are needed but we need to write 16 values...
CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84\xC9\x2C\x06\x93\x86\xB9\x9E\xD7", 16);
CYRF_SetTxRxMode(RX_EN); //Receive mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //Prepare to receive
bind_counter=2*DSM_BIND_COUNT; //Timeout of 4.2s if no packet received
phase++; // change from BIND_CHECK to BIND_READ
return 2000;
case DSM_BIND_READ:
//Read data from RX
rx_phase = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_phase & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_phase |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_phase & 0x07) == 0x02)
{ // data received with no errors
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
if(len>MAX_PKT-2)
len=MAX_PKT-2;
CYRF_ReadDataPacketLen(pkt+1, len);
if(len==10 && DSM_Check_RX_packet())
{
pkt[0]=0x80;
telemetry_link=1; // send received data on serial
phase++;
return 2000;
}
}
else
if((rx_phase & 0x02) != 0x02)
{ // data received with errors
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
CYRF_SetTxRxMode(RX_EN); // Force end state read
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX operation
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive
}
if( --bind_counter == 0 )
{ // Exit if no answer has been received for some time
phase++; // DSM_CHANSEL
return 7000 ;
}
return 7000;
#endif
case DSM_CHANSEL:
BIND_DONE;
cyrf_configdata();
CYRF_SetTxRxMode(TX_EN);
hopping_frequency_no = 0;
phase = DSM_CH1_WRITE_A; // in fact phase++
set_sop_data_crc();
return 10000;
case DSM_CH1_WRITE_A:
case DSM_CH1_WRITE_B:
case DSM_CH2_WRITE_A:
case DSM_CH2_WRITE_B:
build_data_packet(phase == DSM_CH1_WRITE_B||phase == DSM_CH2_WRITE_B); // build lower or upper channels
CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS); // clear IRQ flags
CYRF_WriteDataPacket(packet);
phase++; // change from WRITE to CHECK mode
return DSM_WRITE_DELAY;
case DSM_CH1_CHECK_A:
case DSM_CH1_CHECK_B:
start=micros();
while ((uint16_t)micros()-start < 500) // Wait max 500µs
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
break;
set_sop_data_crc();
phase++; // change from CH1_CHECK to CH2_WRITE
return DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
case DSM_CH2_CHECK_A:
case DSM_CH2_CHECK_B:
start=micros();
while ((uint16_t)micros()-start < 500) // Wait max 500µs
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
break;
if (phase == DSM_CH2_CHECK_A)
CYRF_SetPower(0x28); //Keep transmit power in sync
#if defined DSM_TELEMETRY
phase++; // change from CH2_CHECK to CH2_READ
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 DSM_CH2_READ_A:
case DSM_CH2_READ_B:
//Read telemetry
rx_phase = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_phase & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_phase |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_phase & 0x07) == 0x02)
{ // good data (complete with no errors)
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
if(len>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;
}
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x20); // Abort RX operation
if (phase == DSM_CH2_READ_A && (sub_protocol==DSM2_22 || sub_protocol==DSMX_22) && DSM_num_ch < 8) // 22ms mode
{
CYRF_SetTxRxMode(RX_EN); // Force end state read
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); // Clear abort RX operation
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
phase = DSM_CH2_READ_B;
return 11000;
}
if (phase == DSM_CH2_READ_A)
phase = DSM_CH1_WRITE_B; //Transmit upper
else
phase = DSM_CH1_WRITE_A; //Transmit lower
CYRF_SetTxRxMode(TX_EN); //TX mode
CYRF_WriteRegister(CYRF_29_RX_ABORT, 0x00); //Clear abort RX operation
set_sop_data_crc();
return DSM_READ_DELAY;
#else
// No telemetry
set_sop_data_crc();
if (phase == DSM_CH2_CHECK_A)
{
if(DSM_num_ch > 7 || sub_protocol==DSM2_11 || sub_protocol==DSMX_11)
phase = DSM_CH1_WRITE_B; //11ms mode or upper to transmit change from CH2_CHECK_A to CH1_WRITE_A
else
{ //Normal mode 22ms
phase = DSM_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper)
return 22000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY ;
}
}
else
phase = DSM_CH1_WRITE_A; // change from CH2_CHECK_B to CH1_WRITE_A (upper already transmitted so transmit lower)
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
#endif
}
return 0;
}
uint16_t initDsm()
{
CYRF_GetMfgData(cyrfmfg_id);
//Model match
cyrfmfg_id[3]^=RX_num;
//Calc sop_col
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
//Fix for OrangeRX using wrong pncodes by preventing access to "Col 8"
if(sop_col==0)
{
cyrfmfg_id[rx_tx_addr[0]%3]^=0x01; //Change a bit so sop_col will be different from 0
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
}
//Hopping frequencies
if (sub_protocol == DSMX_11 || sub_protocol == DSMX_22)
calc_dsmx_channel();
else
{
uint8_t tmpch[10];
CYRF_FindBestChannels(tmpch, 10, 5, 3, 75);
//
uint8_t idx = random(0xfefefefe) % 10;
hopping_frequency[0] = tmpch[idx];
while(1)
{
idx = random(0xfefefefe) % 10;
if (tmpch[idx] != hopping_frequency[0])
break;
}
hopping_frequency[1] = tmpch[idx];
}
//
cyrf_config();
CYRF_SetTxRxMode(TX_EN);
//
update_channels();
//
if(IS_AUTOBIND_FLAG_on )
{
BIND_IN_PROGRESS;
initialize_bind_phase();
phase = DSM_BIND_WRITE;
bind_counter=DSM_BIND_COUNT;
}
else
phase = DSM_CHANSEL;//
return 10000;
}
#endif

View File

@ -21,16 +21,13 @@
//For Debug
//#define NO_SCRAMBLE
#define PKTS_PER_CHANNEL 4
#define DEVO_BIND_COUNT 0x1388
//#define TELEMETRY_ENABLE 0x30
#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
//
//#define TELEM_ON 0
//#define TELEM_OFF 1
enum Devo_PhaseState
{
#define DEVO_PKTS_PER_CHANNEL 4
#define DEVO_BIND_COUNT 0x1388
#define DEVO_NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
enum {
DEVO_BIND,
DEVO_BIND_SENDCH,
DEVO_BOUND,
@ -46,6 +43,7 @@ enum Devo_PhaseState
DEVO_BOUND_10,
};
<<<<<<< HEAD
const uint8_t sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
/* 0 */ {0x3C,0x37,0xCC,0x91,0xE2,0xF8,0xCC,0x91}, //0x91CCF8E291CC373C
@ -67,56 +65,84 @@ uint8_t use_fixed_id;
uint8_t failsafe_pkt;
static void __attribute__((unused)) scramble_pkt()
=======
static void __attribute__((unused)) DEVO_scramble_pkt()
>>>>>>> refs/remotes/pascallanger/master
{
#ifdef NO_SCRAMBLE
return;
#else
uint8_t i;
for(i = 0; i < 15; i++)
for(uint8_t i = 0; i < 15; i++)
packet[i + 1] ^= cyrfmfg_id[i % 4];
#endif
}
<<<<<<< HEAD
static void __attribute__((unused)) add_pkt_suffix()
=======
static void __attribute__((unused)) DEVO_add_pkt_suffix()
>>>>>>> refs/remotes/pascallanger/master
{
uint8_t bind_state;
if (use_fixed_id)
uint8_t bind_state;
#ifdef ENABLE_PPM
if(mode_select && option==0 && IS_BIND_DONE_on) //PPM mode and option not already set and bind is finished
{
if (bind_counter > 0)
bind_state = 0xc0;
else
bind_state = 0x80;
BIND_SET_INPUT;
BIND_SET_PULLUP; // set pullup
if(IS_BIND_BUTTON_on)
{
eeprom_write_byte((uint8_t*)(30+mode_select),0x01); // Set fixed id mode for the current model
option=1;
}
BIND_SET_OUTPUT;
}
#endif //ENABLE_PPM
if(prev_option!=option && IS_BIND_DONE_on)
{
MProtocol_id = RX_num + MProtocol_id_master;
bind_counter=DEVO_BIND_COUNT;
}
if (option)
{
if (bind_counter > 0)
bind_state = 0xc0;
else
bind_state = 0x80;
}
else
bind_state = 0x00;
packet[10] = bind_state | (PKTS_PER_CHANNEL - pkt_num - 1);
bind_state = 0x00;
packet[10] = bind_state | (DEVO_PKTS_PER_CHANNEL - packet_count - 1);
packet[11] = *(hopping_frequency_ptr + 1);
packet[12] = *(hopping_frequency_ptr + 2);
packet[13] = fixed_id & 0xff;
packet[14] = (fixed_id >> 8) & 0xff;
packet[15] = (fixed_id >> 16) & 0xff;
packet[13] = MProtocol_id & 0xff;
packet[14] = (MProtocol_id >> 8) & 0xff;
packet[15] = (MProtocol_id >> 16) & 0xff;
}
<<<<<<< HEAD
static void __attribute__((unused)) build_beacon_pkt(uint8_t upper)
=======
static void __attribute__((unused)) DEVO_build_beacon_pkt(uint8_t upper)
>>>>>>> refs/remotes/pascallanger/master
{
packet[0] = ((DEVO_NUM_CHANNELS << 4) | 0x07);
// uint8_t enable = 0;
packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x07;
uint8_t max = 8;
// int offset = 0;
if (upper)
{
packet[0] += 1;
max = 4;
// offset = 8;
}
for(uint8_t i = 0; i < max; i++)
packet[i+1] = 0;
// packet[9] = enable;
packet[9] = 0;
add_pkt_suffix();
DEVO_add_pkt_suffix();
}
<<<<<<< HEAD
static void __attribute__((unused)) build_bind_pkt()
=======
static void __attribute__((unused)) DEVO_build_bind_pkt()
>>>>>>> refs/remotes/pascallanger/master
{
packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x0a;
packet[1] = bind_counter & 0xff;
@ -128,7 +154,7 @@ static void __attribute__((unused)) build_bind_pkt()
packet[7] = cyrfmfg_id[1];
packet[8] = cyrfmfg_id[2];
packet[9] = cyrfmfg_id[3];
add_pkt_suffix();
DEVO_add_pkt_suffix();
//The fixed-id portion is scrambled in the bind packet
//I assume it is ignored
packet[13] ^= cyrfmfg_id[0];
@ -136,16 +162,19 @@ static void __attribute__((unused)) build_bind_pkt()
packet[15] ^= cyrfmfg_id[2];
}
<<<<<<< HEAD
static void __attribute__((unused)) build_data_pkt()
=======
static void __attribute__((unused)) DEVO_build_data_pkt()
>>>>>>> refs/remotes/pascallanger/master
{
uint8_t i;
static uint8_t ch_idx=0;
packet[0] = (DEVO_NUM_CHANNELS << 4) | (0x0b + ch_idx);
uint8_t sign = 0x0b;
for (i = 0; i < 4; i++)
for (uint8_t i = 0; i < 4; i++)
{
//
int16_t value= map(Servo_data[ch_idx * 4 + i],PPM_MIN,PPM_MAX,-1600,1600);//range -1600...+1600
//s32 value = (s32)Channels[ch_idx * 4 + i] * 0x640 / CHAN_MAX_VALUE;//10000
int16_t value=map(Servo_data[CH_EATR[ch_idx * 4 + i]],servo_min_125,servo_max_125,-1600,1600);//range -1600..+1600
if(value < 0)
{
value = -value;
@ -155,13 +184,17 @@ static void __attribute__((unused)) build_data_pkt()
packet[2 * i + 2] = (value >> 8) & 0xff;
}
packet[9] = sign;
ch_idx = ch_idx + 1;
ch_idx++;
if (ch_idx * 4 >= DEVO_NUM_CHANNELS)
ch_idx = 0;
add_pkt_suffix();
DEVO_add_pkt_suffix();
}
<<<<<<< HEAD
static void __attribute__((unused)) cyrf_set_bound_sop_code()
=======
static void __attribute__((unused)) DEVO_cyrf_set_bound_sop_code()
>>>>>>> refs/remotes/pascallanger/master
{
/* crc == 0 isn't allowed, so use 1 if the math results in 0 */
uint8_t crc = (cyrfmfg_id[0] + (cyrfmfg_id[1] >> 6) + cyrfmfg_id[2]);
@ -170,68 +203,70 @@ static void __attribute__((unused)) cyrf_set_bound_sop_code()
uint8_t sopidx = (0xff &((cyrfmfg_id[0] << 2) + cyrfmfg_id[1] + cyrfmfg_id[2])) % 10;
CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed((crc << 8) + crc);
CYRF_ConfigSOPCode(sopcodes[sopidx]);
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sopidx]);
CYRF_SetPower(0x08);
}
<<<<<<< HEAD
static void __attribute__((unused)) cyrf_init()
=======
const uint8_t PROGMEM DEVO_init_vals[][2] = {
{ CYRF_1D_MODE_OVERRIDE, 0x38 },
{ CYRF_03_TX_CFG, 0x08 },
{ CYRF_06_RX_CFG, 0x4A },
{ CYRF_0B_PWR_CTRL, 0x00 },
{ CYRF_10_FRAMING_CFG, 0xA4 },
{ CYRF_11_DATA32_THOLD, 0x05 },
{ CYRF_12_DATA64_THOLD, 0x0E },
{ CYRF_1B_TX_OFFSET_LSB, 0x55 },
{ CYRF_1C_TX_OFFSET_MSB, 0x05 },
{ CYRF_32_AUTO_CAL_TIME, 0x3C },
{ CYRF_35_AUTOCAL_OFFSET, 0x14 },
{ CYRF_39_ANALOG_CTRL, 0x01 },
{ CYRF_1E_RX_OVERRIDE, 0x10 },
{ CYRF_1F_TX_OVERRIDE, 0x00 },
{ CYRF_01_TX_LENGTH, 0x10 },
{ CYRF_0F_XACT_CFG, 0x10 },
{ CYRF_27_CLK_OVERRIDE, 0x02 },
{ CYRF_28_CLK_EN, 0x02 },
{ CYRF_0F_XACT_CFG, 0x28 }
};
static void __attribute__((unused)) DEVO_cyrf_init()
>>>>>>> refs/remotes/pascallanger/master
{
/* Initialise CYRF chip */
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x39);
CYRF_SetPower(0x08);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4A);
CYRF_WriteRegister(CYRF_0B_PWR_CTRL, 0x00);
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04);
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL, 0x20);
CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xA4);
CYRF_WriteRegister(CYRF_11_DATA32_THOLD, 0x05);
CYRF_WriteRegister(CYRF_12_DATA64_THOLD, 0x0E);
CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55);
CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05);
CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3C);
CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14);
CYRF_WriteRegister(CYRF_39_ANALOG_CTRL, 0x01);
CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x10);
CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00);
CYRF_WriteRegister(CYRF_01_TX_LENGTH, 0x10);
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x10);
CYRF_WriteRegister(CYRF_27_CLK_OVERRIDE, 0x02);
CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x28);
for(uint8_t i = 0; i < sizeof(DEVO_init_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte( &DEVO_init_vals[i][0]), pgm_read_byte( &DEVO_init_vals[i][1]) );
}
<<<<<<< HEAD
static void __attribute__((unused)) set_radio_channels()
=======
static void __attribute__((unused)) DEVO_set_radio_channels()
>>>>>>> refs/remotes/pascallanger/master
{
//int i;
CYRF_FindBestChannels(hopping_frequency, 3, 4, 4, 80);
//printf("Radio Channels:");
// for (i = 0; i < 3; i++) {
// printf(" %02x", radio_ch[i]);
//Serial.print(radio_ch[i]);
// }
// printf("\n");
//Makes code a little easier to duplicate these here
hopping_frequency[3] = hopping_frequency[0];
hopping_frequency[4] = hopping_frequency[1];
}
static void __attribute__((unused)) DEVO_BuildPacket()
{
static uint8_t failsafe_pkt=0;
switch(phase)
{
case DEVO_BIND:
if(bind_counter>0)
if(bind_counter)
bind_counter--;
build_bind_pkt();
DEVO_build_bind_pkt();
phase = DEVO_BIND_SENDCH;
break;
case DEVO_BIND_SENDCH:
if(bind_counter>0)
if(bind_counter)
bind_counter--;
build_data_pkt();
scramble_pkt();
DEVO_build_data_pkt();
DEVO_scramble_pkt();
if (bind_counter == 0)
{
phase = DEVO_BOUND;
@ -250,10 +285,10 @@ static void __attribute__((unused)) DEVO_BuildPacket()
case DEVO_BOUND_7:
case DEVO_BOUND_8:
case DEVO_BOUND_9:
build_data_pkt();
scramble_pkt();
DEVO_build_data_pkt();
DEVO_scramble_pkt();
phase++;
if (bind_counter > 0)
if (bind_counter)
{
bind_counter--;
if (bind_counter == 0)
@ -261,19 +296,20 @@ static void __attribute__((unused)) DEVO_BuildPacket()
}
break;
case DEVO_BOUND_10:
build_beacon_pkt(DEVO_NUM_CHANNELS > 8 ? failsafe_pkt : 0);
DEVO_build_beacon_pkt(DEVO_NUM_CHANNELS > 8 ? failsafe_pkt : 0);
failsafe_pkt = failsafe_pkt ? 0 : 1;
scramble_pkt();
DEVO_scramble_pkt();
phase = DEVO_BOUND_1;
break;
}
pkt_num++;
if(pkt_num == PKTS_PER_CHANNEL)
pkt_num = 0;
packet_count++;
if(packet_count == DEVO_PKTS_PER_CHANNEL)
packet_count = 0;
}
uint16_t devo_callback()
{
static uint8_t txState=0;
if (txState == 0)
{
txState = 1;
@ -284,24 +320,24 @@ uint16_t devo_callback()
txState = 0;
uint8_t i = 0;
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
if(++i > NUM_WAIT_LOOPS)
if(++i > DEVO_NUM_WAIT_LOOPS)
return 1200;
if (phase == DEVO_BOUND)
{
/* exit binding state */
phase = DEVO_BOUND_3;
cyrf_set_bound_sop_code();
DEVO_cyrf_set_bound_sop_code();
}
if(pkt_num == 0)
if(packet_count == 0)
{
//Keep tx power updated
CYRF_SetPower(0x08);
CYRF_SetPower(0x08); //Keep tx power updated
hopping_frequency_ptr = hopping_frequency_ptr == &hopping_frequency[2] ? hopping_frequency : hopping_frequency_ptr + 1;
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
}
return 1200;
}
<<<<<<< HEAD
/*static void __attribute__((unused)) devo_bind()
{
fixed_id = Model_fixed_id;
@ -328,63 +364,39 @@ devo_bind();
*/
=======
>>>>>>> refs/remotes/pascallanger/master
uint16_t DevoInit()
{
CYRF_Reset();
cyrf_init();
DEVO_cyrf_init();
CYRF_GetMfgData(cyrfmfg_id);
CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed(0x0000);
CYRF_ConfigSOPCode(sopcodes[0]);
set_radio_channels();
use_fixed_id = 0;
failsafe_pkt = 0;
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[0]);
DEVO_set_radio_channels();
hopping_frequency_ptr = hopping_frequency;
//
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
//FIXME: Properly setnumber of channels;
pkt_num = 0;
ch_idx = 0;
txState = 0;
//uint8_t txid[4];
//
/*
if(BIND_0){
Model_fixed_id=0;
eeprom_write_block((const void*)0,(void*)40,4);
while(1){
LED_ON;
delay(100);
LED_OFF;
delay(100);
}
}
else{
eeprom_read_block((void*)txid,(const void*)40,3);
Model_fixed_id=(txid[0] | ((uint32_t)txid[1]<<8) | ((uint32_t)txid[2]<<16));
}
*/
if(! Model_fixed_id)
{//model fixed ID =0
fixed_id = ((uint32_t)(hopping_frequency[0] ^ cyrfmfg_id[0] ^ cyrfmfg_id[3]) << 16)
| ((uint32_t)(hopping_frequency[1] ^ cyrfmfg_id[1] ^ cyrfmfg_id[4]) << 8)
| ((uint32_t)(hopping_frequency[2] ^ cyrfmfg_id[2] ^ cyrfmfg_id[5]) << 0);
fixed_id = fixed_id % 1000000;
packet_count = 0;
prev_option=option;
if(option==0)
{
MProtocol_id = ((uint32_t)(hopping_frequency[0] ^ cyrfmfg_id[0] ^ cyrfmfg_id[3]) << 16)
| ((uint32_t)(hopping_frequency[1] ^ cyrfmfg_id[1] ^ cyrfmfg_id[4]) << 8)
| ((uint32_t)(hopping_frequency[2] ^ cyrfmfg_id[2] ^ cyrfmfg_id[5]) << 0);
MProtocol_id %= 1000000;
bind_counter = DEVO_BIND_COUNT;
phase = DEVO_BIND;
//PROTOCOL_SetBindState(0x1388 * 2400 / 1000); //msecs
BIND_IN_PROGRESS;
}
else
{
fixed_id = Model_fixed_id;
use_fixed_id = 1;
phase = DEVO_BOUND_1;
bind_counter = 0;
cyrf_set_bound_sop_code();
DEVO_cyrf_set_bound_sop_code();
}
return 2400;
}

View File

@ -35,7 +35,7 @@ static void __attribute__((unused)) ESKY_init(uint8_t bind)
NRF24L01_Initialize();
// 2-bytes CRC, radio off
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
if (bind)
@ -119,8 +119,8 @@ static void __attribute__((unused)) ESKY_send_packet(uint8_t bind)
{
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];

View File

@ -0,0 +1,212 @@
/*
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_ori[4] + packet_ori[5] + packet_ori[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 = 0xA0;
else // roll
trim_val = 0x60;
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] = 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_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
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);
bind_counter--;
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;
packet_count=0;
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

View File

@ -15,17 +15,26 @@
// Last sync with hexfet new_protocols/fy326_nrf24l01.c dated 2015-07-29
#if defined(FY326_NRF24L01_INO)
<<<<<<< HEAD
=======
>>>>>>> refs/remotes/pascallanger/master
#include "iface_nrf24l01.h"
#define FY326_INITIAL_WAIT 500
#define FY326_PACKET_PERIOD 1500
#define FY326_PACKET_CHKTIME 300
#define FY326_PACKET_SIZE 15
<<<<<<< HEAD
#define FY326_BIND_COUNT 16
=======
#define FY326_BIND_COUNT 16
>>>>>>> refs/remotes/pascallanger/master
#define FY326_RF_BIND_CHANNEL 0x17
#define FY326_NUM_RF_CHANNELS 5
enum {
<<<<<<< HEAD
FY326_INIT1 = 0,
FY326_BIND1,
FY326_BIND2,
@ -33,6 +42,11 @@ enum {
FY319_INIT1,
FY319_BIND1,
FY319_BIND2,
=======
FY326_BIND1=0,
FY326_BIND2,
FY326_DATA
>>>>>>> refs/remotes/pascallanger/master
};
#define rxid channel
@ -42,7 +56,11 @@ static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
{
packet[0] = rx_tx_addr[3];
if(bind)
<<<<<<< HEAD
packet[1] = 0x55;
=======
packet[1] = 0x55;
>>>>>>> refs/remotes/pascallanger/master
else
packet[1] = GET_FLAG(Servo_AUX3, 0x80) // Headless
| GET_FLAG(Servo_AUX2, 0x40) // RTH
@ -53,6 +71,7 @@ static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
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
<<<<<<< HEAD
if(sub_protocol == FY319) {
packet[6] = 255 - scale_channel(AILERON, 0, 255);
packet[7] = scale_channel(ELEVATOR, 0, 255);
@ -68,6 +87,16 @@ static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim;
packet[12] = 0; // throttle_trim;
packet[13] = rxid;
=======
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;
>>>>>>> refs/remotes/pascallanger/master
packet[14] = rx_tx_addr[4];
if (bind)
@ -76,12 +105,20 @@ static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no %= FY326_NUM_RF_CHANNELS;
<<<<<<< HEAD
}
// clear packet status bits and TX FIFO
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
=======
}
// clear packet status bits and TX FIFO
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WritePayload(packet, FY326_PACKET_SIZE);
@ -90,12 +127,18 @@ static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
static void __attribute__((unused)) FY326_init()
{
<<<<<<< HEAD
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
if(sub_protocol == FY319)
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // Five-byte rx/tx address
else
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address
=======
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address
>>>>>>> refs/remotes/pascallanger/master
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();
@ -107,13 +150,19 @@ static void __attribute__((unused)) FY326_init()
NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL);
NRF24L01_SetBitrate(NRF24L01_BR_250K);
NRF24L01_SetPower();
<<<<<<< HEAD
NRF24L01_Activate(0x73);
=======
NRF24L01_Activate(0x73);
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f);
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07);
NRF24L01_Activate(0x73);
}
<<<<<<< HEAD
uint16_t fy326_callback()
{
uint8_t i;
@ -206,11 +255,55 @@ uint16_t fy326_callback()
FY326_send_packet(0);
break;
}
=======
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;
}
>>>>>>> refs/remotes/pascallanger/master
return FY326_PACKET_PERIOD;
}
static void __attribute__((unused)) FY326_initialize_txid()
{
<<<<<<< HEAD
if(sub_protocol == FY319) {
hopping_frequency[0] = (rx_tx_addr[0]&0x0f) & ~0x80;
hopping_frequency[1] = (rx_tx_addr[0] >> 4) & ~0x80;
@ -224,11 +317,19 @@ static void __attribute__((unused)) FY326_initialize_txid()
hopping_frequency[3] = 0x30 + (rx_tx_addr[1] >> 4);
hopping_frequency[4] = 0x40 + (rx_tx_addr[2] >> 4);
}
=======
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);
>>>>>>> refs/remotes/pascallanger/master
}
uint16_t initFY326(void)
{
BIND_IN_PROGRESS; // autobind protocol
<<<<<<< HEAD
rxid = 0xaa;
bind_counter = 0;
FY326_initialize_txid();
@ -237,6 +338,13 @@ uint16_t initFY326(void)
phase = FY319_INIT1;
else
phase = FY326_INIT1;
=======
rxid = 0xAA;
bind_counter = 0;
FY326_initialize_txid();
FY326_init();
phase=FY326_BIND1;
>>>>>>> refs/remotes/pascallanger/master
return FY326_INITIAL_WAIT;
}

View File

@ -21,6 +21,7 @@
//FlySky constants & variables
#define FLYSKY_BIND_COUNT 2500
<<<<<<< HEAD
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,
@ -47,6 +48,15 @@ enum {
// flags going to byte 12
FLAG_V9X9_FLIP = 0x10,
FLAG_V9X9_LED = 0x20,
=======
enum {
// flags going to byte 10
FLAG_V9X9_VIDEO = 0x40,
FLAG_V9X9_CAMERA= 0x80,
// flags going to byte 12
FLAG_V9X9_FLIP = 0x10,
FLAG_V9X9_LED = 0x20,
>>>>>>> refs/remotes/pascallanger/master
};
enum {
@ -69,12 +79,12 @@ enum {
FLAG_V912_BTMBTN= 0x80,
};
uint8_t chanrow;
uint8_t chancol;
uint8_t chanoffset;
const uint8_t PROGMEM V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
0x49, 0x49, 0x49, 0x49, 0x49, };
static void __attribute__((unused)) flysky_apply_extension_flags()
{
<<<<<<< HEAD
const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
0x49, 0x49, 0x49, 0x49, 0x49, };
static uint8_t seq_counter;
@ -146,6 +156,77 @@ static void __attribute__((unused)) flysky_apply_extension_flags()
default:
break;
}
=======
static uint8_t seq_counter;
switch(sub_protocol)
{
case V9X9:
if(Servo_AUX1)
packet[12] |= FLAG_V9X9_FLIP;
if(Servo_AUX2)
packet[12] |= FLAG_V9X9_LED;
if(Servo_AUX3)
packet[10] |= FLAG_V9X9_CAMERA;
if(Servo_AUX4)
packet[10] |= FLAG_V9X9_VIDEO;
break;
case V6X6:
packet[13] = 0x03; // 3 = 100% rate (0=40%, 1=60%, 2=80%)
packet[14] = 0x00;
if(Servo_AUX1)
packet[14] |= FLAG_V6X6_FLIP;
if(Servo_AUX2)
packet[14] |= FLAG_V6X6_LED;
if(Servo_AUX3)
packet[14] |= FLAG_V6X6_CAMERA;
if(Servo_AUX4)
packet[14] |= FLAG_V6X6_VIDEO;
if(Servo_AUX5)
{
packet[13] |= FLAG_V6X6_HLESS1;
packet[14] |= FLAG_V6X6_HLESS2;
}
if(Servo_AUX6) //use option to manipulate these bytes
packet[14] |= FLAG_V6X6_RTH;
if(Servo_AUX7)
packet[14] |= FLAG_V6X6_XCAL;
if(Servo_AUX8)
packet[14] |= FLAG_V6X6_YCAL;
packet[15] = 0x10; // unknown
packet[16] = 0x10; // unknown
packet[17] = 0xAA; // unknown
packet[18] = 0xAA; // unknown
packet[19] = 0x60; // unknown, changes at irregular interval in stock TX
packet[20] = 0x02; // unknown
break;
case V912:
seq_counter++;
if( seq_counter > 9)
seq_counter = 0;
packet[12] |= 0x20; // bit 6 is always set ?
packet[13] = 0x00; // unknown
packet[14] = 0x00;
if(Servo_AUX1)
packet[14] = FLAG_V912_BTMBTN;
if(Servo_AUX2)
packet[14] |= FLAG_V912_TOPBTN;
packet[15] = 0x27; // [15] and [16] apparently hold an analog channel with a value lower than 1000
packet[16] = 0x03; // maybe it's there for a pitch channel for a CP copter ?
packet[17] = pgm_read_byte( &V912_X17_SEQ[seq_counter] ) ; // not sure what [17] & [18] are for
if(seq_counter == 0) // V912 Rx does not even read those bytes... [17-20]
packet[18] = 0x02;
else
packet[18] = 0x00;
packet[19] = 0x00; // unknown
packet[20] = 0x00; // unknown
break;
default:
break;
}
>>>>>>> refs/remotes/pascallanger/master
}
static void __attribute__((unused)) flysky_build_packet(uint8_t init)
@ -161,12 +242,20 @@ 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];
<<<<<<< HEAD
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)
}
=======
for(i = 0; i < 8; i++)
{
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)
}
>>>>>>> refs/remotes/pascallanger/master
flysky_apply_extension_flags();
}
@ -180,6 +269,7 @@ uint16_t ReadFlySky()
if (! bind_counter)
BIND_DONE;
}
<<<<<<< HEAD
else
{
flysky_build_packet(0);
@ -207,7 +297,62 @@ uint16_t initFlySky() {
else
bind_counter = 0;
return 2400;
=======
else
{
flysky_build_packet(0);
A7105_WriteData(21, hopping_frequency[hopping_frequency_no]);
hopping_frequency_no = (hopping_frequency_no + 1) & 0x0F;
A7105_SetPower();
}
return 1510; //1460 on deviation but not working with the latest V911 bricks... Turnigy 9X v2 is 1533, Flysky TX for 9XR/9XR Pro is 1510, V911 TX is 1490.
}
const uint8_t PROGMEM tx_channels[8][4] = {
{ 0x12, 0x34, 0x56, 0x78},
{ 0x18, 0x27, 0x36, 0x45},
{ 0x41, 0x82, 0x36, 0x57},
{ 0x84, 0x13, 0x65, 0x72},
{ 0x87, 0x64, 0x15, 0x32},
{ 0x76, 0x84, 0x13, 0x52},
{ 0x71, 0x62, 0x84, 0x35},
{ 0x71, 0x86, 0x43, 0x52}
};
uint16_t initFlySky()
{
uint8_t chanrow;
uint8_t chanoffset;
uint8_t temp;
A7105_Init(INIT_FLYSKY); //flysky_init();
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;
chanoffset=rx_tx_addr[3]/16;
// Build frequency hop table
for(uint8_t i=0;i<16;i++)
{
temp=pgm_read_byte_near(&tx_channels[chanrow>>1][i>>2]);
if(i&0x01)
temp&=0x0F;
else
temp>>=4;
temp*=0x0A;
if(i&0x02)
temp+=0x50;
hopping_frequency[((chanrow&1)?15-i:i)]=temp-chanoffset;
}
hopping_frequency_no=0;
if(IS_AUTOBIND_FLAG_on)
bind_counter = FLYSKY_BIND_COUNT;
else
bind_counter = 0;
return 2400;
>>>>>>> refs/remotes/pascallanger/master
}
#endif

View File

@ -0,0 +1,208 @@
/*
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(FRSKYD_CC2500_INO)
#include "iface_cc2500.h"
static void __attribute__((unused)) frsky2way_init(uint8_t bind)
{
// Configure cc2500 for tx mode
//
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);
}
prev_option = option ;
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
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_0A_CHANNR, 0x00);
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);
//#######END INIT########
}
static uint8_t __attribute__((unused)) get_chan_num(uint16_t idx)
{
uint8_t ret = (idx * 0x1e) % 0xeb;
if(idx == 3 || idx == 23 || idx == 47)
ret++;
if(idx > 47)
return 0;
return ret;
}
static void __attribute__((unused)) frsky2way_build_bind_packet()
{
//11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01
//11 03 01 19 3e 00 02 8e 2f bb 5c 00 00 00 00 00 00 01
packet[0] = 0x11;
packet[1] = 0x03;
packet[2] = 0x01;
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
uint16_t idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = get_chan_num(idx++);
packet[7] = get_chan_num(idx++);
packet[8] = get_chan_num(idx++);
packet[9] = get_chan_num(idx++);
packet[10] = get_chan_num(idx++);
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x00;
packet[16] = 0x00;
packet[17] = 0x01;
}
static void __attribute__((unused)) frsky2way_data_frame()
{//pachet[4] is telemetry user frame counter(hub)
//11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88
//11 57 12 00 00 01 f2 f2 f2 f2 06 06 ca ca ca ca 18 18
packet[0] = 0x11; //Length
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = counter;//
#if defined TELEMETRY
packet[4] = telemetry_counter;
#else
packet[4] = 0x00;
#endif
packet[5] = 0x01;
//
packet[10] = 0;
packet[11] = 0;
packet[16] = 0;
packet[17] = 0;
for(uint8_t i = 0; i < 8; i++)
{
uint16_t value;
value = convert_channel_frsky(i);
if(i < 4)
{
packet[6+i] = value & 0xff;
packet[10+(i>>1)] |= ((value >> 8) & 0x0f) << (4 *(i & 0x01));
}
else
{
packet[8+i] = value & 0xff;
packet[16+((i-4)>>1)] |= ((value >> 8) & 0x0f) << (4 * ((i-4) & 0x01));
}
}
}
uint16_t initFrSky_2way()
{
if(IS_AUTOBIND_FLAG_on)
{
frsky2way_init(1);
state = FRSKY_BIND;
}
else
{
frsky2way_init(0);
state = FRSKY_DATA2;
}
return 10000;
}
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_WriteData(packet, packet[0]+1);
state++;
return 9000;
}
if (state == FRSKY_BIND_DONE)
{
state = FRSKY_DATA2;
frsky2way_init(0);
counter = 0;
BIND_DONE;
}
else
if (state == FRSKY_DATA5)
{
CC2500_Strobe(CC2500_SRX);//0x34 RX enable
state = FRSKY_DATA1;
return 9200;
}
counter = (counter + 1) % 188;
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);
state++;
return 1300;
}
else
{
if (state == FRSKY_DATA1)
{
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len && len<=MAX_PKT)//27 bytes
{
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.
#endif
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower(); // Set tx_power
}
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ;
}
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);
frsky2way_data_frame();
CC2500_WriteData(packet, packet[0]+1);
state++;
}
return state == FRSKY_DATA4 ? 7500 : 9000;
}
#endif

View File

@ -0,0 +1,209 @@
/*
This project is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Multiprotocol is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(FRSKYV_CC2500_INO)
#define FRSKYV_BIND_COUNT 200
enum {
FRSKYV_DATA1=0,
FRSKYV_DATA2,
FRSKYV_DATA3,
FRSKYV_DATA4,
FRSKYV_DATA5
};
#include "iface_cc2500.h"
const PROGMEM uint8_t FRSKYV_cc2500_conf[][2]={
{ CC2500_17_MCSM1, 0x0c },
{ CC2500_18_MCSM0, 0x18 },
{ CC2500_06_PKTLEN, 0xff },
{ CC2500_07_PKTCTRL1, 0x04 },
{ CC2500_08_PKTCTRL0, 0x05 },
{ CC2500_3E_PATABLE, 0xfe },
{ CC2500_0B_FSCTRL1, 0x08 },
{ CC2500_0C_FSCTRL0, 0x00 },
{ CC2500_0D_FREQ2, 0x5c },
{ CC2500_0E_FREQ1, 0x58 },
{ CC2500_0F_FREQ0, 0x9d },
{ CC2500_10_MDMCFG4, 0xaa },
{ CC2500_11_MDMCFG3, 0x10 },
{ CC2500_12_MDMCFG2, 0x93 },
{ CC2500_13_MDMCFG1, 0x23 },
{ CC2500_14_MDMCFG0, 0x7a },
{ CC2500_15_DEVIATN, 0x41 }
};
static void __attribute__((unused)) FRSKYV_init()
{
for(uint8_t i=0;i<17;i++)
{
uint8_t reg=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][1]);
if(reg==CC2500_0C_FSCTRL0)
val=option;
CC2500_WriteReg(reg,val);
}
prev_option = option ;
for(uint8_t i=19;i<36;i++)
{
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
CC2500_WriteReg(reg,val);
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
}
static uint8_t __attribute__((unused)) FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len)
{
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x80)
result = (result << 1) ^ 0x07;
else
result = result << 1;
}
return result;
}
static uint8_t __attribute__((unused)) FRSKYV_crc8_le(uint8_t *data, uint8_t len)
{
uint8_t result = 0xD6;
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x01)
result = (result >> 1) ^ 0x83;
else
result = result >> 1;
}
return result;
}
static void __attribute__((unused)) FRSKYV_build_bind_packet()
{
//0e 03 01 57 12 00 06 0b 10 15 1a 00 00 00 61
packet[0] = 0x0e; //Length
packet[1] = 0x03; //Packet type
packet[2] = 0x01; //Packet type
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
packet[5] = (binding_idx % 10) * 5;
packet[6] = packet[5] * 5 + 6;
packet[7] = packet[5] * 5 + 11;
packet[8] = packet[5] * 5 + 16;
packet[9] = packet[5] * 5 + 21;
packet[10] = packet[5] * 5 + 26;
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = FRSKYV_crc8(0x93, packet, 14);
}
static uint8_t __attribute__((unused)) FRSKYV_calc_channel()
{
uint32_t temp=seed;
temp = (temp * 0xaa) % 0x7673;
seed = temp;
return (seed & 0xff) % 0x32;
}
static void __attribute__((unused)) FRSKYV_build_data_packet()
{
uint8_t idx = 0; // transmit lower channels
packet[0] = 0x0e;
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = seed & 0xff;
packet[4] = seed >> 8;
if (phase == FRSKYV_DATA1 || phase == FRSKYV_DATA3)
packet[5] = 0x0f;
else
if(phase == FRSKYV_DATA2 || phase == FRSKYV_DATA4)
{
packet[5] = 0xf0;
idx=4; // transmit upper channels
}
else
packet[5] = 0x00;
for(uint8_t i = 0; i < 4; i++)
{
uint16_t value = convert_channel_frsky(i+idx);
packet[2*i + 6] = value & 0xff;
packet[2*i + 7] = value >> 8;
}
packet[14] = FRSKYV_crc8(crc8, packet, 14);
}
uint16_t ReadFRSKYV()
{
if(IS_BIND_DONE_on)
{ // Normal operation
uint8_t chan = FRSKYV_calc_channel();
CC2500_Strobe(CC2500_SIDLE);
if (option != prev_option)
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
prev_option=option;
}
CC2500_WriteReg(CC2500_0A_CHANNR, chan * 5 + 6);
FRSKYV_build_data_packet();
if (phase == FRSKYV_DATA5)
{
CC2500_SetPower();
phase = FRSKYV_DATA1;
}
else
phase++;
CC2500_WriteData(packet, packet[0]+1);
return 9006;
}
// Bind mode
FRSKYV_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteData(packet, packet[0]+1);
binding_idx++;
if(binding_idx>=FRSKYV_BIND_COUNT)
BIND_DONE;
return 53460;
}
uint16_t initFRSKYV()
{
//ID is 15 bits. Using rx_tx_addr[2] and rx_tx_addr[3] since we want to use RX_Num for model match
rx_tx_addr[2]&=0x7F;
crc8 = FRSKYV_crc8_le(rx_tx_addr+2, 2);
FRSKYV_init();
seed = 1;
binding_idx=0;
phase = FRSKYV_DATA1;
return 10000;
}
#endif

View File

@ -218,6 +218,7 @@
packet[29]=lowByte(crc);
}
<<<<<<< HEAD
uint16_t ReadFrSkyX()
{
switch(state)
@ -306,4 +307,315 @@
}
return 10000;
}
=======
uint8_t chanskip;
uint8_t counter_rst;
uint8_t ctr;
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_25_FSCAL1, calData[ch]);
CC2500_WriteReg(CC2500_0A_CHANNR, ch==47? 0:hop(ch));
}
static void __attribute__((unused)) frskyX_init()
{
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_06_PKTLEN)
val=0x1E;
else
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;
CC2500_WriteReg(reg,val);
}
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x04);
prev_option = option ;
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,hop(c));
CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900);//
calData[c] = CC2500_ReadReg(CC2500_25_FSCAL1);
}
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR,0x00);
CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900);
calData[47] = 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);
}
//**CRC**
const uint16_t PROGMEM CRC_Short[]={
0x0000, 0x1189, 0x2312, 0x329B, 0x4624, 0x57AD, 0x6536, 0x74BF,
0x8C48, 0x9DC1, 0xAF5A, 0xBED3, 0xCA6C, 0xDBE5, 0xE97E, 0xF8F7 };
static uint16_t CRCTable(uint8_t val)
{
uint16_t word ;
word = pgm_read_word(&CRC_Short[val&0x0F]) ;
val /= 16 ;
return word ^ (0x1081 * val) ;
}
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) ^ CRCTable((uint8_t)(crc>>8) ^ *data++);
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]-servo_min_125)*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] = hop(idx++);
packet[7] = hop(idx++);
packet[8] = hop(idx++);
packet[9] = hop(idx++);
packet[10] = hop(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)+hopping_frequency_no;
packet[5] = counter_rst;
packet[6] = RX_num;
//packet[7] = FLAGS 00 - standard packet
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
//20 - range check packet
packet[7] = 0;
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);
hopping_frequency_no=0;
BIND_DONE;
state++;
break;
case FRSKY_DATA1:
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ;
}
CC2500_SetTxRxMode(TX_EN);
set_start(hopping_frequency_no);
CC2500_SetPower();
CC2500_Strobe(CC2500_SFRX);
hopping_frequency_no = (hopping_frequency_no+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)
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;
}
>>>>>>> refs/remotes/pascallanger/master
#endif

View File

@ -120,10 +120,9 @@ 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];
temp=map(limit_channel_100(j),PPM_MIN_100,PPM_MAX_100,0,1000);
j=CH_AETR[i];
temp=map(limit_channel_100(j),servo_min_100,servo_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;
if (j == AUX3)

View File

@ -0,0 +1,247 @@
/*
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(HONTAI_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define HONTAI_BIND_COUNT 80
#define HONTAI_PACKET_PERIOD 13500
#define HONTAI_INITIAL_WAIT 500
#define HONTAI_BIND_HONTAI_PACKET_SIZE 10
#define HONTAI_PACKET_SIZE 12
#define HONTAI_RF_BIND_CHANNEL 0
enum{
HONTAI_FLAG_FLIP = 0x01,
HONTAI_FLAG_PICTURE = 0x02,
HONTAI_FLAG_VIDEO = 0x04,
HONTAI_FLAG_HEADLESS = 0x08,
HONTAI_FLAG_RTH = 0x10,
HONTAI_FLAG_CALIBRATE = 0x20,
};
// proudly swiped from http://www.drdobbs.com/implementing-the-ccitt-cyclical-redundan/199904926
#define HONTAI_POLY 0x8408
static void __attribute__((unused)) crc16(uint8_t *data_p, uint8_t length)
{
uint16_t crc = 0xffff;
length -= 2;
do
{
for (uint8_t i = 0, data = (uint8_t)*data_p++;
i < 8;
i++, data >>= 1)
{
if ((crc & 0x01) ^ (data & 0x01))
crc = (crc >> 1) ^ HONTAI_POLY;
else
crc >>= 1;
}
} while (--length);
crc = ~crc;
*data_p++ = crc & 0xff;
*data_p = crc >> 8;
}
static void __attribute__((unused)) HONTAI_send_packet(uint8_t bind)
{
uint8_t packet_size;
if (bind)
{
memcpy(packet, rx_tx_addr, 5);
memset(&packet[5], 0, 3);
packet_size=HONTAI_BIND_HONTAI_PACKET_SIZE;
}
else
{
if(sub_protocol == FORMAT_JJRCX1)
packet[0] = GET_FLAG(Servo_AUX2, 0x02); // Arm
else
packet[0] = 0x0b;
packet[1] = 0x00;
packet[2] = 0x00;
packet[3] = (convert_channel_8b_scale(THROTTLE, 0, 127) << 1) // Throttle
| GET_FLAG(Servo_AUX3, 0x01); // Picture
packet[4] = convert_channel_8b_scale(AILERON, 63, 0); // Aileron
if(sub_protocol == FORMAT_HONTAI)
{
packet[4] |= GET_FLAG(Servo_AUX6, 0x80) // RTH
| GET_FLAG(Servo_AUX5, 0x40); // Headless
}
else
{
packet[4] |= 0x80; // not sure what this bit does
if (sub_protocol == FORMAT_X5C1)
packet[4] |= GET_FLAG(Servo_AUX2, 0x40); // Lights (X5C1)
}
packet[5] = convert_channel_8b_scale(ELEVATOR, 0, 63) // Elevator
| GET_FLAG(Servo_AUX7, 0x80) // Calibrate
| GET_FLAG(Servo_AUX1, 0x40); // Flip
packet[6] = convert_channel_8b_scale(RUDDER, 0, 63) // Rudder
| GET_FLAG(Servo_AUX4, 0x80); // Video
if(sub_protocol == FORMAT_X5C1)
packet[7] = convert_channel_8b_scale(AILERON, 0, 63)-31; // Aileron trim
else
packet[7] = convert_channel_8b_scale(AILERON, 0, 32)-16; // Aileron trim
if(sub_protocol == FORMAT_HONTAI)
packet[8] = convert_channel_8b_scale(RUDDER, 0, 32)-16; // Rudder trim
else
{
packet[8] = 0xc0 // Always in expert mode
| GET_FLAG(Servo_AUX6, 0x02) // RTH
| GET_FLAG(Servo_AUX5, 0x01); // Headless
}
if (sub_protocol == FORMAT_X5C1)
packet[9] = convert_channel_8b_scale(ELEVATOR, 0, 63)-31; // Elevator trim
else
packet[9] = convert_channel_8b_scale(ELEVATOR, 0, 32)-16; // Elevator trim
packet_size=HONTAI_PACKET_SIZE;
}
crc16(packet, packet_size);
// Power on, TX mode, 2byte CRC
if(sub_protocol == FORMAT_JJRCX1)
NRF24L01_SetTxRxMode(TX_EN);
else
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_05_RF_CH, bind ? HONTAI_RF_BIND_CHANNEL : hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no %= 3;
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
if(sub_protocol == FORMAT_JJRCX1)
NRF24L01_WritePayload(packet, packet_size);
else
XN297_WritePayload(packet, packet_size);
NRF24L01_SetPower();
}
static void __attribute__((unused)) HONTAI_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
if(sub_protocol == FORMAT_JJRCX1)
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"\xd2\xb5\x99\xb3\x4a", 5);
else
XN297_SetTXAddr((const uint8_t*)"\xd2\xb5\x99\xb3\x4a", 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 Acknowldgement on all data pipes
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_Activate(0x73); // Activate feature register
if(sub_protocol == FORMAT_JJRCX1)
{
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xff); // JJRC uses dynamic payload length
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); // match other stock settings even though AA disabled...
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07);
}
else
{
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x00);
}
NRF24L01_Activate(0x73); // Deactivate feature register
}
const uint8_t PROGMEM hopping_frequency_nonels[][3] = {
{0x05, 0x19, 0x28}, // Hontai
{0x0a, 0x1e, 0x2d}}; // JJRC X1
const uint8_t PROGMEM addr_vals[4][16] = {
{0x24, 0x26, 0x2a, 0x2c, 0x32, 0x34, 0x36, 0x4a, 0x4c, 0x4e, 0x54, 0x56, 0x5a, 0x64, 0x66, 0x6a},
{0x92, 0x94, 0x96, 0x9a, 0xa4, 0xa6, 0xac, 0xb2, 0xb4, 0xb6, 0xca, 0xcc, 0xd2, 0xd4, 0xd6, 0xda},
{0x93, 0x95, 0x99, 0x9b, 0xa5, 0xa9, 0xab, 0xad, 0xb3, 0xb5, 0xc9, 0xcb, 0xcd, 0xd3, 0xd5, 0xd9},
{0x25, 0x29, 0x2b, 0x2d, 0x33, 0x35, 0x49, 0x4b, 0x4d, 0x59, 0x5b, 0x65, 0x69, 0x6b, 0x6d, 0x6e}};
static void __attribute__((unused)) HONTAI_init2()
{
uint8_t data_tx_addr[5];
//TX address
data_tx_addr[0] = pgm_read_byte_near( &addr_vals[0][ rx_tx_addr[3] & 0x0f]);
data_tx_addr[1] = pgm_read_byte_near( &addr_vals[1][(rx_tx_addr[3] >> 4) & 0x0f]);
data_tx_addr[2] = pgm_read_byte_near( &addr_vals[2][ rx_tx_addr[4] & 0x0f]);
data_tx_addr[3] = pgm_read_byte_near( &addr_vals[3][(rx_tx_addr[4] >> 4) & 0x0f]);
data_tx_addr[4] = 0x24;
if(sub_protocol == FORMAT_JJRCX1)
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, data_tx_addr, sizeof(data_tx_addr));
else
XN297_SetTXAddr(data_tx_addr, sizeof(data_tx_addr));
//Hopping frequency table
for(uint8_t i=0;i<3;i++)
hopping_frequency[i]=pgm_read_byte_near( &hopping_frequency_nonels[sub_protocol == FORMAT_JJRCX1?1:0][i] );
hopping_frequency_no=0;
}
static void __attribute__((unused)) HONTAI_initialize_txid()
{
rx_tx_addr[4] = rx_tx_addr[2];
if(sub_protocol == FORMAT_HONTAI)
{
rx_tx_addr[0] = 0x4c; // first three bytes some kind of model id? - set same as stock tx
rx_tx_addr[1] = 0x4b;
rx_tx_addr[2] = 0x3a;
}
else
{
rx_tx_addr[0] = 0x4b; // JJRC X1
rx_tx_addr[1] = 0x59;
rx_tx_addr[2] = 0x3a;
}
}
uint16_t HONTAI_callback()
{
if(bind_counter!=0)
{
HONTAI_send_packet(1);
bind_counter--;
if (bind_counter == 0)
{
HONTAI_init2();
BIND_DONE;
}
}
else
HONTAI_send_packet(0);
return HONTAI_PACKET_PERIOD;
}
uint16_t initHONTAI()
{
BIND_IN_PROGRESS; // autobind protocol
bind_counter = HONTAI_BIND_COUNT;
HONTAI_initialize_txid();
HONTAI_init();
return HONTAI_INITIAL_WAIT;
}
#endif

View File

@ -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;
@ -345,7 +345,6 @@ uint16_t initHubsan() {
const uint8_t allowed_ch[] = {0x14, 0x1e, 0x28, 0x32, 0x3c, 0x46, 0x50, 0x5a, 0x64, 0x6e, 0x78, 0x82};
A7105_Init(INIT_HUBSAN); //hubsan_init();
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
sessionid = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16);
channel = allowed_ch[random(0xfefefefe) % sizeof(allowed_ch)];

View File

@ -0,0 +1,249 @@
/*
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 PROGMEM j6pro_bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49};
const uint8_t j6pro_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(j6pro_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_PROGMEM_ConfigSOPCode(j6pro_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_PROGMEM_ConfigSOPCode(DEVO_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()
{
j6pro_cyrf_init();
if(IS_AUTOBIND_FLAG_on) {
phase = J6PRO_BIND;
}
else {
phase = J6PRO_CHANSEL;
}
return 2400;
}
#endif

View File

@ -246,7 +246,11 @@ static void __attribute__((unused)) kn_init()
NRF24L01_Initialize();
<<<<<<< HEAD
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
=======
NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO));
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
@ -259,7 +263,11 @@ static void __attribute__((unused)) kn_init()
NRF24L01_Activate(0x73);
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0
// Enable: Dynamic Payload Length to enable PCF
<<<<<<< HEAD
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL));
=======
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, _BV(NRF2401_1D_EN_DPL));
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_SetPower();

View File

@ -12,7 +12,11 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
<<<<<<< HEAD
// compatible with MJX WLH08, X600, X800, H26D
=======
// compatible with MJX WLH08, X600, X800, H26D, Eachine E010
>>>>>>> refs/remotes/pascallanger/master
// Last sync with hexfet new_protocols/mjxq_nrf24l01.c dated 2016-01-17
#if defined(MJXQ_NRF24L01_INO)
@ -26,6 +30,20 @@
#define MJXQ_RF_NUM_CHANNELS 4
#define MJXQ_ADDRESS_LENGTH 5
<<<<<<< HEAD
=======
// haven't figured out txid<-->rf channel mapping for MJX models
const uint8_t PROGMEM MJXQ_map_rfchan[][4] = {
{0x0A, 0x46, 0x3A, 0x42},
{0x0A, 0x3C, 0x36, 0x3F},
{0x0A, 0x43, 0x36, 0x3F} };
const uint8_t PROGMEM MJXQ_map_txid[][3] = {
{0xF8, 0x4F, 0x1C},
{0xC8, 0x6E, 0x02},
{0x48, 0x6A, 0x40} };
>>>>>>> refs/remotes/pascallanger/master
#define MJXQ_PAN_TILT_COUNT 16 // for H26D - match stock tx timing
#define MJXQ_PAN_DOWN 0x08
#define MJXQ_PAN_UP 0x04
@ -39,6 +57,7 @@ static uint8_t __attribute__((unused)) MJXQ_pan_tilt_value()
packet_count++;
if(packet_count & MJXQ_PAN_TILT_COUNT)
{
<<<<<<< HEAD
if(Servo_AUX8)
pan=MJXQ_PAN_UP;
if(Servo_data[AUX8]<PPM_MIN_COMMAND)
@ -47,6 +66,16 @@ static uint8_t __attribute__((unused)) MJXQ_pan_tilt_value()
pan=MJXQ_TILT_UP;
if(Servo_data[AUX9]<PPM_MIN_COMMAND)
pan=MJXQ_TILT_DOWN;
=======
if(Servo_data[AUX8]>PPM_MAX_COMMAND)
pan=MJXQ_PAN_UP;
if(Servo_data[AUX8]<PPM_MIN_COMMAND)
pan=MJXQ_PAN_DOWN;
if(Servo_data[AUX9]>PPM_MAX_COMMAND)
pan+=MJXQ_TILT_UP;
if(Servo_data[AUX9]<PPM_MIN_COMMAND)
pan+=MJXQ_TILT_DOWN;
>>>>>>> refs/remotes/pascallanger/master
}
return pan;
}
@ -57,10 +86,17 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
packet[0] = convert_channel_8b(THROTTLE);
packet[1] = convert_channel_s8b(RUDDER);
packet[4] = 0x40; // rudder does not work well with dyntrim
<<<<<<< HEAD
packet[2] = convert_channel_s8b(ELEVATOR);
packet[5] = MJXQ_CHAN2TRIM(packet[2]); // trim elevator
packet[3] = convert_channel_s8b(AILERON);
packet[6] = MJXQ_CHAN2TRIM(packet[3]); // trim aileron
=======
packet[2] = 0x80 ^ convert_channel_s8b(ELEVATOR);
packet[5] = GET_FLAG(Servo_AUX5, 1) ? 0x40 : MJXQ_CHAN2TRIM(packet[2]); // trim elevator
packet[3] = convert_channel_s8b(AILERON);
packet[6] = GET_FLAG(Servo_AUX5, 1) ? 0x40 : MJXQ_CHAN2TRIM(packet[3]); // trim aileron
>>>>>>> refs/remotes/pascallanger/master
packet[7] = rx_tx_addr[0];
packet[8] = rx_tx_addr[1];
packet[9] = rx_tx_addr[2];
@ -85,6 +121,10 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
packet[10]=MJXQ_pan_tilt_value();
// fall through on purpose - no break
case WLH08:
<<<<<<< HEAD
=======
case E010:
>>>>>>> refs/remotes/pascallanger/master
packet[10] += GET_FLAG(Servo_AUX6, 0x02) //RTH
| GET_FLAG(Servo_AUX5, 0x01); //HEADLESS
if (!bind)
@ -97,11 +137,14 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
}
break;
case X600:
<<<<<<< HEAD
if(Servo_AUX5) //HEADLESS
{ // driven trims cause issues when headless is enabled
packet[5] = 0x40;
packet[6] = 0x40;
}
=======
>>>>>>> refs/remotes/pascallanger/master
packet[10] = GET_FLAG(!Servo_AUX2, 0x02); //LED
packet[11] = GET_FLAG(Servo_AUX6, 0x01); //RTH
if (!bind)
@ -135,7 +178,11 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
if (sub_protocol == H26D)
NRF24L01_SetTxRxMode(TX_EN);
else
<<<<<<< HEAD
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
=======
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++ / 2]);
hopping_frequency_no %= 2 * MJXQ_RF_NUM_CHANNELS; // channels repeated
@ -158,12 +205,20 @@ static void __attribute__((unused)) MJXQ_init()
if (sub_protocol == WLH08)
memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS);
else
<<<<<<< HEAD
if (sub_protocol == H26D)
=======
if (sub_protocol == H26D || sub_protocol == E010)
>>>>>>> refs/remotes/pascallanger/master
memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS);
else
{
memcpy(hopping_frequency, "\x0a\x35\x42\x3d", MJXQ_RF_NUM_CHANNELS);
<<<<<<< HEAD
memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_RF_NUM_CHANNELS);
=======
memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_ADDRESS_LENGTH);
>>>>>>> refs/remotes/pascallanger/master
}
@ -182,12 +237,20 @@ static void __attribute__((unused)) MJXQ_init()
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, MJXQ_PACKET_SIZE); // rx pipe 0 (used only for blue board)
<<<<<<< HEAD
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
=======
if (sub_protocol == E010)
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250K
else
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_SetPower();
}
static void __attribute__((unused)) MJXQ_init2()
{
<<<<<<< HEAD
// haven't figured out txid<-->rf channel mapping for MJX models
static const uint8_t rf_map[][4] = {
{0x0A, 0x46, 0x3A, 0x42},
@ -198,10 +261,19 @@ static void __attribute__((unused)) MJXQ_init2()
else
if (sub_protocol == WLH08)
memcpy(hopping_frequency, rf_map[rx_tx_addr[0]%3], MJXQ_RF_NUM_CHANNELS);
=======
if (sub_protocol == H26D)
memcpy(hopping_frequency, "\x32\x3e\x42\x4e", MJXQ_RF_NUM_CHANNELS);
else
if (sub_protocol != WLH08 && sub_protocol != E010)
for(uint8_t i=0;i<MJXQ_RF_NUM_CHANNELS;i++)
hopping_frequency[i]=pgm_read_byte_near( &MJXQ_map_rfchan[rx_tx_addr[4]%3][i] );
>>>>>>> refs/remotes/pascallanger/master
}
static void __attribute__((unused)) MJXQ_initialize_txid()
{
<<<<<<< HEAD
// haven't figured out txid<-->rf channel mapping for MJX models
static const uint8_t tx_map[][3]={
{0xF8, 0x4F, 0x1C},
@ -211,6 +283,17 @@ static void __attribute__((unused)) MJXQ_initialize_txid()
rx_tx_addr[0]&=0xF8; // txid must be multiple of 8
else
memcpy(rx_tx_addr,tx_map[rx_tx_addr[0]%3],3);
=======
rx_tx_addr[0]&=0xF8;
if (sub_protocol == E010)
{
rx_tx_addr[1]=(rx_tx_addr[1]&0xF0)|0x0C;
rx_tx_addr[2]&=0xF0;
}
else
for(uint8_t i=0;i<3;i++)
rx_tx_addr[i]=pgm_read_byte_near( &MJXQ_map_txid[rx_tx_addr[4]%3][i] );
>>>>>>> refs/remotes/pascallanger/master
}
uint16_t MJXQ_callback()

View File

@ -12,7 +12,11 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
<<<<<<< HEAD
// compatible with MT99xx, Eachine H7, Yi Zhan i6S
=======
// compatible with MT99xx, Eachine H7, Yi Zhan i6S and LS114/124
>>>>>>> refs/remotes/pascallanger/master
// Last sync with Goebish mt99xx_nrf24l01.c dated 2016-01-29
#if defined(MT99XX_NRF24L01_INO)
@ -37,12 +41,26 @@ enum{
FLAG_MT_FLIP = 0x80,
};
<<<<<<< HEAD
=======
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,
};
>>>>>>> refs/remotes/pascallanger/master
enum {
MT99XX_INIT = 0,
MT99XX_BIND,
MT99XX_DATA
};
<<<<<<< HEAD
static void __attribute__((unused)) MT99XX_send_packet()
{
const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60};
@ -71,6 +89,56 @@ static void __attribute__((unused)) MT99XX_send_packet()
// 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];
=======
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};
static uint8_t yz_seq_num=0;
static uint8_t ls_counter=0;
if(sub_protocol != YZ)
{ // 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 ,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 );
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
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;
}
>>>>>>> refs/remotes/pascallanger/master
uint8_t result=checksum_offset;
for(uint8_t i=0; i<8; i++)
result += packet[i];
@ -79,9 +147,15 @@ static void __attribute__((unused)) MT99XX_send_packet()
else
{ // YZ
packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0x64); // throttle
<<<<<<< HEAD
packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0x64); // rudder
packet[2] = convert_channel_8b_scale(ELEVATOR,0x00,0x64); // elevator
packet[3] = convert_channel_8b_scale(AILERON ,0x00,0x64); // aileron
=======
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 ,0x64,0x00); // aileron
>>>>>>> refs/remotes/pascallanger/master
if(packet_count++ >= 23)
{
yz_seq_num ++;
@ -102,7 +176,14 @@ static void __attribute__((unused)) MT99XX_send_packet()
packet[8] = 0xff;
}
<<<<<<< HEAD
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);
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
XN297_WritePayload(packet, MT99XX_PACKET_SIZE);
@ -120,8 +201,16 @@ static void __attribute__((unused)) MT99XX_send_packet()
static void __attribute__((unused)) MT99XX_init()
{
NRF24L01_Initialize();
<<<<<<< HEAD
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_FlushTx();
=======
if(sub_protocol == YZ)
XN297_SetScrambledMode(XN297_UNSCRAMBLED);
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_FlushTx();
XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5);
>>>>>>> refs/remotes/pascallanger/master
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 +222,40 @@ static void __attribute__((unused)) MT99XX_init()
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
<<<<<<< HEAD
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) | (sub_protocol == YZ ? BV(XN297_UNSCRAMBLED):0) );
XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5);
=======
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP) );
>>>>>>> refs/remotes/pascallanger/master
}
static void __attribute__((unused)) MT99XX_initialize_txid()
{
<<<<<<< HEAD
=======
rx_tx_addr[3] = 0xCC;
rx_tx_addr[4] = 0xCC;
>>>>>>> refs/remotes/pascallanger/master
if(sub_protocol == YZ)
{
rx_tx_addr[0] = 0x53; // test (SB id)
rx_tx_addr[1] = 0x00;
<<<<<<< HEAD
}
checksum_offset = (rx_tx_addr[0] + rx_tx_addr[1]) & 0xff;
=======
rx_tx_addr[2] = 0x00;
}
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];
>>>>>>> refs/remotes/pascallanger/master
channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8;
}
@ -157,16 +267,26 @@ uint16_t MT99XX_callback()
{
if (bind_counter == 0)
{
<<<<<<< HEAD
rx_tx_addr[2] = 0x00;
rx_tx_addr[3] = 0xCC;
rx_tx_addr[4] = 0xCC;
=======
>>>>>>> refs/remotes/pascallanger/master
// set tx address for data packets
XN297_SetTXAddr(rx_tx_addr, 5);
BIND_DONE;
}
else
{
<<<<<<< HEAD
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]);
>>>>>>> refs/remotes/pascallanger/master
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
XN297_WritePayload(packet, MT99XX_PACKET_SIZE); // bind packet
@ -193,6 +313,7 @@ uint16_t initMT99XX(void)
MT99XX_init();
packet[0] = 0x20;
<<<<<<< HEAD
if(sub_protocol!=YZ)
{ // MT99 & H7
packet_period = MT99XX_PACKET_PERIOD_MT;
@ -210,6 +331,32 @@ uint16_t initMT99XX(void)
packet[4] = rx_tx_addr[0]; // 1st byte for data state tx address
packet[5] = rx_tx_addr[1]; // 2nd byte for data state tx address (always 0x00 on Yi Zhan ?)
packet[6] = 0x00; // 3rd byte for data state tx address (always 0x00 ?)
=======
packet_period = MT99XX_PACKET_PERIOD_MT;
switch(sub_protocol)
{ // MT99 & H7
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;
}
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
>>>>>>> refs/remotes/pascallanger/master
packet[7] = checksum_offset; // checksum offset
packet[8] = 0xAA; // fixed
packet_count=0;

View 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

View File

@ -0,0 +1,162 @@
#define ARDUINO_AVR_PRO 1
//#define __AVR_ATmega328P__ 1
#define XMEGA 1
// For BLUE module use:
//#define DSM_BLUE
#include <stdlib.h>
#include <string.h>
#include <avr/interrupt.h>
static void protocol_init(void) ;
static void update_aux_flags(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 update_led_status(void) ;
static void set_rx_tx_addr(uint32_t id) ;
uint16_t limit_channel_100(uint8_t ch) ;
void initTXSerial( uint8_t speed);
void Serial_write(uint8_t data);
extern void NRF24L01_Reset(void ) ;
extern void 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 uint16_t initJ6Pro(void) ;
extern uint16_t ReadJ6Pro(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 delayMilliseconds(unsigned long ms) ;
extern void init(void) ;
extern void modules_reset() ;
extern void Update_All() ;
extern void tx_pause() ;
extern void tx_resume() ;
extern void TelemetryUpdate() ;
extern uint16_t initDsm() ;
extern uint16_t ReadDsm() ;
#define yield()
#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)
#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();
#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
// 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 ;
}
#include "Multiprotocol.ino"
#include "SPI.ino"
#include "Convert.ino"
#include "Arduino.ino"
#include "cyrf6936_SPI.ino"
#include "DSM_cyrf6936.ino"
#include "Devo_cyrf6936.ino"
#include "J6Pro_cyrf6936.ino"
#include "Telemetry.ino"
int main(void)
{
init() ;
setup() ;
for(;;)
{
loop() ;
}
}

View File

@ -0,0 +1,485 @@
/*
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/>.
*/
// Check selected board type
#ifndef XMEGA
#if not defined(ARDUINO_AVR_PRO) && not defined(ARDUINO_AVR_MINI) && not defined(ARDUINO_AVR_NANO)
#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
//******************
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105
MODE_HUBSAN = 2, // =>A7105
MODE_FRSKYD = 3, // =>CC2500
MODE_HISKY = 4, // =>NRF24L01
MODE_V2X2 = 5, // =>NRF24L01
MODE_DSM = 6, // =>CYRF6936
MODE_DEVO = 7, // =>CYRF6936
MODE_YD717 = 8, // =>NRF24L01
MODE_KN = 9, // =>NRF24L01
MODE_SYMAX = 10, // =>NRF24L01
MODE_SLT = 11, // =>NRF24L01
MODE_CX10 = 12, // =>NRF24L01
MODE_CG023 = 13, // =>NRF24L01
MODE_BAYANG = 14, // =>NRF24L01
MODE_FRSKYX = 15, // =>CC2500
MODE_ESKY = 16, // =>NRF24L01
MODE_MT99XX = 17, // =>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
MODE_ASSAN = 24, // =>NRF24L01
MODE_FRSKYV = 25, // =>CC2500
MODE_HONTAI = 26, // =>NRF24L01
MODE_OPENLRS = 27, // =>OpenLRS hardware
};
enum Flysky
{
Flysky = 0,
V9X9 = 1,
V6X6 = 2,
V912 = 3
};
enum Hisky
{
Hisky = 0,
HK310 = 1
};
enum DSM
{
DSM2_22 = 0,
DSM2_11 = 1,
DSMX_22 = 2,
DSMX_11 = 3,
DSM_AUTO = 4
};
enum YD717
{
YD717 = 0,
SKYWLKR = 1,
SYMAX4 = 2,
XINXUN = 3,
NIHUI = 4
};
enum KN
{
WLTOYS = 0,
FEILUN = 1
};
enum SYMAX
{
SYMAX = 0,
SYMAX5C = 1
};
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE = 1, // also compatible with CX10-A, CX12
DM007 = 2,
Q282 = 3,
JC3015_1 = 4,
JC3015_2 = 5,
MK33041 = 6,
Q242 = 7
};
enum CG023
{
CG023 = 0,
YD829 = 1,
H8_3D = 2
};
enum MT99XX
{
MT99 = 0,
H7 = 1,
YZ = 2,
LS = 3
};
enum MJXQ
{
WLH08 = 0,
X600 = 1,
X800 = 2,
H26D = 3,
E010 = 4
};
enum FRSKYX
{
CH_16 = 0,
CH_8 = 1,
};
enum HONTAI
{
FORMAT_HONTAI = 0,
FORMAT_JJRCX1 = 1,
FORMAT_X5C1 = 2
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
#define AUTOBIND 1
#define NO_AUTOBIND 0
struct PPM_Parameters
{
uint8_t protocol : 6;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
uint8_t power : 1;
uint8_t autobind : 1;
uint8_t option;
};
// Macros
#define NOP() __asm__ __volatile__("nop")
//*******************
//*** Timer ***
//*******************
#ifdef XMEGA
#define TIFR1 TCC1.INTFLAGS
#define OCF1A_bm TC1_CCAIF_bm
#define OCR1A TCC1.CCA
#define TCNT1 TCC1.CNT
#define UDR0 USARTC0.DATA
#define OCF1B_bm TC1_CCBIF_bm
#define OCR1B TCC1.CCB
#define TIMSK1 TCC1.INTCTRLB
#define SET_TIMSK1_OCIE1B TIMSK1 = (TIMSK1 & 0xF3) | 0x04
#define CLR_TIMSK1_OCIE1B TIMSK1 &= 0xF3
#else
#define OCF1A_bm _BV(OCF1A)
#define OCF1B_bm _BV(OCF1B)
#define SET_TIMSK1_OCIE1B TIMSK1 |= _BV(OCIE1B)
#define CLR_TIMSK1_OCIE1B TIMSK1 &=~_BV(OCIE1B)
#endif
//***************
//*** Flags ***
//***************
#define RX_FLAG_on protocol_flags |= _BV(0)
#define RX_FLAG_off protocol_flags &= ~_BV(0)
#define IS_RX_FLAG_on ( ( protocol_flags & _BV(0) ) !=0 )
//
#define CHANGE_PROTOCOL_FLAG_on protocol_flags |= _BV(1)
#define CHANGE_PROTOCOL_FLAG_off protocol_flags &= ~_BV(1)
#define IS_CHANGE_PROTOCOL_FLAG_on ( ( protocol_flags & _BV(1) ) !=0 )
//
#define POWER_FLAG_on protocol_flags |= _BV(2)
#define POWER_FLAG_off protocol_flags &= ~_BV(2)
#define IS_POWER_FLAG_on ( ( protocol_flags & _BV(2) ) !=0 )
//
#define RANGE_FLAG_on protocol_flags |= _BV(3)
#define RANGE_FLAG_off protocol_flags &= ~_BV(3)
#define IS_RANGE_FLAG_on ( ( protocol_flags & _BV(3) ) !=0 )
//
#define AUTOBIND_FLAG_on protocol_flags |= _BV(4)
#define AUTOBIND_FLAG_off protocol_flags &= ~_BV(4)
#define IS_AUTOBIND_FLAG_on ( ( protocol_flags & _BV(4) ) !=0 )
//
#define BIND_BUTTON_FLAG_on protocol_flags |= _BV(5)
#define BIND_BUTTON_FLAG_off protocol_flags &= ~_BV(5)
#define IS_BIND_BUTTON_FLAG_on ( ( protocol_flags & _BV(5) ) !=0 )
//PPM RX OK
#define PPM_FLAG_off protocol_flags &= ~_BV(6)
#define PPM_FLAG_on protocol_flags |= _BV(6)
#define IS_PPM_FLAG_on ( ( protocol_flags & _BV(6) ) !=0 )
//Bind flag
#define BIND_IN_PROGRESS protocol_flags &= ~_BV(7)
#define BIND_DONE protocol_flags |= _BV(7)
#define IS_BIND_DONE_on ( ( protocol_flags & _BV(7) ) !=0 )
//
#define BAD_PROTO_off protocol_flags2 &= ~_BV(0)
#define BAD_PROTO_on protocol_flags2 |= _BV(0)
#define IS_BAD_PROTO_on ( ( protocol_flags2 & _BV(0) ) !=0 )
//
#define RX_DONOTUPDTAE_off protocol_flags2 &= ~_BV(1)
#define RX_DONOTUPDTAE_on protocol_flags2 |= _BV(1)
#define IS_RX_DONOTUPDTAE_on ( ( protocol_flags2 & _BV(1) ) !=0 )
//
#define RX_MISSED_BUFF_off protocol_flags2 &= ~_BV(2)
#define RX_MISSED_BUFF_on protocol_flags2 |= _BV(2)
#define IS_RX_MISSED_BUFF_on ( ( protocol_flags2 & _BV(2) ) !=0 )
//TX Pause
#define TX_MAIN_PAUSE_off protocol_flags2 &= ~_BV(3)
#define TX_MAIN_PAUSE_on protocol_flags2 |= _BV(3)
#define IS_TX_MAIN_PAUSE_on ( ( protocol_flags2 & _BV(3) ) !=0 )
#define TX_RX_PAUSE_off protocol_flags2 &= ~_BV(4)
#define TX_RX_PAUSE_on protocol_flags2 |= _BV(4)
#define IS_TX_RX_PAUSE_on ( ( protocol_flags2 & _BV(4) ) !=0 )
#define IS_TX_PAUSE_on ( ( protocol_flags2 & (_BV(4)|_BV(3)) ) !=0 )
//********************
//*** Blink timing ***
//********************
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000
#define BLINK_BAD_PROTO_TIME_HIGH 50
//*******************
//*** AUX flags ***
//*******************
#define GET_FLAG(ch, mask) ( ch ? mask : 0)
#define Servo_AUX1 Servo_AUX & _BV(0)
#define Servo_AUX2 Servo_AUX & _BV(1)
#define Servo_AUX3 Servo_AUX & _BV(2)
#define Servo_AUX4 Servo_AUX & _BV(3)
#define Servo_AUX5 Servo_AUX & _BV(4)
#define Servo_AUX6 Servo_AUX & _BV(5)
#define Servo_AUX7 Servo_AUX & _BV(6)
#define Servo_AUX8 Servo_AUX & _BV(7)
//************************
//*** Power settings ***
//************************
enum {
TXPOWER_100uW,
TXPOWER_300uW,
TXPOWER_1mW,
TXPOWER_3mW,
TXPOWER_10mW,
TXPOWER_30mW,
TXPOWER_100mW,
TXPOWER_150mW
};
// A7105 power
// Power amp is ~+16dBm so:
enum A7105_POWER
{
A7105_POWER_0 = 0x00<<3 | 0x00, // TXPOWER_100uW = -23dBm == PAC=0 TBG=0
A7105_POWER_1 = 0x00<<3 | 0x01, // TXPOWER_300uW = -20dBm == PAC=0 TBG=1
A7105_POWER_2 = 0x00<<3 | 0x02, // TXPOWER_1mW = -16dBm == PAC=0 TBG=2
A7105_POWER_3 = 0x00<<3 | 0x04, // TXPOWER_3mW = -11dBm == PAC=0 TBG=4
A7105_POWER_4 = 0x01<<3 | 0x05, // TXPOWER_10mW = -6dBm == PAC=1 TBG=5
A7105_POWER_5 = 0x02<<3 | 0x07, // TXPOWER_30mW = 0dBm == PAC=2 TBG=7
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_7
#define A7105_LOW_POWER A7105_POWER_3
#define A7105_RANGE_POWER A7105_POWER_0
#define A7105_BIND_POWER A7105_POWER_0
// NRF Power
// Power setting is 0..3 for nRF24L01
// Claimed power amp for nRF24L01 from eBay is 20dBm.
enum NRF_POWER
{ // Raw w 20dBm PA
NRF_POWER_0 = 0x00, // 0 : -18dBm (16uW) 2dBm (1.6mW)
NRF_POWER_1 = 0x01, // 1 : -12dBm (60uW) 8dBm (6mW)
NRF_POWER_2 = 0x02, // 2 : -6dBm (250uW) 14dBm (25mW)
NRF_POWER_3 = 0x03 // 3 : 0dBm (1mW) 20dBm (100mW)
};
#define NRF_HIGH_POWER NRF_POWER_2
#define NRF_LOW_POWER NRF_POWER_1
#define NRF_RANGE_POWER NRF_POWER_0
#define NRF_BIND_POWER NRF_POWER_0
// CC2500 power output from the chip itself
// The numbers do not take into account any outside amplifier
enum CC2500_POWER
{
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_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
{
CYRF_POWER_0 = 0x00, // -35dbm
CYRF_POWER_1 = 0x01, // -30dbm
CYRF_POWER_2 = 0x02, // -24dbm
CYRF_POWER_3 = 0x03, // -18dbm
CYRF_POWER_4 = 0x04, // -13dbm
CYRF_POWER_5 = 0x05, // -5dbm
CYRF_POWER_6 = 0x06, // 0dbm
CYRF_POWER_7 = 0x07 // +4dbm
};
#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
enum TXRX_State {
TXRX_OFF,
TX_EN,
RX_EN
};
// Packet ack status values
enum {
PKT_PENDING = 0,
PKT_ACKED,
PKT_TIMEOUT
};
// baudrate defines for serial
#define SPEED_100K 0
#define SPEED_9600 1
#define SPEED_57600 2
#define SPEED_125K 3
//****************************************
//*** MULTI protocol serial definition ***
//****************************************
/*
**************************
16 channels serial protocol
**************************
Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Total of 26 bytes
Stream[0] = 0x55 sub_protocol values are 0..31
Stream[0] = 0x54 sub_protocol values are 32..63
header
Stream[1] = sub_protocol|BindBit|RangeCheckBit|AutoBindBit;
sub_protocol is 0..31 (bits 0..4), value should be added with 32 if Stream[0] = 0x54
=> Reserved 0
Flysky 1
Hubsan 2
FrskyD 3
Hisky 4
V2x2 5
DSM 6
Devo 7
YD717 8
KN 9
SymaX 10
SLT 11
CX10 12
CG023 13
Bayang 14
FrskyX 15
ESky 16
MT99XX 17
MJXQ 18
SHENQI 19
FY326 20
SFHSS 21
J6PRO 22
FQ777 23
ASSAN 24
FrskyV 25
HONTAI 26
OpenLRS 27
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
Stream[2] = RxNum | Power | Type;
RxNum value is 0..15 (bits 0..3)
Type is 0..7 <<4 (bit 4..6)
sub_protocol==Flysky
Flysky 0
V9x9 1
V6x6 2
V912 3
sub_protocol==Hisky
Hisky 0
HK310 1
sub_protocol==DSM
DSM2_22 0
DSM2_11 1
DSMX_22 2
DSMX_11 3
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
sub_protocol==CX10
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
DM007 2
Q282 3
JC3015_1 4
JC3015_2 5
MK33041 6
Q242 7
sub_protocol==CG023
CG023 0
YD829 1
H8_3D 2
sub_protocol==MT99XX
MT99 0
H7 1
YZ 2
LS 3
sub_protocol==MJXQ
WLH08 0
X600 1
X800 2
H26D 3
E010 4
sub_protocol==FRSKYX
CH_16 0
CH_8 1
sub_protocol==HONTAI
FORMAT_HONTAI 0
FORMAT_JJRCX1 1
FORMAT_X5C1 2
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
option_protocol value is -127..127
Stream[4] to [25] = Channels
16 Channels on 11 bits (0..2047)
0 -125%
204 -100%
1024 0%
1843 +100%
2047 +125%
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
*/

File diff suppressed because it is too large Load Diff

View File

@ -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,35 @@ 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 uint8_t __attribute__((unused)) NRF24L01_ReadPayloadLength()
{
NRF_CSN_off;
SPI_Write(R_RX_PL_WID);
uint8_t len = SPI_Read();
NRF_CSN_on;
return len;
}
static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
{
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 +115,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;
}
@ -189,25 +160,29 @@ void NRF24L01_SetPower()
if(IS_RANGE_FLAG_on)
power=NRF_POWER_0;
rf_setup = (rf_setup & 0xF9) | (power << 1);
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
if(prev_power != power)
{
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
prev_power=power;
}
}
void NRF24L01_SetTxRxMode(enum TXRX_State mode)
{
if(mode == TX_EN) {
NRF_CSN_off;
NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
| (1 << NRF24L01_07_TX_DS)
| (1 << NRF24L01_07_MAX_RT));
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);
NRF_CSN_on;
delayMicroseconds(130);
NRF_CE_on;
}
else
if (mode == RX_EN) {
NRF_CSN_off;
NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // reset the flag(s)
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // switch to RX mode
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
@ -217,13 +192,13 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
| (1 << NRF24L01_00_CRCO)
| (1 << NRF24L01_00_PWR_UP)
| (1 << NRF24L01_00_PRIM_RX));
_delay_us(130);
NRF_CSN_on;
delayMicroseconds(130);
NRF_CE_on;
}
else
{
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC)); //PowerDown
NRF_CSN_off;
NRF_CE_off;
}
}
@ -239,25 +214,31 @@ void NRF24L01_Reset()
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_Strobe(0xff); // NOP
NRF24L01_ReadReg(0x07);
NRF24L01_ReadReg(NRF24L01_07_STATUS);
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))) {
case BV(NRF24L01_07_TX_DS):
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):
case _BV(NRF24L01_07_MAX_RT):
return PKT_TIMEOUT;
}
return PKT_PENDING;
}
///////////////
// XN297 emulation layer
<<<<<<< HEAD
uint8_t xn297_scramble_enabled;
=======
uint8_t xn297_scramble_enabled=XN297_SCRAMBLED; //enabled by default
>>>>>>> refs/remotes/pascallanger/master
uint8_t xn297_addr_len;
uint8_t xn297_tx_addr[5];
uint8_t xn297_rx_addr[5];
@ -270,6 +251,7 @@ static const uint8_t xn297_scramble[] = {
0x1b, 0x5d, 0x19, 0x10, 0x24, 0xd3, 0xdc, 0x3f,
0x8e, 0xc5, 0x2f};
<<<<<<< HEAD
const uint16_t PROGMEM xn297_crc_xorout[] = {
0x0000, 0x3d5f, 0xa6f1, 0x3a23, 0xaa16, 0x1caf,
0x62b2, 0xe0eb, 0x0821, 0xbe07, 0x5f1a, 0xaf15,
@ -277,6 +259,8 @@ const uint16_t PROGMEM xn297_crc_xorout[] = {
0x1852, 0xdf36, 0x129d, 0xb17c, 0xd5f5, 0x70d7,
0xb798, 0x5133, 0x67db, 0xd94e};
=======
>>>>>>> refs/remotes/pascallanger/master
const uint16_t PROGMEM xn297_crc_xorout_scrambled[] = {
0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C,
0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B,
@ -284,6 +268,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 +286,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)
@ -346,10 +336,21 @@ void XN297_SetRXAddr(const uint8_t* addr, uint8_t len)
void XN297_Configure(uint16_t flags)
{
<<<<<<< HEAD
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);
=======
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;
>>>>>>> refs/remotes/pascallanger/master
}
void XN297_WritePayload(uint8_t* msg, uint8_t len)
@ -411,6 +412,7 @@ void XN297_ReadPayload(uint8_t* msg, uint8_t len)
// End of XN297 emulation
///////////////
<<<<<<< HEAD
// LT8910 emulation layer
uint8_t LT8910_buffer[64];
uint8_t LT8910_buffer_start;
@ -435,23 +437,62 @@ void LT8910_Config(uint8_t preamble_len, uint8_t trailer_len, uint8_t flags, uin
LT8910_Preamble_Len=preamble_len;
//Trailer 4 to 18 bits
LT8910_Tailer_Len=trailer_len;
=======
// 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;
>>>>>>> refs/remotes/pascallanger/master
//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
<<<<<<< HEAD
LT8910_Flags=flags;
//CRC init constant
LT8910_CRC_Initial_Data=crc_init;
}
void LT8910_SetChannel(uint8_t channel)
=======
LT8900_Flags=flags;
//CRC init constant
LT8900_CRC_Initial_Data=crc_init;
}
void LT8900_SetChannel(uint8_t channel)
>>>>>>> refs/remotes/pascallanger/master
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, channel +2); //NRF24L01 is 2400+channel but LT8900 is 2402+channel
}
<<<<<<< HEAD
void LT8910_SetTxRxMode(enum TXRX_State mode)
=======
void LT8900_SetTxRxMode(enum TXRX_State mode)
>>>>>>> refs/remotes/pascallanger/master
{
if(mode == TX_EN)
{
@ -477,12 +518,17 @@ void LT8910_SetTxRxMode(enum TXRX_State mode)
NRF24L01_SetTxRxMode(TXRX_OFF);
}
<<<<<<< HEAD
void LT8910_BuildOverhead()
=======
void LT8900_BuildOverhead()
>>>>>>> refs/remotes/pascallanger/master
{
uint8_t pos;
//Build overhead
//preamble
<<<<<<< HEAD
memset(LT8910_buffer,LT8910_addr[0]&0x01?0xAA:0x55,LT8910_Preamble_Len-1);
pos=LT8910_Preamble_Len-1;
//address
@ -500,10 +546,30 @@ void LT8910_BuildOverhead()
}
void LT8910_SetAddress(uint8_t *address,uint8_t addr_size)
=======
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)
>>>>>>> refs/remotes/pascallanger/master
{
uint8_t addr[5];
//Address size (SyncWord) 2 to 8 bytes, 16/32/48/64 bits
<<<<<<< HEAD
LT8910_addr_size=addr_size;
memcpy(LT8910_addr,address,LT8910_addr_size);
@ -524,14 +590,44 @@ uint8_t LT8910_ReadPayload(uint8_t* msg, uint8_t len)
unsigned int crc=LT8910_CRC_Initial_Data,a;
pos=LT8910_buffer_overhead_bits/8-LT8910_buffer_start;
end=pos+len+(LT8910_Flags&_BV(LT8910_PACKET_LENGTH_EN)?1:0)+(LT8910_Flags&_BV(LT8910_CRC_ON)?2:0);
=======
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);
>>>>>>> refs/remotes/pascallanger/master
//Read payload
NRF24L01_ReadPayload(buffer,end+1);
//Check address + trail
for(i=0;i<pos;i++)
<<<<<<< HEAD
if(LT8910_buffer[LT8910_buffer_start+i]!=buffer[i])
return 0; // wrong address...
//Shift buffer to remove trail bits
shift=LT8910_buffer_overhead_bits&0x7;
=======
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;
>>>>>>> refs/remotes/pascallanger/master
for(i=pos;i<end;i++)
{
a=(buffer[i]<<8)+buffer[i+1];
@ -539,7 +635,11 @@ uint8_t LT8910_ReadPayload(uint8_t* msg, uint8_t len)
buffer[i]=(a>>8)&0xFF;
}
//Check len
<<<<<<< HEAD
if(LT8910_Flags&_BV(LT8910_PACKET_LENGTH_EN))
=======
if(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN))
>>>>>>> refs/remotes/pascallanger/master
{
crc=crc16_update(crc,buffer[pos]);
if(bit_reverse(len)!=buffer[pos++])
@ -552,7 +652,11 @@ uint8_t LT8910_ReadPayload(uint8_t* msg, uint8_t len)
msg[i]=bit_reverse(buffer[pos++]);
}
//Check CRC
<<<<<<< HEAD
if(LT8910_Flags&_BV(LT8910_CRC_ON))
=======
if(LT8900_Flags&_BV(LT8900_CRC_ON))
>>>>>>> refs/remotes/pascallanger/master
{
if(buffer[pos++]!=((crc>>8)&0xFF)) return 0; // wrong CRC...
if(buffer[pos]!=(crc&0xFF)) return 0; // wrong CRC...
@ -561,12 +665,21 @@ uint8_t LT8910_ReadPayload(uint8_t* msg, uint8_t len)
return 1;
}
<<<<<<< HEAD
void LT8910_WritePayload(uint8_t* msg, uint8_t len)
{
unsigned int crc=LT8910_CRC_Initial_Data,a,mask;
uint8_t i, pos=0,tmp, buffer[64], pos_final,shift;
//Add packet len
if(LT8910_Flags&_BV(LT8910_PACKET_LENGTH_EN))
=======
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))
>>>>>>> refs/remotes/pascallanger/master
{
tmp=bit_reverse(len);
buffer[pos++]=tmp;
@ -580,12 +693,17 @@ void LT8910_WritePayload(uint8_t* msg, uint8_t len)
crc=crc16_update(crc,tmp);
}
//Add CRC
<<<<<<< HEAD
if(LT8910_Flags&_BV(LT8910_CRC_ON))
=======
if(LT8900_Flags&_BV(LT8900_CRC_ON))
>>>>>>> refs/remotes/pascallanger/master
{
buffer[pos++]=crc>>8;
buffer[pos++]=crc;
}
//Shift everything to fit behind the trailer (4 to 18 bits)
<<<<<<< HEAD
shift=LT8910_buffer_overhead_bits&0x7;
pos_final=LT8910_buffer_overhead_bits/8;
mask=~(0xFF<<(8-shift));
@ -595,10 +713,27 @@ void LT8910_WritePayload(uint8_t* msg, uint8_t len)
a=buffer[i]<<(8-shift);
LT8910_buffer[pos_final+i]=(LT8910_buffer[pos_final+i]&mask>>8)|a>>8;
LT8910_buffer[pos_final+i+1]=(LT8910_buffer[pos_final+i+1]&mask)|a;
=======
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;
>>>>>>> refs/remotes/pascallanger/master
}
if(shift)
pos++;
//Send everything
<<<<<<< HEAD
NRF24L01_WritePayload(LT8910_buffer+LT8910_buffer_start,pos_final+pos-LT8910_buffer_start);
}
// End of LT8910 emulation
=======
NRF24L01_WritePayload(LT8900_buffer+LT8900_buffer_start,pos_final+pos-LT8900_buffer_start);
}
// End of LT8900 emulation
>>>>>>> refs/remotes/pascallanger/master

209
Multiprotocol/Pins.h Normal file
View File

@ -0,0 +1,209 @@
/*
This project is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Multiprotocol is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
//*******************
//*** Pinouts ***
//*******************
// TX
#define SERIAL_TX_pin 1 //PD1
#define SERIAL_TX_port PORTD
#define SERIAL_TX_ddr DDRD
#define SERIAL_TX_output SERIAL_TX_ddr |= _BV(SERIAL_TX_pin)
#define SERIAL_TX_on SERIAL_TX_port |= _BV(SERIAL_TX_pin)
#define SERIAL_TX_off SERIAL_TX_port &= ~_BV(SERIAL_TX_pin)
#ifdef DEBUG_TX
#define DEBUG_TX_on SERIAL_TX_ON
#define DEBUG_TX_off SERIAL_TX_OFF
#define DEBUG_TX_toggle SERIAL_TX_port ^= _BV(SERIAL_TX_pin)
#else
#define DEBUG_TX_on
#define DEBUG_TX_off
#define DEBUG_TX_toggle
#endif
// Dial
#define MODE_DIAL1_pin 2
#define MODE_DIAL1_port PORTB
#define MODE_DIAL1_ipr PINB
#define MODE_DIAL2_pin 3
#define MODE_DIAL2_port PORTB
#define MODE_DIAL2_ipr PINB
#define MODE_DIAL3_pin 4
#define MODE_DIAL3_port PORTB
#define MODE_DIAL3_ipr PINB
#define MODE_DIAL4_pin 0
#define MODE_DIAL4_port PORTC
#define MODE_DIAL4_ipr PINC
// PPM
#define PPM_pin 3 //D3 = PD3
#define PPM_port PORTD
// SDIO
#define SDI_pin 5 //D5 = PD5
#define SDI_port PORTD
#define SDI_ipr PIND
#define SDI_ddr DDRD
#ifdef XMEGA
#define SDI_on SDI_port.OUTSET = _BV(SDI_pin)
#define SDI_off SDI_port.OUTCLR = _BV(SDI_pin)
#else
#define SDI_on SDI_port |= _BV(SDI_pin)
#define SDI_off SDI_port &= ~_BV(SDI_pin)
#define SDI_1 (SDI_ipr & _BV(SDI_pin))
#define SDI_0 (SDI_ipr & _BV(SDI_pin)) == 0x00
#endif
#define SDI_input SDI_ddr &= ~_BV(SDI_pin)
#define SDI_output SDI_ddr |= _BV(SDI_pin)
//SDO
#define SDO_pin 6 //D6 = PD6
#define SDO_port PORTD
#define SDO_ipr PIND
#ifdef XMEGA
#define SDO_1 (SDO_port.IN & _BV(SDO_pin))
#define SDO_0 (SDO_port.IN & _BV(SDO_pin)) == 0x00
#else
#define SDO_1 (SDO_ipr & _BV(SDO_pin))
#define SDO_0 (SDO_ipr & _BV(SDO_pin)) == 0x00
#endif
// SCLK
#define SCLK_port PORTD
#define SCLK_ddr DDRD
#ifdef XMEGA
#define SCLK_pin 7 //PD7
#define SCLK_on SCLK_port.OUTSET = _BV(SCLK_pin)
#define SCLK_off SCLK_port.OUTCLR = _BV(SCLK_pin)
#else
#define SCLK_pin 4 //D4 = PD4
#define SCLK_output SCLK_ddr |= _BV(SCLK_pin)
#define SCLK_on SCLK_port |= _BV(SCLK_pin)
#define SCLK_off SCLK_port &= ~_BV(SCLK_pin)
#endif
// A7105
#define A7105_CSN_pin 2 //D2 = PD2
#define A7105_CSN_port PORTD
#define A7105_CSN_ddr DDRD
#define A7105_CSN_output A7105_CSN_ddr |= _BV(A7105_CSN_pin)
#define A7105_CSN_on A7105_CSN_port |= _BV(A7105_CSN_pin)
#define A7105_CSN_off A7105_CSN_port &= ~_BV(A7105_CSN_pin)
// CC2500
#define CC25_CSN_pin 7 //D7 = PD7
#define CC25_CSN_port PORTD
#define CC25_CSN_ddr DDRD
#define CC25_CSN_output CC25_CSN_ddr |= _BV(CC25_CSN_pin)
#define CC25_CSN_on CC25_CSN_port |= _BV(CC25_CSN_pin)
#define CC25_CSN_off CC25_CSN_port &= ~_BV(CC25_CSN_pin)
// NRF24L01
#define NRF_CSN_pin 0 //D8 = PB0
#define NRF_CSN_port PORTB
#define NRF_CSN_ddr DDRB
#define NRF_CSN_output NRF_CSN_ddr |= _BV(NRF_CSN_pin)
#define NRF_CSN_on NRF_CSN_port |= _BV(NRF_CSN_pin)
#define NRF_CSN_off NRF_CSN_port &= ~_BV(NRF_CSN_pin)
#define NRF_CE_on
#define NRF_CE_off
// CYRF6936
#ifdef XMEGA
#define CYRF_CSN_pin 4 //PD4
#define CYRF_CSN_port PORTD
#define CYRF_CSN_ddr DDRD
#define CYRF_CSN_on CYRF_CSN_port.OUTSET = _BV(CYRF_CSN_pin)
#define CYRF_CSN_off CYRF_CSN_port.OUTCLR = _BV(CYRF_CSN_pin)
#define CYRF_RST_pin 0 //PE0
#define CYRF_RST_port PORTE
#define CYRF_RST_ddr DDRE
#define CYRF_RST_HI CYRF_RST_port.OUTSET = _BV(CYRF_RST_pin)
#define CYRF_RST_LO CYRF_RST_port.OUTCLR = _BV(CYRF_RST_pin)
#else
#define CYRF_CSN_pin 1 //D9 = PB1
#define CYRF_CSN_port PORTB
#define CYRF_CSN_ddr DDRB
#define CYRF_CSN_output CYRF_CSN_ddr |= _BV(CYRF_CSN_pin)
#define CYRF_CSN_on CYRF_CSN_port |= _BV(CYRF_CSN_pin)
#define CYRF_CSN_off CYRF_CSN_port &= ~_BV(CYRF_CSN_pin)
#define CYRF_RST_pin 5 //A5 = PC5
#define CYRF_RST_port PORTC
#define CYRF_RST_ddr DDRC
#define CYRF_RST_output CYRF_RST_ddr |= _BV(CYRF_RST_pin)
#define CYRF_RST_HI CYRF_RST_port |= _BV(CYRF_RST_pin)
#define CYRF_RST_LO CYRF_RST_port &= ~_BV(CYRF_RST_pin)
#endif
//RF Switch
#ifdef XMEGA
#define PE1_on
#define PE1_off
#define PE2_on
#define PE2_off
#else
#define PE1_pin 1 //A1 = PC1
#define PE1_port PORTC
#define PE1_ddr DDRC
#define PE1_output PE1_ddr |= _BV(PE1_pin)
#define PE1_on PE1_port |= _BV(PE1_pin)
#define PE1_off PE1_port &= ~_BV(PE1_pin)
#define PE2_pin 2 //A2 = PC2
#define PE2_port PORTC
#define PE2_ddr DDRC
#define PE2_output PE2_ddr |= _BV(PE2_pin)
#define PE2_on PE2_port |= _BV(PE2_pin)
#define PE2_off PE2_port &= ~_BV(PE2_pin)
#endif
// LED
#ifdef XMEGA
#define LED_pin 1 //PD1
#define LED_port PORTD
#define LED_ddr DDRD
#define LED_on LED_port.OUTCLR = _BV(LED_pin)
#define LED_off LED_port.OUTSET = _BV(LED_pin)
#define LED_toggle LED_port.OUTTGL = _BV(LED_pin)
#define LED_output LED_port.DIRSET = _BV(LED_pin)
#define IS_LED_on (LED_port.OUT & _BV(LED_pin))
#else
#define LED_pin 5 //D13 = PB5
#define LED_port PORTB
#define LED_ddr DDRB
#define LED_on LED_port |= _BV(LED_pin)
#define LED_off LED_port &= ~_BV(LED_pin)
#define LED_toggle LED_port ^= _BV(LED_pin)
#define LED_output LED_ddr |= _BV(LED_pin)
#define IS_LED_on (LED_port & _BV(LED_pin))
#endif
//BIND
#ifdef XMEGA
#define BIND_pin 2 //PD2
#define BIND_port PORTD
#define IS_BIND_BUTTON_on ( (BIND_port.IN & _BV(BIND_pin)) == 0x00 )
#else
#define BIND_pin 5 //D13 = PB5
#define BIND_port PORTB
#define BIND_ipr PINB
#define BIND_ddr DDRB
#define BIND_SET_INPUT BIND_ddr &= ~_BV(BIND_pin)
#define BIND_SET_OUTPUT BIND_ddr |= _BV(BIND_pin)
#define BIND_SET_PULLUP BIND_port |= _BV(BIND_pin)
#define IS_BIND_BUTTON_on ( (BIND_ipr & _BV(BIND_pin)) == 0x00 )
#endif

View File

@ -0,0 +1,247 @@
/*
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_COARSE 0
#define SFHSS_PACKET_LEN 13
#define SFHSS_TX_ID_LEN 2
uint8_t fhss_code; // 0-27
enum {
SFHSS_START = 0x00,
SFHSS_CAL = 0x01,
SFHSS_DATA1 = 0x02, // do not change this value
SFHSS_DATA2 = 0x0B, // do not change this value
SFHSS_TUNE = 0x0F
};
#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_rf_init()
{
CC2500_Strobe(CC2500_SIDLE);
for (uint8_t i = 0; i < 39; ++i)
CC2500_WriteReg(i, pgm_read_byte_near(&SFHSS_init_values[i]));
prev_option = option;
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
}
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_WriteReg(CC2500_25_FSCAL1, calData[rf_ch_num]);
}
static void __attribute__((unused)) SFHSS_tune_freq()
{
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_WriteReg(CC2500_0F_FREQ0, SFHSS_FREQ0_VAL + SFHSS_COARSE);
prev_option = option ;
phase = SFHSS_START; // Restart the tune process if option is changed to get good tuned values
}
}
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.
// Values grow down and to the right, so we just revert every channel.
static uint16_t __attribute__((unused)) SFHSS_convert_channel(uint8_t num)
{
return (uint16_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,906,86));
}
static void __attribute__((unused)) SFHSS_build_data_packet()
{
#define spacer1 0x02 //0b10
#define spacer2 (spacer1 << 4)
uint8_t ch_offset = phase == 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 or 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) | phase;
}
static void __attribute__((unused)) SFHSS_send_packet()
{
CC2500_WriteData(packet, SFHSS_PACKET_LEN);
}
uint16_t ReadSFHSS()
{
switch(phase)
{
case SFHSS_START:
rf_ch_num = 0;
SFHSS_tune_chan();
phase = SFHSS_CAL;
return 2000;
case SFHSS_CAL:
calData[rf_ch_num]=CC2500_ReadReg(CC2500_25_FSCAL1);
if (++rf_ch_num < 30)
SFHSS_tune_chan();
else
{
rf_ch_num = 0;
phase = SFHSS_DATA1;
}
return 2000;
/* Work cycle, 6.8ms, second packet 1.65ms after first */
case SFHSS_DATA1:
SFHSS_build_data_packet();
SFHSS_send_packet();
phase = SFHSS_DATA2;
return 1650;
case SFHSS_DATA2:
SFHSS_build_data_packet();
SFHSS_send_packet();
SFHSS_calc_next_chan();
phase = SFHSS_TUNE;
return 2000;
case SFHSS_TUNE:
phase = SFHSS_DATA1;
SFHSS_tune_freq();
SFHSS_tune_chan_fast();
CC2500_SetPower();
return 3150;
}
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; // Not a TX bind protocol
SFHSS_get_tx_id();
fhss_code=rx_tx_addr[2]%28; // Initialize it to random 0-27 inclusive
SFHSS_rf_init();
phase = SFHSS_START;
return 10000;
}
#endif

View File

@ -1,3 +1,21 @@
<<<<<<< HEAD
=======
/*
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/>.
*/
>>>>>>> refs/remotes/pascallanger/master
#if defined(SHENQI_NRF24L01_INO)
#include "iface_nrf24l01.h"
@ -24,10 +42,17 @@ void SHENQI_init()
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes rx/tx address
<<<<<<< HEAD
LT8910_Config(4, 8, _BV(LT8910_CRC_ON)|_BV(LT8910_PACKET_LENGTH_EN), 0xAA);
LT8910_SetChannel(2);
LT8910_SetAddress((uint8_t *)"\x9A\x9A\x9A\x9A",4);
LT8910_SetTxRxMode(RX_EN);
=======
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);
>>>>>>> refs/remotes/pascallanger/master
}
void SHENQI_send_packet()
@ -36,6 +61,7 @@ void SHENQI_send_packet()
if(packet_count==0)
{
uint8_t bind_addr[4];
<<<<<<< HEAD
bind_addr[0]=0x9A;
bind_addr[1]=0x9A;
bind_addr[2]=rx_tx_addr[2];
@ -44,24 +70,48 @@ void SHENQI_send_packet()
LT8910_SetChannel(2);
packet[1]=rx_tx_addr[1];
packet[2]=rx_tx_addr[0];
=======
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];
>>>>>>> refs/remotes/pascallanger/master
packet_period=2508;
}
else
{
<<<<<<< HEAD
LT8910_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[1]&0x0F);
LT8910_SetChannel(freq);
=======
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);
>>>>>>> refs/remotes/pascallanger/master
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...)
<<<<<<< HEAD
LT8910_WritePayload(packet,3);
while(NRF24L01_packet_ack()!=PKT_ACKED);
LT8910_WritePayload(packet,3);
=======
LT8900_WritePayload(packet,3);
while(NRF24L01_packet_ack()!=PKT_ACKED);
LT8900_WritePayload(packet,3);
>>>>>>> refs/remotes/pascallanger/master
packet_count++;
if(packet_count==7)
@ -79,6 +129,7 @@ uint16_t SHENQI_callback()
SHENQI_send_packet();
else
{
<<<<<<< HEAD
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
{
if(LT8910_ReadPayload(packet, 3))
@ -87,6 +138,16 @@ uint16_t SHENQI_callback()
rx_tx_addr[3]=packet[1];
rx_tx_addr[2]=packet[2];
LT8910_SetTxRxMode(TX_EN);
=======
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);
>>>>>>> refs/remotes/pascallanger/master
packet_period=14000;
}
NRF24L01_FlushRx();
@ -101,7 +162,11 @@ uint16_t initSHENQI()
SHENQI_init();
hopping_frequency_no = 0;
packet_count=0;
<<<<<<< HEAD
packet_period=100;
=======
packet_period=500;
>>>>>>> refs/remotes/pascallanger/master
return 1000;
}

View File

@ -34,7 +34,7 @@ enum {
static void __attribute__((unused)) SLT_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); // 2-bytes CRC, radio off
NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO)); // 2-bytes CRC, radio off
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4-byte RX/TX address
@ -93,7 +93,7 @@ static void __attribute__((unused)) SLT_set_tx_id(void)
static void __attribute__((unused)) SLT_wait_radio()
{
if (packet_sent)
while (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS))) ;
while (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & _BV(NRF24L01_07_TX_DS))) ;
packet_sent = 0;
}
@ -101,7 +101,7 @@ static void __attribute__((unused)) SLT_send_data(uint8_t *data, uint8_t len)
{
SLT_wait_radio();
NRF24L01_FlushTx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_RX_DR) | BV(NRF24L01_07_MAX_RT));
NRF24L01_WriteReg(NRF24L01_07_STATUS, _BV(NRF24L01_07_TX_DS) | _BV(NRF24L01_07_RX_DR) | _BV(NRF24L01_07_MAX_RT));
NRF24L01_WritePayload(data, len);
//NRF24L01_PulseCE();
packet_sent = 1;
@ -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);
}

86
Multiprotocol/SPI.ino Normal file
View File

@ -0,0 +1,86 @@
/*
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/>.
*/
/********************/
/** SPI routines **/
/********************/
#ifdef XMEGA
#define XNOP() NOP()
#else
#define XNOP()
#endif
void SPI_Write(uint8_t command)
{
uint8_t n=8;
SCLK_off;//SCK start low
XNOP();
SDI_off;
XNOP();
do
{
if(command&0x80)
SDI_on;
else
SDI_off;
XNOP();
SCLK_on;
XNOP();
XNOP();
command = command << 1;
SCLK_off;
XNOP();
}
while(--n) ;
SDI_on;
}
uint8_t SPI_Read(void)
{
uint8_t result=0,i;
for(i=0;i<8;i++)
{
result=result<<1;
if(SDO_1)
result |= 0x01;
SCLK_on;
XNOP();
XNOP();
NOP();
SCLK_off;
XNOP();
XNOP();
}
return result;
}
#ifdef A7105_INSTALLED
uint8_t SPI_SDIO_Read(void)
{
uint8_t result=0;
SDI_input;
for(uint8_t i=0;i<8;i++)
{
result=result<<1;
if(SDI_1) ///if SDIO =1
result |= 0x01;
SCLK_on;
NOP();
SCLK_off;
}
SDI_output;
return result;
}
#endif

View File

@ -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
@ -174,7 +174,7 @@ static void __attribute__((unused)) symax_init()
NRF24L01_SetTxRxMode(TX_EN);
//
NRF24L01_ReadReg(NRF24L01_07_STATUS);
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3F); // Enable all data pipes (even though not used?)
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
@ -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
@ -292,7 +292,7 @@ static void __attribute__((unused)) symax_set_channels(uint8_t address)
static void __attribute__((unused)) symax_init2()
{
uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24,
static uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24,
0x27, 0x2c, 0x1c, 0x3e, 0x39, 0x2d, 0x22};
if (sub_protocol==SYMAX5C)
@ -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();

261
Multiprotocol/TX_Def.h Normal file
View File

@ -0,0 +1,261 @@
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX_100 2012 // 100%
#define PPM_MIN_100 988 // 100%
#define PPM_MAX_125 2140 // 125%
#define PPM_MIN_125 860 // 125%
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#define PPM_MAX_125 2100 // 125%
#define PPM_MIN_125 900 // 125%
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
// Multiplex MC2020
#if defined(TX_MPX)
#define PPM_MAX_100 1950 // 100%
#define PPM_MIN_100 1250 // 100%
#define PPM_MAX_125 2050 // 125%
#define PPM_MIN_125 1150 // 125%
#endif
//Serial MIN MAX values
#define SERIAL_MAX_100 2012 // 100%
#define SERIAL_MIN_100 988 // 100%
#define SERIAL_MAX_125 2140 // 125%
#define SERIAL_MIN_125 860 // 125%
//PPM values used to compare
#define PPM_MIN_COMMAND 1250
#define PPM_SWITCH 1550
#define PPM_MAX_COMMAND 1750
//Channel definitions
#ifdef AETR
enum {
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
};
#endif
#ifdef AERT
enum {
AILERON =0,
ELEVATOR,
RUDDER,
THROTTLE,
};
#endif
#ifdef ARET
enum {
AILERON =0,
RUDDER,
ELEVATOR,
THROTTLE,
};
#endif
#ifdef ARTE
enum {
AILERON =0,
RUDDER,
THROTTLE,
ELEVATOR,
};
#endif
#ifdef ATRE
enum {
AILERON =0,
THROTTLE,
RUDDER,
ELEVATOR,
};
#endif
#ifdef ATER
enum {
AILERON =0,
THROTTLE,
ELEVATOR,
RUDDER,
};
#endif
#ifdef EATR
enum {
ELEVATOR =0,
AILERON,
THROTTLE,
RUDDER,
};
#endif
#ifdef EART
enum {
ELEVATOR =0,
AILERON,
RUDDER,
THROTTLE,
};
#endif
#ifdef ERAT
enum {
ELEVATOR =0,
RUDDER,
AILERON,
THROTTLE,
};
#endif
#ifdef ERTA
enum {
ELEVATOR =0,
RUDDER,
THROTTLE,
AILERON,
};
#endif
#ifdef ETRA
enum {
ELEVATOR =0,
THROTTLE,
RUDDER,
AILERON,
};
#endif
#ifdef ETAR
enum {
ELEVATOR =0,
THROTTLE,
AILERON,
RUDDER,
};
#endif
#ifdef TEAR
enum {
THROTTLE =0,
ELEVATOR,
AILERON,
RUDDER,
};
#endif
#ifdef TERA
enum {
THROTTLE =0,
ELEVATOR,
RUDDER,
AILERON,
};
#endif
#ifdef TREA
enum {
THROTTLE =0,
RUDDER,
ELEVATOR,
AILERON,
};
#endif
#ifdef TRAE
enum {
THROTTLE =0,
RUDDER,
AILERON,
ELEVATOR,
};
#endif
#ifdef TARE
enum {
THROTTLE =0,
AILERON,
RUDDER,
ELEVATOR,
};
#endif
#ifdef TAER
enum {
THROTTLE =0,
AILERON,
ELEVATOR,
RUDDER,
};
#endif
#ifdef RETA
enum {
RUDDER =0,
ELEVATOR,
THROTTLE,
AILERON,
};
#endif
#ifdef REAT
enum {
RUDDER =0,
ELEVATOR,
AILERON,
THROTTLE,
};
#endif
#ifdef RAET
enum {
RUDDER =0,
AILERON,
ELEVATOR,
THROTTLE,
};
#endif
#ifdef RATE
enum {
RUDDER =0,
AILERON,
THROTTLE,
ELEVATOR,
};
#endif
#ifdef RTAE
enum {
RUDDER =0,
THROTTLE,
AILERON,
ELEVATOR,
};
#endif
#ifdef RTEA
enum {
RUDDER =0,
THROTTLE,
ELEVATOR,
AILERON,
};
#endif
#define AUX1 4
#define AUX2 5
#define AUX3 6
#define AUX4 7
#define AUX5 8
#define AUX6 9
#define AUX7 10
#define AUX8 11
#define AUX9 12
#define AUX10 13
#define AUX11 14
#define AUX12 15
#define AUX13 16

View File

@ -1,3 +1,4 @@
<<<<<<< HEAD
//*************************************
// FrSky Telemetry serial code *
// By Midelic on RCGroups *
@ -171,6 +172,240 @@
100K 8E2 normal-multiprotocol
-every 12ms-
1 2 3 4 5 6 7 8 9 CRC DESCR
=======
/*
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/>.
*/
//**************************
// Telemetry serial code *
//**************************
#if defined TELEMETRY
#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 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 pktx1[MAX_PKTX];
uint8_t index;
uint8_t frame[18];
#ifdef BASH_SERIAL
// For bit-bashed serial output
struct t_serial_bash
{
uint8_t head ;
uint8_t tail ;
uint8_t data[64] ;
uint8_t busy ;
uint8_t speed ;
} SerialControl ;
#endif
#if defined DSM_TELEMETRY
void DSM_frame()
{
Serial_write(0xAA); // Telemetry packet
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++)
{
if ((frame[i] == START_STOP) || (frame[i] == BYTESTUFF))
{
Serial_write(BYTESTUFF);
frame[i] ^= STUFF_MASK;
}
Serial_write(frame[i]);
}
Serial_write(START_STOP);
}
void compute_RSSIdbm()
{
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))
{
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 SPORT_TELEMETRY && defined FRSKYX_CC2500_INO
if (protocol==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
}
}
#endif
}
}
void frsky_link_frame()
{
frame[0] = 0xFE;
if (protocol==MODE_FRSKYD)
{
compute_RSSIdbm();
frame[1] = pktt[3];
frame[2] = pktt[4];
frame[3] = pktt[5];
frame[4] = (uint8_t)RSSI_dBm;
}
else
if (protocol==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, j=8, i;
//uint8_t c=0, n=0;
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();
}
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-or multiple of 12; %36
1 2 3 4 5 6 7 8 9 CRC DESCR
>>>>>>> refs/remotes/pascallanger/master
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 +417,24 @@
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
<<<<<<< HEAD
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
>>>>>>> refs/remotes/pascallanger/master
[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)
<<<<<<< HEAD
[05] ????? 03 10 21 32 //TX/RX telemetry hand-shake bytes
=======
[05] HD-SK 03 10 21 32 //TX/RX telemetry hand-shake bytes
>>>>>>> refs/remotes/pascallanger/master
[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,6 +442,7 @@
[10] STRM4 03 03 03 03
[11] STRM5 F1 F1 F1 F1
[12] STRM6 D1 D1 D0 D0
<<<<<<< HEAD
[13] CHKSUM1
[14] CHKSUM2
*/
@ -334,4 +580,573 @@
#endif
}
#endif
#endif
=======
[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
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
Serial_write(p[0]) ;
for (uint8_t i = 1; i < 9; i++)
{
if (i == 8)
p[i] = 0xff - crc_s;
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;
}
}
}
void sportIdle()
{
Serial_write(START_STOP);
}
void sportSendFrame()
{
uint8_t i;
sport_counter = (sport_counter + 1) %36;
if(sport_counter<6)
{
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] = 0x02 ;//dummy values if swr 20230f00
frame[5] = 0x23;
frame[6] = 0x0F;
break;
case 2: // RSSI
frame[2] = 0x01;
frame[3] = 0xf1;
frame[4] = rssi;
break;
case 4: //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]=pktx1[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 == START_STOP) // Happens if missed packet
{//waiting for 0x7e
index = 0;
pass = 1;
break;
}
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
if ( sport )
{
// overrun!
}
else
{
uint8_t i ;
for ( i = 0 ; i < FRSKY_SPORT_PACKET_SIZE ; i += 1 )
{
pktx1[i] = pktx[i] ; // Double buffer
}
sport = 1;//ok to send
}
pass = 0;//reset
}
}
#endif
void TelemetryUpdate()
{
#if defined SPORT_TELEMETRY
if (protocol==MODE_FRSKYX)
{ // FrSkyX
if(telemetry_link)
{
if(pktt[4] & 0x80)
rssi=pktt[4] & 0x7F ;
else
RxBt = (pktt[4]<<1) + 1 ;
for (uint8_t i=0; i < pktt[6]; i++)
proces_sport_data(pktt[7+i]);
telemetry_link=0;
}
}
#endif
// check for space in tx buffer
#ifdef BASH_SERIAL
uint8_t h ;
uint8_t t ;
h = SerialControl.head ;
t = SerialControl.tail ;
if ( h >= t )
{
t += 64 - h ;
}
else
{
t -= h ;
}
if ( t < 32 )
{
return ;
}
#else
uint8_t h ;
uint8_t t ;
h = tx_head ;
t = tx_tail ;
if ( h >= t )
{
t += TXBUFFER_SIZE - h ;
}
else
{
t -= h ;
}
if ( t < 16 )
{
return ;
}
#endif
#if defined DSM_TELEMETRY
if(telemetry_link && protocol == MODE_DSM )
{ // DSM
DSM_frame();
telemetry_link=0;
return;
}
#endif
if(telemetry_link && protocol != MODE_FRSKYX )
{ // FrSky + Hubsan
frsky_link_frame();
telemetry_link=0;
return;
}
#if defined HUB_TELEMETRY
if(!telemetry_link && protocol == MODE_FRSKYD)
{ // FrSky
frsky_user_frame();
return;
}
#endif
#if defined SPORT_TELEMETRY
if (protocol==MODE_FRSKYX)
{ // FrSkyX
uint32_t now = micros();
if ((now - last) > SPORT_TIME)
{
sportSendFrame();
last += SPORT_TIME ;
}
}
#endif
}
/**************************/
/**************************/
/** Serial TX routines **/
/**************************/
/**************************/
#ifndef BASH_SERIAL
// Routines for normal serial output
void Serial_write(uint8_t data)
{
uint8_t nextHead ;
nextHead = tx_head + 1 ;
if ( nextHead >= TXBUFFER_SIZE )
nextHead = 0 ;
tx_buff[nextHead]=data;
tx_head = nextHead ;
tx_resume();
}
void initTXSerial( uint8_t speed)
{
#ifdef ENABLE_PPM
if(speed==SPEED_9600)
{ // 9600
#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);
#endif
}
else if(speed==SPEED_57600)
{ // 57600
#ifdef XMEGA
/*USARTC0.BAUDCTRLA = 207 ;
USARTC0.BAUDCTRLB = 0 ;
USARTC0.CTRLB = 0x18 ;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
USARTC0.CTRLC = 0x03 ;*/
#else
//57600 bauds
UBRR0H = 0x00;
UBRR0L = 0x22;
UCSR0A = 0x02 ; // Set X2 bit
//Set frame format to 8 data bits, none, 1 stop bit
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
#endif
}
else if(speed==SPEED_125K)
{ // 125000
#ifdef XMEGA
/*USARTC0.BAUDCTRLA = 207 ;
USARTC0.BAUDCTRLB = 0 ;
USARTC0.CTRLB = 0x18 ;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
USARTC0.CTRLC = 0x03 ;*/
#else
//125000 bauds
UBRR0H = 0x00;
UBRR0L = 0x07;
UCSR0A = 0x00 ; // Clear X2 bit
//Set frame format to 8 data bits, none, 1 stop bit
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
#endif
}
#endif
#ifndef XMEGA
UCSR0B |= (1<<TXEN0);//tx enable
#endif
}
#ifdef XMEGA
ISR(USARTC0_DRE_vect)
#else
ISR(USART_UDRE_vect)
#endif
{ // Transmit interrupt
if(tx_head!=tx_tail)
{
if(++tx_tail>=TXBUFFER_SIZE)//head
tx_tail=0;
UDR0=tx_buff[tx_tail];
}
if (tx_tail == tx_head)
tx_pause(); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
}
#else //BASH_SERIAL
// Routines for bit-bashed serial output
// Speed is 0 for 100K and 1 for 9600
void initTXSerial( uint8_t speed)
{
TIMSK0 = 0 ; // Stop all timer 0 interrupts
#ifdef INVERT_SERIAL
SERIAL_TX_off;
#else
SERIAL_TX_on;
#endif
UCSR0B &= ~(1<<TXEN0) ;
SerialControl.speed = speed ;
if ( speed == SPEED_9600 )
{
OCR0A = 207 ; // 104uS period
TCCR0A = 3 ;
TCCR0B = 0x0A ; // Fast PMM, 2MHz
}
else // 100K
{
TCCR0A = 0 ;
TCCR0B = 2 ; // Clock/8 (0.5uS)
}
}
void Serial_write( uint8_t byte )
{
uint8_t temp ;
uint8_t temp1 ;
uint8_t byteLo ;
#ifdef INVERT_SERIAL
byte = ~byte ;
#endif
byteLo = byte ;
byteLo >>= 7 ; // Top bit
if ( SerialControl.speed == SPEED_100K )
{
#ifdef INVERT_SERIAL
byteLo |= 0x02 ; // Parity bit
#else
byteLo |= 0xFC ; // Stop bits
#endif
// calc parity
temp = byte ;
temp >>= 4 ;
temp = byte ^ temp ;
temp1 = temp ;
temp1 >>= 2 ;
temp = temp ^ temp1 ;
temp1 = temp ;
temp1 <<= 1 ;
temp ^= temp1 ;
temp &= 0x02 ;
#ifdef INVERT_SERIAL
byteLo ^= temp ;
#else
byteLo |= temp ;
#endif
}
else
{
byteLo |= 0xFE ; // Stop bit
}
byte <<= 1 ;
#ifdef INVERT_SERIAL
byte |= 1 ; // Start bit
#endif
uint8_t next = (SerialControl.head + 2) & 0x3f ;
if ( next != SerialControl.tail )
{
SerialControl.data[SerialControl.head] = byte ;
SerialControl.data[SerialControl.head+1] = byteLo ;
SerialControl.head = next ;
}
if(!IS_TX_PAUSE_on)
tx_resume();
}
void resumeBashSerial()
{
cli() ;
if ( SerialControl.busy == 0 )
{
sei() ;
// Start the transmission here
#ifdef INVERT_SERIAL
GPIOR2 = 0 ;
#else
GPIOR2 = 0x01 ;
#endif
if ( SerialControl.speed == SPEED_100K )
{
GPIOR1 = 1 ;
OCR0B = TCNT0 + 40 ;
OCR0A = OCR0B + 210 ;
TIFR0 = (1<<OCF0A) | (1<<OCF0B) ;
TIMSK0 |= (1<<OCIE0B) ;
SerialControl.busy = 1 ;
}
else
{
GPIOR1 = 1 ;
TIFR0 = (1<<TOV0) ;
TIMSK0 |= (1<<TOIE0) ;
SerialControl.busy = 1 ;
}
}
else
{
sei() ;
}
}
// Assume timer0 at 0.5uS clock
ISR(TIMER0_COMPA_vect)
{
uint8_t byte ;
byte = GPIOR0 ;
if ( byte & 0x01 )
SERIAL_TX_on;
else
SERIAL_TX_off;
byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR0 = byte ;
if ( --GPIOR1 == 0 )
{
TIMSK0 &= ~(1<<OCIE0A) ;
GPIOR1 = 3 ;
}
else
{
OCR0A += 20 ;
}
}
ISR(TIMER0_COMPB_vect)
{
uint8_t byte ;
byte = GPIOR2 ;
if ( byte & 0x01 )
SERIAL_TX_on;
else
SERIAL_TX_off;
byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR2 = byte ;
if ( --GPIOR1 == 0 )
{
if ( IS_TX_PAUSE_on )
{
SerialControl.busy = 0 ;
TIMSK0 &= ~(1<<OCIE0B) ;
}
else
{
// prepare next byte and allow for 2 stop bits
struct t_serial_bash *ptr = &SerialControl ;
if ( ptr->head != ptr->tail )
{
GPIOR0 = ptr->data[ptr->tail] ;
GPIOR2 = ptr->data[ptr->tail+1] ;
ptr->tail = ( ptr->tail + 2 ) & 0x3F ;
GPIOR1 = 8 ;
OCR0A = OCR0B + 40 ;
OCR0B = OCR0A + 8 * 20 ;
TIMSK0 |= (1<<OCIE0A) ;
}
else
{
SerialControl.busy = 0 ;
TIMSK0 &= ~(1<<OCIE0B) ;
}
}
}
else
{
OCR0B += 20 ;
}
}
ISR(TIMER0_OVF_vect)
{
uint8_t byte ;
if ( GPIOR1 > 2 )
{
byte = GPIOR0 ;
}
else
{
byte = GPIOR2 ;
}
if ( byte & 0x01 )
SERIAL_TX_on;
else
SERIAL_TX_off;
byte /= 2 ; // Generates shorter code than byte >>= 1
if ( GPIOR1 > 2 )
{
GPIOR0 = byte ;
}
else
{
GPIOR2 = byte ;
}
if ( --GPIOR1 == 0 )
{
// prepare next byte
struct t_serial_bash *ptr = &SerialControl ;
if ( ptr->head != ptr->tail )
{
GPIOR0 = ptr->data[ptr->tail] ;
GPIOR2 = ptr->data[ptr->tail+1] ;
ptr->tail = ( ptr->tail + 2 ) & 0x3F ;
GPIOR1 = 10 ;
}
else
{
SerialControl.busy = 0 ;
TIMSK0 &= ~(1<<TOIE0) ;
}
}
}
#endif // BASH_SERIAL
#endif // TELEMETRY
>>>>>>> refs/remotes/pascallanger/master

View File

@ -80,7 +80,7 @@ static void __attribute__((unused)) v202_init()
NRF24L01_Initialize();
// 2-bytes CRC, radio off
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3F); // Enable all data pipes
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
@ -116,7 +116,7 @@ static void __attribute__((unused)) V202_init2()
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
//Done by TX_EN??? => NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
//Done by TX_EN??? => NRF24L01_WriteReg(NRF24L01_00_CONFIG, _BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
}
static void __attribute__((unused)) V2X2_set_tx_id(void)

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

View File

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

View File

@ -13,6 +13,7 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
<<<<<<< HEAD
/** Multiprotocol module configuration file ***/
//Uncomment your TX type
@ -90,6 +91,150 @@ const PPM_Parameters PPM_prot[15]= {
/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 9 */ {MODE_KN , FEILUN , 0 , P_HIGH , AUTOBIND , 0 },
=======
/**********************************************/
/** Multiprotocol module configuration file ***/
/**********************************************/
/*******************/
/*** TX SETTINGS ***/
/*******************/
//Modify the channel order based on your TX: AETR, TAER, RETA...
//Examples: Flysky & DEVO is AETR, JR/Spektrum radio is TAER, Multiplex is AERT...
//Default is AETR.
#define AETR
/**************************/
/*** RF CHIPS INSTALLED ***/
/**************************/
//There are 4 RF components supported. If one of them is not installed you must comment it using "//".
//If a chip is not installed all associated protocols are disabled.
//4-in-1 modules have all RF chips installed
//!!!If a RF chip is present it MUST be marked as installed!!! or weird things will happen you have been warned.
#define A7105_INSTALLED
#define CYRF6936_INSTALLED
#define CC2500_INSTALLED
#define NRF24L01_INSTALLED
/****************************/
/*** PROTOCOLS TO INCLUDE ***/
/****************************/
//In this section select the protocols you want to be accessible when using the module.
//All the protocols will not fit in the module so you need to pick and choose.
//Comment the protocols you are not using with "//" to save Flash space.
//The protocols below need an A7105 to be installed
#define FLYSKY_A7105_INO
#define HUBSAN_A7105_INO
//The protocols below need a CYRF6936 to be installed
#define DEVO_CYRF6936_INO
#define DSM_CYRF6936_INO
#define J6PRO_CYRF6936_INO
//The protocols below need a CC2500 to be installed
#define FRSKYD_CC2500_INO
#define FRSKYV_CC2500_INO
#define FRSKYX_CC2500_INO
#define SFHSS_CC2500_INO
//The protocols below need a NRF24L01 to be installed
#define BAYANG_NRF24L01_INO
#define CG023_NRF24L01_INO
#define CX10_NRF24L01_INO
#define ESKY_NRF24L01_INO
#define HISKY_NRF24L01_INO
#define KN_NRF24L01_INO
#define SLT_NRF24L01_INO
#define SYMAX_NRF24L01_INO
#define V2X2_NRF24L01_INO
#define YD717_NRF24L01_INO
#define MT99XX_NRF24L01_INO
#define MJXQ_NRF24L01_INO
#define SHENQI_NRF24L01_INO
#define FY326_NRF24L01_INO
#define FQ777_NRF24L01_INO
#define ASSAN_NRF24L01_INO
#define HONTAI_NRF24L01_INO
/**************************/
/*** TELEMETRY SETTINGS ***/
/**************************/
//In this section you can configure the telemetry.
//If you do not plan using the telemetry comment this global setting using "//" and skip to the next section.
#define TELEMETRY
//Uncomment to invert the polarity of the telemetry serial signal.
//For ER9X and ERSKY9X it must be commented. For OpenTX it must be uncommented.
//#define INVERT_TELEMETRY
//Comment a line to disable a protocol telemetry
#define DSM_TELEMETRY
#define SPORT_TELEMETRY
#define HUB_TELEMETRY
/****************************/
/*** SERIAL MODE SETTINGS ***/
/****************************/
//In this section you can configure the serial mode.
//The serial mode enables full editing of all the parameters in the GUI of the radio.
//This is available natively for ER9X and ERSKY9X. It is available for OpenTX on Taranis with a special version.
//If you do not plan to use the Serial mode comment this line using "//" to save Flash space
#define ENABLE_SERIAL
/*************************/
/*** PPM MODE SETTINGS ***/
/*************************/
//In this section you can configure all details about PPM.
//If you do not plan to use the PPM mode comment this line using "//" to save Flash space, you don't need to configure anything below in this case
#define ENABLE_PPM
/*** TX END POINTS ***/
//It is important for the module to know the endpoints of your radio.
//Below are some standard transmitters already preconfigured.
//Uncomment only the one which matches your transmitter.
#define TX_ER9X //ER9X/ERSKY9X/OpenTX ( 988<->2012µs)
//#define TX_DEVO7 //DEVO (1120<->1920µs)
//#define TX_SPEKTRUM //Spektrum (1100<->1900µs)
//#define TX_HISKY //HISKY (1100<->1900µs)
//#define TX_MPX //Multiplex MC2020 (1250<->1950µs)
//#define TX_CUSTOM //Custom
// The lines below are used to set the end points in microseconds (µs) if you have selected TX_CUSTOM.
// A few things to considered:
// - If you put too big values compared to your TX you won't be able to reach the extremes which is bad for throttle as an example
// - If you put too low values you won't be able to use your full stick range, it will be maxed out before reaching the end
// - Centered stick value is usually 1500. It should match the middle between MIN and MAX, ie Center=(MAX-MIN)/2+MIN. If your TX is not centered you can adjust the value MIN or MAX.
// - 100% is the value when the model is by default, 125% is the value when you extend the servo travel which is only used by some protocols
#if defined(TX_CUSTOM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
//The table below indicates which protocol to run when a specific position on the dial has been selected.
//All fields and values are explained below. Everything is configurable from here like in the Serial mode.
//Example: You can associate multiple times the same protocol to different dial positions to take advantage of the model match (RX_Num)
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_FRSKYD, 0 , 0 , P_HIGH , NO_AUTOBIND , 40 }, // option=fine freq tuning
/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 6 */ {MODE_DSM , DSM2_22 , 0 , P_HIGH , NO_AUTOBIND , 6 }, // option=number of channels
/* 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 },
>>>>>>> refs/remotes/pascallanger/master
/* 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 },
@ -97,7 +242,11 @@ const PPM_Parameters PPM_prot[15]= {
/* 14 */ {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 15 */ {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 }
};
<<<<<<< HEAD
/* Available protocols and associated sub protocols:
=======
/* Available protocols and associated sub protocols to pick and choose from
>>>>>>> refs/remotes/pascallanger/master
MODE_FLYSKY
Flysky
V9X9
@ -105,16 +254,28 @@ const PPM_Parameters PPM_prot[15]= {
V912
MODE_HUBSAN
NONE
<<<<<<< HEAD
MODE_FRSKY
=======
MODE_FRSKYD
>>>>>>> refs/remotes/pascallanger/master
NONE
MODE_HISKY
Hisky
HK310
MODE_V2X2
NONE
<<<<<<< HEAD
MODE_DSM2
DSM2
DSMX
=======
MODE_DSM
DSM2_22
DSM2_11
DSMX_22
DSMX_11
>>>>>>> refs/remotes/pascallanger/master
MODE_DEVO
NONE
MODE_YD717
@ -147,18 +308,28 @@ const PPM_Parameters PPM_prot[15]= {
MODE_BAYANG
NONE
MODE_FRSKYX
<<<<<<< HEAD
NONE
=======
CH_16
CH_8
>>>>>>> refs/remotes/pascallanger/master
MODE_ESKY
NONE
MODE_MT99XX
MT99
H7
YZ
<<<<<<< HEAD
=======
LS
>>>>>>> refs/remotes/pascallanger/master
MODE_MJXQ
WLH08
X600
X800
H26D
<<<<<<< HEAD
MODE_SHENQI
NONE
MODE_FY326
@ -267,3 +438,38 @@ enum chan_orders{
//Uncoment the desired serial speed
#define BAUD 100000
//#define BAUD 125000
=======
E010
MODE_SHENQI
NONE
MODE_FY326
NONE
MODE_SFHSS
NONE
MODE_J6PRO
NONE
MODE_FQ777
NONE
MODE_ASSAN
NONE
MODE_FRSKYV
NONE
MODE_HONTAI
FORMAT_HONTAI
FORMAT_JJRCX1
FORMAT_X5C1
*/
// RX_Num is used for model match. Using RX_Num values different for each receiver will prevent starting a model with the false config loaded...
// RX_Num value is between 0 and 15.
// Power P_HIGH or P_LOW: High or low power setting for the transmission.
// For indoor P_LOW is more than enough.
// Auto Bind AUTOBIND or NO_AUTOBIND
// For protocols which does not require binding at each power up (like Flysky, FrSky...), you might still want a bind to be initiated each time you power up the TX.
// As an exxample, it's usefull for the WLTOYS F929/F939/F949/F959 (all using the Flysky protocol) which requires a bind at each power up.
// Option: the value is between -127 and +127.
// The option value is only valid for some protocols, read this page for more information: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md
>>>>>>> refs/remotes/pascallanger/master

View File

@ -103,6 +103,13 @@ enum {
//#define NOP 0xFF
// XN297 emulation layer
<<<<<<< HEAD
#define XN297_UNSCRAMBLED 8
=======
enum {
XN297_UNSCRAMBLED = 0,
XN297_SCRAMBLED
};
>>>>>>> refs/remotes/pascallanger/master
#endif

View File

@ -14,8 +14,13 @@
*/
// Check selected board type
#if F_CPU != 16000000L || not defined(__AVR_ATmega328P__)
#error You must select the processor type "ATmega328(5V, 16MHz)"
#ifndef XMEGA
#if not defined(ARDUINO_AVR_PRO) && not defined(ARDUINO_AVR_MINI) && not defined(ARDUINO_AVR_NANO)
#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
//******************
@ -23,133 +28,116 @@
//******************
enum PROTOCOLS
{
MODE_HM830=40, // =>NRF24L01
MODE_CFLIE=41, // =>NRF24L01
MODE_JOYSWAY = 42, // =>A7105
MODE_J6PRO = 43, // =>CYRF6936
MODE_H377=44, // =>NRF24L01
MODE_WK2x01 = 45, // =>CYRF6936
MODE_ESKY150=46, // =>NRF24L01
MODE_BlueFly=47, // =>NRF24L01
MODE_HonTai=48, // =>NRF24L01
MODE_UDI=49, // =>NRF24L01
MODE_NE260=50, // =>NRF24L01
MODE_FBL100=51, // =>NRF24L01
MODE_SKYARTEC=52, // =>CC2500
MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105
MODE_HUBSAN = 2, // =>A7105
MODE_FRSKY = 3, // =>CC2500
MODE_HISKY = 4, // =>NRF24L01
MODE_V2X2 = 5, // =>NRF24L01
MODE_DSM2 = 6, // =>CYRF6936
MODE_DEVO =7, // =>CYRF6936
MODE_YD717 = 8, // =>NRF24L01
MODE_KN = 9, // =>NRF24L01
MODE_SYMAX = 10, // =>NRF24L01
MODE_SLT = 11, // =>NRF24L01
MODE_CX10 = 12, // =>NRF24L01
MODE_CG023 = 13, // =>NRF24L01
MODE_BAYANG = 14, // =>NRF24L01
MODE_FRSKYX = 15, // =>CC2500
MODE_ESKY = 16, // =>NRF24L01
MODE_MT99XX=17, // =>NRF24L01
MODE_MJXQ=18, // =>NRF24L01
MODE_SHENQI=19, // =>NRF24L01
MODE_FY326=20 // =>NRF24L01
MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105
MODE_HUBSAN = 2, // =>A7105
MODE_FRSKYD = 3, // =>CC2500
MODE_HISKY = 4, // =>NRF24L01
MODE_V2X2 = 5, // =>NRF24L01
MODE_DSM = 6, // =>CYRF6936
MODE_DEVO = 7, // =>CYRF6936
MODE_YD717 = 8, // =>NRF24L01
MODE_KN = 9, // =>NRF24L01
MODE_SYMAX = 10, // =>NRF24L01
MODE_SLT = 11, // =>NRF24L01
MODE_CX10 = 12, // =>NRF24L01
MODE_CG023 = 13, // =>NRF24L01
MODE_BAYANG = 14, // =>NRF24L01
MODE_FRSKYX = 15, // =>CC2500
MODE_ESKY = 16, // =>NRF24L01
MODE_MT99XX = 17, // =>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
MODE_ASSAN = 24, // =>NRF24L01
MODE_FRSKYV = 25, // =>CC2500
MODE_HONTAI = 26, // =>NRF24L01
MODE_OPENLRS = 27, // =>OpenLRS hardware
};
enum Flysky
{
Flysky=0,
V9X9=1,
V6X6=2,
V912=3
Flysky = 0,
V9X9 = 1,
V6X6 = 2,
V912 = 3
};
enum Hisky
{
Hisky=0,
HK310=1
Hisky = 0,
HK310 = 1
};
enum DSM2{
DSM2=0,
DSMX=1
enum DSM
{
DSM2_22 = 0,
DSM2_11 = 1,
DSMX_22 = 2,
DSMX_11 = 3,
DSM_AUTO = 4
};
enum YD717
{
YD717=0,
SKYWLKR=1,
SYMAX4=2,
XINXUN=3,
NIHUI=4
YD717 = 0,
SKYWLKR = 1,
SYMAX4 = 2,
XINXUN = 3,
NIHUI = 4
};
enum KN
{
WLTOYS=0,
FEILUN=1
WLTOYS = 0,
FEILUN = 1
};
enum SYMAX
{
SYMAX=0,
SYMAX5C=1
SYMAX = 0,
SYMAX5C = 1
};
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE=1, // also compatible with CX10-A, CX12
DM007=2,
Q282=3,
JC3015_1=4,
JC3015_2=5,
MK33041=6,
Q242=7
CX10_GREEN = 0,
CX10_BLUE = 1, // also compatible with CX10-A, CX12
DM007 = 2,
Q282 = 3,
JC3015_1 = 4,
JC3015_2 = 5,
MK33041 = 6,
Q242 = 7
};
enum CG023
{
CG023 = 0,
YD829 = 1,
H8_3D = 2
CG023 = 0,
YD829 = 1,
H8_3D = 2
};
enum MT99XX
{
MT99 = 0,
H7 = 1,
YZ = 2
YZ = 2,
LS = 3
};
enum MJXQ
{
WLH08 = 0,
X600 = 1,
X800 = 2,
H26D = 3
H26D = 3,
E010 = 4
};
enum WK2X01
enum FRSKYX
{
WK2801 = 0,
WK2601 = 1,
WK2401 = 2
};
enum FY326
{
FY326 = 0,
FY319 = 1
CH_16 = 0,
CH_8 = 1,
};
enum HONTAI
{
HONTAI = 0,
JJRCX1 = 1
};
enum UDI
{
U816_V1 = 0,
U816_V2,
U839_2014
};
enum FBL100
{
FBL100 = 0,
HP100
FORMAT_HONTAI = 0,
FORMAT_JJRCX1 = 1,
FORMAT_X5C1 = 2
};
#define NONE 0
@ -160,7 +148,7 @@ enum FBL100
struct PPM_Parameters
{
uint8_t protocol : 5;
uint8_t protocol : 6;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
uint8_t power : 1;
@ -168,83 +156,39 @@ struct PPM_Parameters
uint8_t option;
};
//*******************
//*** Pinouts ***
//*******************
//#define BIND_pin 13
#define LED_pin 13 //Promini original led on B5
//
#define PPM_pin 3 //PPM -D3
#define SDI_pin 5 //SDIO-D5
#define SCLK_pin 4 //SCK-D4
#define CS_pin 2 //CS-D2
#define SDO_pin 6 //D6
//
#define CTRL1 1 //C1 (A1)
#define CTRL2 2 //C2 (A2)
//
#define CTRL1_on PORTC |= _BV(1)
#define CTRL1_off PORTC &= ~_BV(1)
//
#define CTRL2_on PORTC |= _BV(2)
#define CTRL2_off PORTC &= ~_BV(2)
//
#define CS_on PORTD |= _BV(2) //D2
#define CS_off PORTD &= ~_BV(2) //D2
//
#define SCK_on PORTD |= _BV(4) //D4
#define SCK_off PORTD &= ~_BV(4) //D4
//
#define SDI_on PORTD |= _BV(5) //D5
#define SDI_off PORTD &= ~_BV(5) //D5
#define SDI_1 (PIND & (1<<SDI_pin)) == (1<<SDI_pin) //D5
#define SDI_0 (PIND & (1<<SDI_pin)) == 0x00 //D5
//
#define SDI_SET_INPUT DDRD &= ~_BV(5) //D5
#define SDI_SET_OUTPUT DDRD |= _BV(5) //D5
//Hisky /CC2500/CYRF aditional pinout
#define CC25_CSN_pin 7
#define NRF_CSN_pin 8
#define CYRF_CSN_pin 9
//
#define CYRF_RST_pin A5 //reset pin
//
#define CC25_CSN_on PORTD |= _BV(7) //D7
#define CC25_CSN_off PORTD &= ~_BV(7) //D7
//
#define NRF_CSN_on PORTB |= _BV(0) //D8
#define NRF_CSN_off PORTB &= ~_BV(0) //D8
//
#define CYRF_CSN_on PORTB |= _BV(1) //D9
#define CYRF_CSN_off PORTB &= ~_BV(1) //D9
//
#define SDO_1 (PIND & (1<<SDO_pin)) == (1<<SDO_pin) //D6
#define SDO_0 (PIND & (1<<SDO_pin)) == 0x00 //D6
//
#define RS_HI PORTC|=_BV(5) //reset pin cyrf
#define RX_LO PORTB &= ~_BV(5)//
//
//
// LED
#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 )
// Macros
#define NOP() __asm__ __volatile__("nop")
#define BV(bit) (1 << bit)
//Serial flags definition
//*******************
//*** Timer ***
//*******************
#ifdef XMEGA
#define TIFR1 TCC1.INTFLAGS
#define OCF1A_bm TC1_CCAIF_bm
#define OCR1A TCC1.CCA
#define TCNT1 TCC1.CNT
#define UDR0 USARTC0.DATA
#define OCF1B_bm TC1_CCBIF_bm
#define OCR1B TCC1.CCB
#define TIMSK1 TCC1.INTCTRLB
#define SET_TIMSK1_OCIE1B TIMSK1 = (TIMSK1 & 0xF3) | 0x04
#define CLR_TIMSK1_OCIE1B TIMSK1 &= 0xF3
#else
#define OCF1A_bm _BV(OCF1A)
#define OCF1B_bm _BV(OCF1B)
#define SET_TIMSK1_OCIE1B TIMSK1 |= _BV(OCIE1B)
#define CLR_TIMSK1_OCIE1B TIMSK1 &=~_BV(OCIE1B)
#endif
//***************
//*** Flags ***
//***************
#define RX_FLAG_on protocol_flags |= _BV(0)
#define RX_FLAG_off protocol_flags &= ~_BV(0)
#define IS_RX_FLAG_on ( ( protocol_flags & _BV(0) ) !=0 )
//
#define CHANGE_PROTOCOL_FLAG_on protocol_flags |= _BV(1)
#define CHANGE_PROTOCOL_FLAG_off protocol_flags &= ~_BV(1)
#define CHANGE_PROTOCOL_FLAG_off protocol_flags &= ~_BV(1)
#define IS_CHANGE_PROTOCOL_FLAG_on ( ( protocol_flags & _BV(1) ) !=0 )
//
#define POWER_FLAG_on protocol_flags |= _BV(2)
@ -262,27 +206,47 @@ struct PPM_Parameters
#define BIND_BUTTON_FLAG_on protocol_flags |= _BV(5)
#define BIND_BUTTON_FLAG_off protocol_flags &= ~_BV(5)
#define IS_BIND_BUTTON_FLAG_on ( ( protocol_flags & _BV(5) ) !=0 )
//PPM RX OK
#define PPM_FLAG_off protocol_flags &= ~_BV(6)
#define PPM_FLAG_off protocol_flags &= ~_BV(6)
#define PPM_FLAG_on protocol_flags |= _BV(6)
#define IS_PPM_FLAG_on ( ( protocol_flags & _BV(6) ) !=0 )
//Bind flag for blinking
//Bind flag
#define BIND_IN_PROGRESS protocol_flags &= ~_BV(7)
#define BIND_DONE protocol_flags |= _BV(7)
#define IS_BIND_DONE_on ( ( protocol_flags & _BV(7) ) !=0 )
//
#define BAD_PROTO_off protocol_flags2 &= ~_BV(0)
#define BAD_PROTO_on protocol_flags2 |= _BV(0)
#define IS_BAD_PROTO_on ( ( protocol_flags2 & _BV(0) ) !=0 )
//
#define RX_DONOTUPDTAE_off protocol_flags2 &= ~_BV(1)
#define RX_DONOTUPDTAE_on protocol_flags2 |= _BV(1)
#define IS_RX_DONOTUPDTAE_on ( ( protocol_flags2 & _BV(1) ) !=0 )
//
#define RX_MISSED_BUFF_off protocol_flags2 &= ~_BV(2)
#define RX_MISSED_BUFF_on protocol_flags2 |= _BV(2)
#define IS_RX_MISSED_BUFF_on ( ( protocol_flags2 & _BV(2) ) !=0 )
//TX Pause
#define TX_MAIN_PAUSE_off protocol_flags2 &= ~_BV(3)
#define TX_MAIN_PAUSE_on protocol_flags2 |= _BV(3)
#define IS_TX_MAIN_PAUSE_on ( ( protocol_flags2 & _BV(3) ) !=0 )
#define TX_RX_PAUSE_off protocol_flags2 &= ~_BV(4)
#define TX_RX_PAUSE_on protocol_flags2 |= _BV(4)
#define IS_TX_RX_PAUSE_on ( ( protocol_flags2 & _BV(4) ) !=0 )
#define IS_TX_PAUSE_on ( ( protocol_flags2 & (_BV(4)|_BV(3)) ) !=0 )
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
//********************
//*** Blink timing ***
//********************
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000
#define BLINK_BAD_PROTO_TIME_HIGH 50
//AUX flags definition
//*******************
//*** AUX flags ***
//*******************
#define GET_FLAG(ch, mask) ( ch ? mask : 0)
#define Servo_AUX1 Servo_AUX & _BV(0)
#define Servo_AUX2 Servo_AUX & _BV(1)
#define Servo_AUX3 Servo_AUX & _BV(2)
@ -292,8 +256,6 @@ struct PPM_Parameters
#define Servo_AUX7 Servo_AUX & _BV(6)
#define Servo_AUX8 Servo_AUX & _BV(7)
#define GET_FLAG(ch, mask) ( ch ? mask : 0)
//************************
//*** Power settings ***
//************************
@ -321,10 +283,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
@ -338,26 +300,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 = 0x50, // -30dbm
//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
@ -373,8 +345,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,
@ -389,45 +361,11 @@ enum {
PKT_TIMEOUT
};
//*******************
//*** CRC Table ***
//*******************
const uint16_t PROGMEM CRCTable[]=
{
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
};
// baudrate defines for serial
#define SPEED_100K 0
#define SPEED_9600 1
#define SPEED_57600 2
#define SPEED_125K 3
//****************************************
//*** MULTI protocol serial definition ***
@ -438,17 +376,18 @@ const uint16_t PROGMEM CRCTable[]=
**************************
Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Total of 26 bytes
Stream[0] = 0x55
Stream[0] = 0x55 sub_protocol values are 0..31
Stream[0] = 0x54 sub_protocol values are 32..63
header
Stream[1] = sub_protocol|BindBit|RangeCheckBit|AutoBindBit;
sub_protocol is 0..31 (bits 0..4)
sub_protocol is 0..31 (bits 0..4), value should be added with 32 if Stream[0] = 0x54
=> Reserved 0
Flysky 1
Hubsan 2
Frsky 3
FrskyD 3
Hisky 4
V2x2 5
DSM2 6
DSM 6
Devo 7
YD717 8
KN 9
@ -463,6 +402,13 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
MJXQ 18
SHENQI 19
FY326 20
SFHSS 21
J6PRO 22
FQ777 23
ASSAN 24
FrskyV 25
HONTAI 26
OpenLRS 27
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
@ -470,28 +416,30 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
RxNum value is 0..15 (bits 0..3)
Type is 0..7 <<4 (bit 4..6)
sub_protocol==Flysky
Flysky 0
V9x9 1
V6x6 2
V912 3
Flysky 0
V9x9 1
V6x6 2
V912 3
sub_protocol==Hisky
Hisky 0
HK310 1
sub_protocol==DSM2
DSM2 0
DSMX 1
Hisky 0
HK310 1
sub_protocol==DSM
DSM2_22 0
DSM2_11 1
DSMX_22 2
DSMX_11 3
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX4 2
XINXUN 3
NIHUI 4
YD717 0
SKYWLKR 1
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
SYMAX 0
SYMAX5C 1
sub_protocol==CX10
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
@ -509,14 +457,20 @@ 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==FY326
FY326 0
FY319 1
E010 4
sub_protocol==FRSKYX
CH_16 0
CH_8 1
sub_protocol==HONTAI
FORMAT_HONTAI 0
FORMAT_JJRCX1 1
FORMAT_X5C1 2
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
option_protocol value is -127..127
@ -529,4 +483,3 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
2047 +125%
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
*/

View 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

View 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

File diff suppressed because it is too large Load Diff

View 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)))))

View 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

File diff suppressed because it is too large Load Diff

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
View 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.

Binary file not shown.

After

Width:  |  Height:  |  Size: 224 KiB

432
Protocols_Details.md Normal file
View File

@ -0,0 +1,432 @@
#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.
The AETR mentionned here for all protocols depends on the TX settings compilation option set in _Config.h.
***
#A7105 RF Module
##FLYSKY
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be AETR.
###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
##FRSKYV = FrSky 1 way
Models: FrSky receivers V8R4, V8R7 and V8FR.
Extended limits supported
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4
---|---|---|---
CH1|CH2|CH3|CH4
##FRSKYD
Models: FrSky receivers D4R and D8R. DIY RX-F801 and RX-F802 receivers.
Extended limits supported
Telemetry enabled for A0, A1, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
##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. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
###Sub_protocol CH_16
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. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
***
#CYRF6936 RF Module
##DEVO
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be EATR.
Bind procedure using serial:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode).
- Turn on RX (RX LED fast blink).
- Turn on TX (RX LED solid, TX LED fast blink).
- Wait for bind on the TX to complete (TX LED solid).
- Make sure to set the RX_Num value for model match.
- Change option to 1 to use the global ID.
- Do not touch option/RX_Num anymore.
Bind procedure using PPM:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on RX (RX LED fast blink).
- Turn the dial to the model number running protocol DEVO on the module.
- Press the bind button and turn on the TX. TX is now in autobind mode.
- Release bind button after 1 second: RX LED solid, TX LED fast blink.
- Wait for bind on the TX to complete (TX LED solid).
- Press the bind button for 1 second. TX/RX is now in fixed ID mode.
- To verify that the TX is in fixed mode: power cycle the TX, the module LED should be solid ON (no blink).
- Note: Autobind/fixed ID mode is linked to the dial number. Which means that you can have multiple dial numbers set to the same protocol DEVO with different RX_Num and have different bind modes at the same time. It enables PPM users to get model match under DEVO.
##DSM
Extended limits supported
Telemetry enabled for TSSI and plugins
option=number of channels from 4 to 12. An invalid option value will end up with 6 channels.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
Notes:
- model/type/number of channels indicated on the RX can be different from what the RX is in fact wanting to see. So don't hesitate to test different combinations until you have something working. Using Auto is the best way to find these settings.
- RX ouput will always be TAER independently of the input AETR, RETA...
###Sub_protocol DSM2_22
DSM2, Resolution 1024, refresh rate 22ms
###Sub_protocol DSM2_11
DSM2, Resolution 2048, refresh rate 11ms
###Sub_protocol DSMX_22
DSMX, Resolution 2048, refresh rate 22ms
###Sub_protocol DSMX_11
DSMX, Resolution 2048, refresh rate 11ms
###Sub_protocol AUTO
The "AUTO" feature enables the TX to automatically choose what are the best settings for your DSM RX and update your model protocol settings accordingly.
The current radio firmware which are able to use the "AUTO" feature are ersky9x (9XR Pro, 9Xtreme, Taranis, ...) and er9x for M128 (9XR) and M2561.
For these firmwares, you must have a telemetry enabled TX and you have to make sure you set the Telemetry "Usr proto" to "DSMx".
Also on er9x you will need to be sure to match the polarity of the telemetry serial (normal or inverted by bitbashing), while on ersky9x you can set "Invert COM1" accordinlgy.
##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
##ASSAN
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
The transmitter must be close to the receiver while binding.
##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 then press a direction to enter headless mode (like stock TX), OPT2=switch 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
Model: FQ777-124
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.
##HONTAI
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
---|---|---|---|---|---|---|---|---|----|----
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|CAL
###Sub_protocol HONTAI
###Sub_protocol JJRCX1
CH6|
---|
ARM|
###Sub_protocol X5C1 clone
##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
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol X800
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol H26D
###Sub_protocol E010
##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.

128
README.md
View File

@ -1,7 +1,21 @@
<<<<<<< HEAD
# DIY-Multiprotocol-TX-Module
=======
# Overview of the MPTM
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159)
The **Multiprotocol Tx Module** (or **MPTM**) is a 2.4GHz transmitter module which enables almost any TX to control lot of different models available on the market.
The source code is partly based on the [Deviation TX project](http://www.deviationtx.com), thanks to all the developers for their great job on protocols.
>>>>>>> refs/remotes/pascallanger/master
## Quicklinks
* [Download latest releases of the firmware](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases)
* [Forum on rcroups](http://www.rcgroups.com/forums/showthread.php?t=2165676)
* [Available Protocols list](docs/Protocol_Details.md)
* [The old documentation](docs/README-old.md)
* [Documentation to-do list](docs/Documentation_To_Do_List.md)
<<<<<<< HEAD
Fork du projet https://github.com/pascallanger/DIY-Multiprotocol-TX-Module
Afin d'ajouter :
@ -186,4 +200,114 @@ A|E|T|R|FLIP 360|FLIP|VIDEO|LED|MODE 2
Same channels assignement as above.
###D'autres à venir
###D'autres à venir
=======
## Outline of the documentation
1. Introduction (this page)
1. [Available protocols](docs/Protocol_Details.md)
1. [Compatible Transmitters](docs/Transmitters.md)
1. [Module Hardware options](docs/Hardware.md)
1. [Compiling and programming the module (ATmega328)](docs/Compiling.md) and [Compiling STM32](Compiling_STM32.md).
1. Transmitter Setup
- [Taranis](docs/Tx-Taranis.md)
- [FlySky TH9X, Turnigy 9X/R](docs/Tx-FlyskyTH9X.md)
1. [How to for popular models](docs/Models.md)
1. [Troubleshooting](docs/Troubleshooting.md)
2. [Advanced Topics (not for the fainthearted!)](docs/Advanced_Topics.md)
## Introduction
A functioning MPTM consists of (see image below):
<img src="docs/images/DIY_Multiprotocol_Module_Overview.png" width="500" height="300" />
1. A host RC Tx
1. A Multiprotocol Transmitter Module that connects to a host transmitter. This module is typically comprised of
* A microcontroller (currently ATMega328P) that interfaces with the Tx, controls the module functions and forwards the RC commands to the RF hardware
* One or more (but at least one) RF modules that provide the capability to communicate with RC receivers. To communicate with the receiver the RF module in the Tx must match with the RF module type in the receiver. The four most common 2.4GHz RF chips on the market are supported TI CC2500, Nordic NRF24L01, Cypress CYRF6936, and the Amiccom A7105
* MPTM firmware loaded on to the microprocessor. At a high level, this firmware performs a few different functions:
* It interfaces with signals from the host Tx and decodes these for transmission to the model, it manages the activation of the correct hardware RF module for each protocol
* It implements the unique communication protocols for each receiver/model and manages the all-important binding process with a receiver/model
* In the case of some protocols (for example DSMX and FrSky) it receives and decodes the telemetry information and makes this available to the receiver.
1. The physical 2.4GHz antenna (or in some cases multiple antennas) for the modules
In constructing a functioning module there are important choices to be made and tradeoffs to be aware of. The most important are:
##**Choice 1:** Which MPTM hardware option
There are currently four generic paths to get your hands on an MPTM. These are outlined in detail on the [hardware](docs/Hardware.md) page. Here they are, in order of increasing difficulty:
- **Ready-made MPTM** - Available from Banggood which includes a 4-in-1 RF module and an antenna switcher
- **DIY MPTM** - Purchase one of the PCB options from [OSHPark](http://www.oshpark.com) and then solder on your own components and RF modules
- **OrangeRx MPTM** You can improve the Orange Rx Transmitter module available from Hobbyking by uploading this firmware
- **Scratchbuild a MPTM** - Build the module from scratch using perfboard base, an Arduino Pro Mini and discrete components.
The last option is where it all started and how the pioneers in this project made their boards. However, due to the growing interest in “one module to rule them all” you now have options to purchase a ready-made board (with old firmware that you will need to upgrade).
For more information on these options see the [hardware](docs/Hardware.md) page
##**Choice 2:** Which RF modules to include in the MPTM
This depends on your specific needs. However, recent the availability of the 4-in-1 RF modules from Banggood for less than $35 makes it easy to “have it all”. Most manufacturers of RC systems (Spektrum, FrSky, FlySky) and toys (Syma, Hubsan, Horizon Hobby, etc.) use one of these four RF chips to manage the RF link between the transmitter and the reciever/model. Here is an incomplete list of the RF modules and some of the most popular toys that use them. For the complete list see the [Protocol Details](docs/Protocol_Details.md) page.
Manufacturer|RF Chip|Example Protocols
:-----------|-------|:-------
Cyprus Semiconductor| CYRF6936|DSM/DSMX
||Walkera Devo
||J6Pro
Texas Instruments|CC2500|FrSky
||Futaba SFHSS
Amiccom|A7105|FlySky
||Turnigy (most)
||Hubsan
Nordic Semiconductor|NRF24L01|HiSky
||Syma
||ASSAN
||and most other Chinese models
For example, if you have no interest in binding your Tx to an model with and FrSky or Futaba SFHSS receiver you do not need to include the CC2500 RF module in your system.
##**Choice 3:** Which protocols to upload to the MPTM
Of course there always a catch. In this case it is the 32K memory limit on the ATmega328 processor. Due to the amazing work done by devs on this project, the memory required by all the possible protocols exceeds this limit considerably. This means that you will need to make a choice of which protocols you will compile into your firmware. Fortunately, the process of selecting and compiling is not too difficult and it is fully documented on the [Compiling and Programming](docs/Compiling.md) page.
Also, the lead dev Pascal Langer (rcgroups:hpnuts) makes this process even easier for many users by making compiled binaries available for three popular combinations of RF modules. These are always “fresh” (based on the latest stable firmware) and available on the [Releases](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases) page.
Midelic has ported a version the firmware to an STM32 ARM microcontroller. If you go the route of building this version of the DIY MPTM then the memory limits do not apply.
##**Choice 4:** Choosing the type of interface between the MPTM and your Tx (PPM or Serial)
The all the MPTM options supports industry standard PPM interface that works with all transmitters with either:
- a module bay or
- a trainer port or
- any PPM signal that can be accessed inside the Tx.
Most of the older FM radios support the PPM interface.
If you are the owner of a transmitter that supports the er9X/erSky9X or OpenTX firmwares (Frsky Taranis running erSky9x or OpenTx, or any of the FlySky/Turnigy family of Txs running ER9X, ERSky9x or OpenTx) you have the additional option to use a serial protocol to communicate between your Tx and the MPTM. (Owners of Walkera Devo transmitters should look at the [Deviation Tx](http://www.deviationtx.com) project for how to achieve the same end goal). This serial protocol does not require any hardware modifications, but will require updating the firmware on your radio. For those willing to do this, there are some nice advantages:
- The model and protocol selection and binding is done from the Model Settings menu on the Tx
- For telemetry capable receivers, the telemetry integration is done seamlessly with the Tx firmware. (Note that FrSky TH9X/Turnigy 9X/R transmitters require a telemetry mod to be done before telemetry can work)
See the [Setting up your Tx](docs/TransmitterSetup.md) page for more details.
#How to get started?
1. Browse the [Protocols](docs/Protocol_Details.md) page to see which protocols you would like on your module
1. Go to the [Hardware Options](docs/Hardware.md) page to decide which of the MPTM options appeals to you and which RF modules you plan to integrate
1. Once you have your module, you should go to [Compiling and Programming](docs/Compiling.md) page to download, compile and program your MPTM
1. Finally, you should visit the [Setting up your Tx](docs/TransmitterSetup.md) page to configure the last few settings before you can fly to your hearts content!!!!!
# Troubleshooting
Visit the [Troubleshooting](docs/Troubleshooting.md) page. Please bear in mind that the MPTM is a complex system of hardware and software and it make take some patience to get it up and running. Also remember that the developers of the system are actual users of the system. This means that at any moment in time the system is working perfectly for them. A corollary to this is that if you are struggling there are likely two scenarios. First, that the problem is with your hardware or with your configuration, second, and much more unlikely but not impossible scenario, is that you are struggling with a new undiscovered bug. (The author of this documentation speaks from experience ;-) Please check the RC Groups forum and search for keywords relating to your problem before posting a reply. When you do post a reply please so humbly and respectfully you will find many helpful people there. In your reply please include as much relevant information as possible and attach compilation output and _Config.h files as text attachments to keep the forum clean.
# A final word
A very big thanks to all the people who have shared their time so graciously to create this great project. If you come across them on RC Groups, please be kind and show appreciation. In no particular order:
* Pascal Langer (rcgroups: hpnuts)
* Midelic (rcgroups: midelic)
* Mike Blandford (rcgroups: Mike Blandford)
* PhracturedBlue from Deviation-tx
* goebish from Deviation-tx
* victzh from Deviation-tx
* hexfet from Deviation-tx
Your help would be greatly appreciated. If protocol reverse-engineering and dev is not your thing then any help with testing and contributing to the documentation would be amazing. Given the number of different Tx/module hardware/RF module/protocol/model combinations the process of testing and documenting is a major bottleneck for the developers. Anything you can do to help will free them up to do even greater things.
>>>>>>> refs/remotes/pascallanger/master

View File

@ -0,0 +1,71 @@
#ATmega Serial Uploader
Mike Blandford adapted the optiboot bootloader for the 4-in-1 module to allow flashing of the module using a standard Arduino USB to serial adapter or FTDI adapter. No need to open the module case. Once set up is very easy to use:
1. plug the serial wires into the module connector,
2. To activate the bootloader, set the rotary switch to 0
3. hold the bind button down for 0.5s while connecting the USB end of the serial cable into the computer
4. Press upload on the Arduino IDE or issue an AVRdude command from the terminal.
It uses a baudrate of 57600, so is the same as a Pro Mini.
The Serial / FTDI connections on the Tx module are as follows:
- Top Pin: Programmer Tx
- 2nd Pin:
- 3rd Pin: Programmer V+
- 4th Pin: Programmer Gnd
- 5th Pin: Programmer Rx
The bootloader starts up, waits half a second, then checks the rotary switch and the bind button. If they aren't as described above, then the normal application runs.
While the bootloader is running, if it detects a communication problem, it configures the watchdog to reset in 16mS, then waits forever. 16mS later the board should reset, and then restart the bootloader, dropping back to the application half a second later.
This bootloader is for reading and writing the flash only, the EEPROM is not supported, neither is reading/writing the fuses, but it only uses 512 bytes of flash.
##Install the bootloader
To get the bootloader onto the ATmega you need to connect an flashing tool (like USBasp) to the 6-pin ISP connector on the board.
Simply flash the .hex file to get the bootloader on the chip, and change the high fuse at the same time.
The bootloader only uses 512 bytes of flash and is avaialble for download [here](http://www.rcgroups.com/forums/showatt.php?attachmentid=9291360&d=1472324155). The orginal rcgroups post is [here](http://www.rcgroups.com/forums/showpost.php?p=35584619&postcount=4867).
The HIGH fuse needs to be set to 0xD6. (See the section below on Setting the Fuses with AVRdude.)
## Setting fuses with AVRdude
###Determining the location of the avrdude program
The Arduino IDE is used to upload firmware and set fuses on the ATMega microprocessor.
You can install avrdude on your computer, but it is already contained in the Arduino IDE bundle and we suggest that you use the Arduino-bundled version.
1. Unplug any programmer that may be connected to the computer
1. In the Arduino IDE click on Sketch -> Upload Using Programmer
1. After a series of compiling messages you will see an error that a programmer is not found. Scroll up and find the programming command that caused the errors (usually the last white line before the red errors) and copy it into TextEdit or Notepad.
1. This is your programming command and it should look something like this:
**Mac:**
> ```
> /Applications/Arduino.app/Contents/Java/hardware/tools /avr/bin/avrdude -C/Applications/Arduino.app/Contents/ Java/hardware/tools/avr/etc/avrdude.conf -patmega328p -cusbasp -Pusb -Uflash:w:{this part will be unique to your system} /Multiprotocol.ino.hex:i
> ```
**PC:**
> ```
> C:\Program Files (x86)\Arduino\Contents\Java\hardware\tools\ avr\bin\avrdude -CC:\Program Files (x86)\Arduino\Contents\Java\ hardware\tools\avr\etc\avrdude.conf -patmega328p -cusbasp -Pusb -Uflash:w:{this part will be unique on your system}\ Multiprotocol.ino.hex:i
> ```
Select all the text up to the ```-Uflash ``` command, copy it and paste it into a new line and add a “-v” (without the "") at the end of the line.
This is your “verify” command and it should look something like this:
> ```
> /Applications/Arduino.app/Contents/Java/hardware/tools/avr/bin/avrdude -C/Applications/Arduino.app/Contents/Java/hardware/ tools/avr/etc/avrdude.conf -patmega328p -cusbasp -Pusb -v
> ```
We will be using these two commands to program the module.
1. Verify that the connection is working by pasting the Verify line into a terminal. You should see output that includes the fuse settings.
2. 1. To program the High Fuse copy the “verify” command and paste it into the shell add the following text to the end of the line ```-U hfuse:w:0xD6:m ``` . Press Enter.

View File

@ -0,0 +1,30 @@
#Bluetooth Telemetry in PPM Mode
###Telemetry
There are 4 protocols supporting telemetry: Hubsan, DSM, FrSkyD and FrSkyX.
Hubsan displays the battery voltage and TX RSSI.
DSM displays TX RSSI and full telemetry.
FrSkyD displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub).
FrSkyX displays full telemetry (A1, A2, RX RSSI, TX RSSI and Hub).
### If used in PPM mode
Telemetry is available as a serial output on the TX pin of the Atmega328p using the FrSky hub format for Hubsan, FrSkyD, FrSkyX and DSM format for DSM2/X. The serial paramets depends on the protocol:
Protocol|Serial Parameters
--------|-----------------
Hubsan|9600bps 8n1
FrSkyD|9600bps 8n1
FrSkyX|57,600bps 8n1
DSM2/X|125,000bps 8n1
The serial stream is also available on pin 5 of the Module connector (pins numbered from top to bottom) on the [4-in-1 module](Module_BG_4-in-1.md) and the [V2.3d modules](Module_Build_yourself_PCB.md) provided the Tx jumper has been soldered. See the linked module documentation for what this means.
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.

View File

@ -0,0 +1,57 @@
#Manually Setting ATmega328 Fuses
To understand fuses refer to the ATmega328P datasheet (See Section 28.3 Fuse Bits)
## Fuse settings
Here are some fuse settings for common configurations:
Board|Low Fuse|High Fuse|Extended Fuse
-----|--------|---------|-------------
Arduino Pro Mini with Arduino bootloader|0xFF|0xD2|0xFD
DIY 3.2d PCB without bootloader |0xFF|0xD3|0xFD
DIY 3.2d PCB with [custom mikeb bootloader](Advanced_ATmega_Serial_Uploader.md) |0xFF|0xD6|0xFD
Banggood 4-in-1 module without bootloader |0xFF|0xD3|0xFD
Banggood 4-in-1 module with [custom mikeb bootloader](Advanced_ATmega_Serial_Uploader.md) |0xFF|0xD6|0xFD
##Determining the location of the avrdude program
The Arduino IDE is used to upload firmware and set fuses on the ATMega microprocessor.
You can install avrdude on your computer, but it is already contained in the Arduino IDE bundle and we suggest that you use the Arduino-bundled version.
1. Unplug any programmer that may be connected to the computer
1. In the Arduino IDE click on Sketch -> Upload Using Programmer
1. After a series of compiling messages you will see an error that a programmer is not found. Scroll up and find the programming command that caused the errors (usually the last white line before the red errors) and copy it into TextEdit or Notepad.
1. This is your programming command. You can use it to manually upload the latest .hex file compiled by the Arduino IDE "Verify" button, and it should look something like this:
**Mac:**
> ```
> /Applications/Arduino.app/Contents/Java/hardware/tools /avr/bin/avrdude -C/Applications/Arduino.app/Contents/ Java/hardware/tools/avr/etc/avrdude.conf -patmega328p -cusbasp -Pusb -Uflash:w:{this part will be unique to your system} /Multiprotocol.ino.hex:i
> ```
**PC:**
> ```
> C:\Program Files (x86)\Arduino\Contents\Java\hardware\tools\ avr\bin\avrdude -CC:\Program Files (x86)\Arduino\Contents\Java\ hardware\tools\avr\etc\avrdude.conf -patmega328p -cusbasp -Pusb -Uflash:w:{this part will be unique on your system}\ Multiprotocol.ino.hex:i
> ```
Select all the text up to the ```-Uflash ``` command, copy it and paste it into a new line and add a “-v” (without the "") at the end of the line.
This is your “verify” command and it should look something like this:
> ```
> /Applications/Arduino.app/Contents/Java/hardware/tools/avr/bin/avrdude -C/Applications/Arduino.app/Contents/Java/hardware/ tools/avr/etc/avrdude.conf -patmega328p -cusbasp -Pusb -v
> ```
We will be using the command line to program the module.
1. It is good practice to check on the connection with the board before you program fuses. Paste the "verify" command from above into a command line terminal. It should retun with messages that indicate an ATmega328p was successfully found and it should return the current fuse settings.
1. To program the Low Fuse copy the “verify” command and paste it into the shell add the following text to the end of the line ```-U lfuse:w:0xFF:m ``` . Press Enter. ** Note: If you want a different fuse setting, change the 0xFF with the hexadecimal value of the low fuse setting. **
1. To program the Extended Fuse copy the “verify” command and paste it into the shell add the following text to the end of the line ```-U efuse:w:0xFD:m ``` . Press Enter. ** Note: If you want a different fuse setting, change the 0xFD with the hexadecimal value of the extended fuse setting. **
1. There are two options for the High fuse.
- If you selected the 4-in-1 Board in the Arduino IDE then you compiled firmware to not include the unecessary Arduino bootloader. To program the High Fuse copy the “verify” command and paste it into the shell and add the following text to the end of the line ```-U hfuse:w:0xD3:m ``` . Press Enter. ** Note: If you want a different fuse setting, change the 0xD3 with the hexadecimal value of the extended fuse setting. **
- If you selected the Arduino Pro-Mini (or any other Arduino board) in the Arduino IDE then you compiled firmware to include the Arduino bootloader. To program the High Fuse copy the “verify” command and paste it into the shell and add the following text to the end of the line ```-U hfuse:w:0xD2:m ``` . Press Enter. ** Note: If you want a different fuse setting, replace the 0xD2 with the hexadecimal value of the extended fuse setting. **

20
docs/Advanced_Topics.md Normal file
View File

@ -0,0 +1,20 @@
#Advanced Topics {This page is currently a proof of concept}
Warning: the topics on this page are not for the fainthearted. It is strongly recommended that you have some experience in getting up and runnning with your module before you dive in there. On the other hand what is described on this page are some very useful options that could greatly increase the value and the enjoyment of your Multiprotocol module.
#Serial uploader that works through the transmitter pins
This document describes how you can set up your ATmega-based Mulitprotocol module to allow you to update the firmware by connecting a USB to TTL serial (like a FTDI) adapter to the module's transmitter interface pins. It is great if you exclusively use the Serial interface with your transmitter because the Bind button is used as "bootloader" button. It requires a small custom bootloader to be uploaded and a simple interface cable to be soldered up. See the [Advanced ATmega Serial Uploader](Advanced_ATmega_Serial_Uploader.md) page for more details.
Created and supported by: Mike Blandford
RCGroups page: http://www.rcgroups.com/forums/showpost.php?p=35584619&postcount=4867
#Bluetooth telemetry board for telemetry in PPM mode
This document describes a simple bluetooth module to stream telemetry information to a mobile device like an Android smartphone or tablet. This is very useful with modules used in the PPM mode with transmitters that do not support telemetry. See the [Advanced Bluetooth Telemetry](Advanced_Bluetooth_Telemetry.md) page for more details.
Created and supported by: Midelic
RCGroups page: None
#Manually setting fuses on ATmega328
This document describes a relatively simple process to set the fuses on ATmega328 using the flexibility of the command line. It does not require installation of AVRdude because it uses the AVRdude that is bundled with the Arduino IDE. See the [Advanced Manually Setting ATmega328 Fuses](Advanced_Manually_Setting_ATmega328_Fuses.md) page for more details.
Created and supported by: hpnuts
RCGroups page: No rcgroups page

35
docs/BOM_DIY_ATmega.md Normal file
View File

@ -0,0 +1,35 @@
#Bill of Materials DIY ATmega Module
Here is the bill of materials for the ATmega328 version of the DIY MPTM.
If you are looking for the BOM for the DIY STM32 version click [here](BOM_DIY_STM32.md).
Digikey may not be your preferred supplier, but you should find enough information on their page to cross reference parts.
## BOM DIY ATmega PCB - V3.2d
This BOM is for the board that looks like this - check carefully:
<img src="images/MPTM_PCB_3.2d.png" />
Qty|Part|Description|Value|Package|Digikey Part Number
---|----|-----------|-----|-------|-------------------
2|C4 C5|Ceramic Cap|18pF|0603|[445-1272-1-ND](http://www.digikey.com/product-detail/en/tdk-corporation/C1608C0G1H180J080AA/445-1272-1-ND/567674)
2|C2 C7|Ceramic Cap|0.1uF|0603|[45-1316-1-ND](http://www.digikey.com/product-detail/en/tdk-corporation/C1608X7R1E104K080AA/445-1316-1-ND/567697)
3|C1 C3 C6|Cap Tantal|22uF/16V|1206|[478-8254-1-ND](https://www.digikey.com/product-detail/en/avx-corporation/F931C226MAA/478-8254-1-ND/4005702)
2|LED|Red/Green Led|LED3mm|||
1|IC1|ATmega328P|||[ATMEGA328P-AURCT-ND](http://www.digikey.com/product-detail/en/atmel/ATMEGA328P-AUR/ATMEGA328P-AURCT-ND/3789455)
1|JP1 JP2|Pin header|1x3||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|U4 U6|Pin header|1x10||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|P1|ISP|2x3||[3M9459-ND](http://www.digikey.com/product-search/en?keywords=3M%20961206-6404-AR)
1|P2|Receptacle|5-pin||[WM14512-ND](http://www.digikey.com/product-search/en?keywords=Molex%2C%20LLC%200022142054)
2|R4 R6|Resistor|1K|0603|[P1.0KGCT-ND](http://www.digikey.com/product-search/en?keywords=P1.0KGCT-ND)
1|R2|Resistor|2.2K|0603|[P2.2KGCT-ND](http://www.digikey.com/product-search/en?keywords=P2.2KGCT-ND)
2|R1 R3|Resistor|10k|0603|[P10KGCT-ND](http://www.digikey.com/product-search/en?keywords=P10KGCT-ND)
1|R5|Resistor|20K|0603|[P20KGCT-ND](http://www.digikey.com/product-search/en?keywords=P20KGCT-ND)
1|SW1|Hex Switch||4-DIP|[FR01KR16P-W-S-ND](https://www.digikey.com/product-detail/en/nkk-switches/FR01KR16P-W-S/FR01KR16P-W-S-ND/2104098)
1|Sw2|Momentary Switch||6mm|[ 450-1643-ND](https://www.digikey.com/product-detail/en/te-connectivity-alcoswitch-switches/2-1825910-7/450-1642-ND/1632528)
1|SW3|Momentary Switch||6mm|[CKN9104CT-ND](http://www.digikey.com/product-search/en?keywords=CKN9104CT-ND)
1|U1|Voltage reg 5V|AMS1117-50|SOT223|[LM1117MP-5.0/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MP-5.0-NOPB/LM1117MP-5.0-NOPBCT-ND/363589)
1|U2|Voltage reg 3.3V|AMS1117-33|SOT223|[LM1117MPX-3.3/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MPX-3.3-NOPB/LM1117MPX-3.3-NOPBCT-ND/1010516)
1|X1|8 MHz Crystal|8MHz||[535-10267-1-ND](http://www.digikey.com/product-search/en?keywords=535-10267-1-ND)
1||2.4GHz Antenna|||[553-1309-ND](http://www.digikey.com/product-search/en?keywords=553-1309-ND)

77
docs/BOM_DIY_STM32.md Normal file
View File

@ -0,0 +1,77 @@
#Bill of Materials DIY STM32 Module
Here is the bill of materials for the STM32 version of the DIY MPTM. There are two versions. Carefully compare your board with the picture below to determine which version you have.
If you are looking for the BOM for the DIY ATmega328 3.2d version click [here](BOM_DIY_ATmega.md).
Digikey may not be your preferred supplier, but you should find enough information on their page to cross reference parts.
## BOM DIY STM32 PCB - the first Version
This BOM is for the board that looks like this - check carefully:
<img src="https://camo.githubusercontent.com/9b8dc4eb5618583ebe8fc01f03f2da75766080b3/68747470733a2f2f36343464623464653335303563343061303434342d33323737323362636532393865336666353831336662343262616565666261612e73736c2e6366312e7261636b63646e2e636f6d2f66326435393865616364386539656562633338313861646634373737373139392e706e67" />
Qty|Part|Description|Value|Package|Digikey Part Number
---|----|-----------|-----|-------|-------------------
1|3.3VJumper|Jumper|1x2||[3M9467-ND](https://www.digikey.com/product-detail/en/3m/961102-5604-AR/3M9467-ND/2071508)
2|C1,C2|Cap Cera|0.1uF|0805|[311-1361-1-ND](https://www.digikey.com/product-detail/en/yageo/CC0805ZRY5V9BB104/311-1361-1-ND/2103145)
3|C3,8,9|Cap Tantal|22uF/16V|1206|[478-8254-1-ND](https://www.digikey.com/product-detail/en/avx-corporation/F931C226MAA/478-8254-1-ND/4005702)
1|D1|Diode Shottky|1N5819||[1N5819HW-FDICT-ND](https://www.digikey.com/product-detail/en/diodes-incorporated/1N5819HW-7-F/1N5819HW-FDICT-ND/815283)
1|IC1|Voltage reg 3.3V|AMS1117-33|SOT223|[LM1117MPX-3.3/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MPX-3.3-NOPB/LM1117MPX-3.3-NOPBCT-ND/1010516)
1|IC2|Voltage reg 5V|AMS1117-50|SOT223|[LM1117MP-5.0/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MP-5.0-NOPB/LM1117MP-5.0-NOPBCT-ND/363589)
1|J301|Receptacle|5-pin||[WM3103-ND](http://www.digikey.com/product-search/en?keywords=WM3103-ND)
1|JP1|Pin header|1x3||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|JP2|Pin header|1x4||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|L1|High Freq Inductor|10uH|1812|[CM453232-100KLCT-ND](https://www.digikey.com/product-detail/en/bourns-inc/CM453232-100KL/CM453232-100KLCT-ND/3437938)
1|LED|Red Led|LED3mm|||
2|R1,R8|SMD Resistor|2.2K|0805|[RMCF0805JT2K20CT-ND ](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT2K20/RMCF0805JT2K20CT-ND/1942563)
3|R2,R5,R10|SMD Resistor|10K|0805|[RMCF0805JT10K0CT-ND](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT10K0/RMCF0805JT10K0CT-ND/1942577)
1|R3|SMD Resistor|4.7K|0805|[311-4.70KCRCT-ND](https://www.digikey.com/product-detail/en/yageo/RC0805FR-074K7L/311-4.70KCRCT-ND/730876)
1|R5|SMD Resistor|1K|0805|[311-1.0KARCT-ND](https://www.digikey.com/product-detail/en/yageo/RC0805JR-071KL/311-1.0KARCT-ND/731165)
1|R7|SMD Resistor|470|0805|[RMCF0805JT470RCT-ND](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT470R/RMCF0805JT470RCT-ND/1942551)
1|Switch|Hex Switch||4-DIP|[FR01KR16P-W-S-ND](https://www.digikey.com/product-detail/en/nkk-switches/FR01KR16P-W-S/FR01KR16P-W-S-ND/2104098)
1|Switch|Momentary Switch||6mm|[ 450-1643-ND](https://www.digikey.com/product-detail/en/te-connectivity-alcoswitch-switches/2-1825910-7/450-1642-ND/1632528)
1|MCU|STM32F103CBT6||LQFP48|[STM32F103CBT6](https://www.digikey.com/product-detail/en/stmicroelectronics/STM32F103CBT6/497-6288-ND/1754420)
1|U$1|4-in-1 RF Module|||[Banggood 4-in-1 Module](http://www.banggood.com/DIY-2_4G-CC2500-NRF24L01-A7105-CYRF6936-Multi-RF-4-IN-1-Wireless-Module-p-1046308.html)
1|Y2|8mHz Resonator|8mHz||[490-1195-1-ND](https://www.digikey.com/product-detail/en/murata-electronics-north-america/CSTCE8M00G55-R0/490-1195-1-ND/584632)
1|U1|Dual INPUT-XOR|SN74LVC2G00DCTR|SSOP-8|[296-13257-1-ND](https://www.digikey.com/product-detail/en/texas-instruments/SN74LVC2G00DCTR/296-13257-1-ND/484537)
1|U.FL|SMD ant. conn.|||[WM5587CT-ND](https://www.digikey.com/product-detail/en/molex-llc/0734120110/WM5587CT-ND/1894612)
## BOM DIY STM32 PCB - the V0.8
This BOM is for the board that looks like this - check carefully:
<img src="https://camo.githubusercontent.com/b46c53c214cf87184d202f57f328413d3629ca24/68747470733a2f2f36343464623464653335303563343061303434342d33323737323362636532393865336666353831336662343262616565666261612e73736c2e6366312e7261636b63646e2e636f6d2f36633561613434363133356336363336613030383064623763613238663162652e706e67" />
Qty|Part|Description|Value|Package|Digikey Part Number
---|----|-----------|-----|-------|-------------------
1|J301|Receptacle|5-pin||[WM3103-ND](http://www.digikey.com/product-search/en?keywords=WM3103-ND)
1|SV201|Jumper|1x3||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|SV202|Pin header|1x4||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|SV203|Pin header|1x4||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
1|SV204|Pin header|1x3||[S1011EC-40-ND](https://www.digikey.com/product-detail/en/sullins-connector-solutions/PRPC040SAAN-RC/S1011EC-40-ND/2775214)
3|C101, 102, 103|Cap Tantal|22uF/16V|1206|[478-8254-1-ND](https://www.digikey.com/product-detail/en/avx-corporation/F931C226MAA/478-8254-1-ND/4005702)
7|C201, 202, 204, 205, 206, 209, 301|Cap Cera|0.1uF|0805|[311-1361-1-ND](https://www.digikey.com/product-detail/en/yageo/CC0805ZRY5V9BB104/311-1361-1-ND/2103145)
1|C203|Cap Cera|4u7|0805|[311-1371-1-ND](https://www.digikey.com/product-detail/en/yageo/CC0805ZRY5V6BB475/311-1371-1-ND/2103155)
1|C207|Cap Cera|1uF|0805|[311-1365-1-ND](https://www.digikey.com/product-detail/en/yageo/CC0805KKX7R7BB105/311-1365-1-ND/2103149)
1|C208|Cap Cera|10nF|0805|[311-1085-1-ND](http://www.digikey.com/product-detail/en/yageo/CC0603KRX7R9BB103/311-1085-1-ND/302995)
1|D301, D302, D303|Diode Shottky|BAT48||[497-5711-1-ND](https://www.digikey.com/product-detail/en/stmicroelectronics/BAT48JFILM/497-5711-1-ND/1299964)
1|IC101|Voltage reg 5V|AMS1117-50|SOT223|[LM1117MP-5.0/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MP-5.0-NOPB/LM1117MP-5.0-NOPBCT-ND/363589)
1|IC102|Voltage reg 3.3V|AMS1117-33|SOT223|[LM1117MPX-3.3/NOPBCT-ND](https://www.digikey.com/product-detail/en/texas-instruments/LM1117MPX-3.3-NOPB/LM1117MPX-3.3-NOPBCT-ND/1010516)
1|L101|High Freq Inductor|10uH|1812|[CM453232-100KLCT-ND](https://www.digikey.com/product-detail/en/bourns-inc/CM453232-100KL/CM453232-100KLCT-ND/3437938)
1|LED101, LED102|Red/Green Led|LED3mm|||
2|R302, R303|SMD Resistor|2.2K|0805|[RMCF0805JT2K20CT-ND ](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT2K20/RMCF0805JT2K20CT-ND/1942563)
3|R202, R203|SMD Resistor|10K|0805|[RMCF0805JT10K0CT-ND](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT10K0/RMCF0805JT10K0CT-ND/1942577)
1|R301, R305|SMD Resistor|4.7K|0805|[311-4.70KCRCT-ND](https://www.digikey.com/product-detail/en/yageo/RC0805FR-074K7L/311-4.70KCRCT-ND/730876)
1|R101, 201|SMD Resistor|1K|0805|[311-1.0KARCT-ND](https://www.digikey.com/product-detail/en/yageo/RC0805JR-071KL/311-1.0KARCT-ND/731165)
1|R304|SMD Resistor|470|0805|[RMCF0805JT470RCT-ND](https://www.digikey.com/product-detail/en/stackpole-electronics-inc/RMCF0805JT470R/RMCF0805JT470RCT-ND/1942551)
1|S201|Hex Switch||4-DIP|[FR01KR16P-W-S-ND](https://www.digikey.com/product-detail/en/nkk-switches/FR01KR16P-W-S/FR01KR16P-W-S-ND/2104098)
1|S202|Momentary Switch||6mm|[ 450-1643-ND](https://www.digikey.com/product-detail/en/te-connectivity-alcoswitch-switches/2-1825910-7/450-1642-ND/1632528)
1|IC201|STM32F103CBT6||LQFP48|[STM32F103CBT6](https://www.digikey.com/product-detail/en/stmicroelectronics/STM32F103CBT6/497-6288-ND/1754420)
1|M401|4-in-1 RF Module|||[Banggood 4-in-1 Module](http://www.banggood.com/DIY-2_4G-CC2500-NRF24L01-A7105-CYRF6936-Multi-RF-4-IN-1-Wireless-Module-p-1046308.html)
1|Y201|8mHz Resonator|8mHz||[490-1195-1-ND](https://www.digikey.com/product-detail/en/murata-electronics-north-america/CSTCE8M00G55-R0/490-1195-1-ND/584632)
1|U301|Dual INPUT-XOR|SN74LVC2G00DCTR|SSOP-8|[296-13257-1-ND](https://www.digikey.com/product-detail/en/texas-instruments/SN74LVC2G00DCTR/296-13257-1-ND/484537)
1|CON401|SMD ant. conn.|||[WM5587CT-ND](https://www.digikey.com/product-detail/en/molex-llc/0734120110/WM5587CT-ND/1894612)

10
docs/Bind_Timing.md Normal file
View File

@ -0,0 +1,10 @@
#Getting your Bind timing right.
On many consumer models it it important for the Tx to send a bind signal in a narrow window once the model has powered up.
If the bind signal is not recieved during this window, the bind sequence times out. Try this:
1. power the transmitter up with the throttle stick high. This will trigger the warning window on the transmitter and put a hold on the transmitter bind process.
1. turn on the model
1. while holding the bind button (if in PPM mode), at the right moment bring the throttle down to instantly bring the transmitter into bind mode.
If you are using Serial Mode it is best to check the Autobind box in the Model Settings menu. This will automatically initiate a bind sequence as soon as the Tx module powers up (Note: the Tx module only powers up when the transmitter passes the Switch/Throttle Warning page).

210
docs/Compiling.md Normal file
View File

@ -0,0 +1,210 @@
# Compiling and Programming (ATmega 328P)
**If you are Compling for the STM32 version of the Multiprotocol Module please go to the dedicated [Compiling and Programming STM32](Compiling_STM32.md) page.**
**This page describes the basic Compiling and Programming process. There are some other more advanced processes that have some superior features described under the [Advanced Topics](Advanced_Topics.md) page.** Some options are:
- Using an FTDI cable to upload firmware over the module - Tx pins
Multiprotocol source can be compiled using the Arduino IDE.
##Install the Arduino IDE and the Multiprotocol project
1. Download the Arduino IDE. The currently supported Arduino version is 1.6.10. available for [Windows]( https://www.arduino.cc/download_handler.php?f=/arduino-1.6.10-windows.exe) and [Mac OSX](http://arduino.cc/download_handler.php?f=/arduino-1.6.10-macosx.zip)
1. Download the zip file with the Multiprotocol module source code from [here](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/archive/master.zip)
1. Unzip and copy the source code folder **Multiprotocol** to a folder of your choosing
1. Click on the **Multiprotocol.ino** file in the **Multiprotocol** folder and the Arduino environment should appear and the Multiprotocol project will be loaded.
##Prepare the Arduino IDE:
The Arduino IDE must be customized to optimally compile the firmware. The following additions to the environment will remove the Arduino bootloader to free up additional memory for protocols.
###Mac OSX:
1. Using finder navigate to ```Applications``` folder
1. Ctl-Click on the Arduino application and select **Show Package Contents**.
1. Browse to ```Contents/Java/hardware/arduino`` and double click on boards.txt
1. Copy and paste the following text into the end of the file and save it:
```
##############################################################
## Multi 4-in-1 (3.3V, 16 MHz) w/ ATmega328
## --------------------------------------------------
multi.name=Multi 4-in-1
multi.upload.tool=avrdude
multi.upload.protocol=arduino
multi.bootloader.tool=avrdude
multi.bootloader.unlock_bits=0x3F
multi.bootloader.lock_bits=0x0F
multi.build.board=AVR_PRO
multi.build.core=arduino
multi.build.variant=eightanaloginputs
multi.menu.cpu.16MHzatmega328=ATmega328 (3.3V, 16 MHz)
multi.menu.cpu.16MHzatmega328.upload.maximum_size=32768
multi.menu.cpu.16MHzatmega328.upload.maximum_data_size=2048
multi.menu.cpu.16MHzatmega328.upload.speed=57600
multi.menu.cpu.16MHzatmega328.bootloader.low_fuses=0xFF
multi.menu.cpu.16MHzatmega328.bootloader.high_fuses=0xD3
multi.menu.cpu.16MHzatmega328.bootloader.extended_fuses=0xFD
multi.menu.cpu.16MHzatmega328.build.mcu=atmega328p
multi.menu.cpu.16MHzatmega328.build.f_cpu=16000000L
##############################################################
```
1. Open the file *platform.txt* in the same folder and change the line that reads
```compiler.c.elf.extra_flags= ```
to
```compiler.c.elf.extra_flags=-Wl,--relax ```
paste the following text into the end of the file and save it.
Close and reopen the Arduino IDE and load the Multiprotocol project.
### Windows:
Using File Explorer navigate to
```C:\Program Files(x86)\Arduino\hardware\arduino\avr ```
Open ```boards.txt``` in your favourite text editor (Notepad)
Copy and paste the "Multi 4-in-1" text listed above into the end of the file and save it.
Open the file *platform.txt* in the same folder and change the line that reads
```compiler.c.elf.extra_flags= ```
to
```compiler.c.elf.extra_flags=-Wl,--relax ```
Close and reopen the Arduino IDE and load the Multiprotocol project.
## Common process for OSX and Windows
If you have module with an Arduino Pro-Mini then scroll down to [Programming Arduino Pro-Mini Boards](#Programming_Arduino_Pro_Mini)
If you are using one of the DIY Mulitprotocol modules with the ATmega soldered directly to a PCB (like the 3.2d board or the Banggood readymade 4-in-1 module) then follow these instructions.
###Preparing for ATMega328P microcontroller
1. Under the Tools -> Board select the Multi 4-in-1 board
1. Under Tools -> Programmer select your programmer (probably USBASP)
<a name="CustomizeFirmareToYourNeeds"></a>
###Customize the firmware to your hardware and your needs
On all modules with ATMega microprocessors, the memory required for all the protocols exceeds the available 32k of flash memory. You will need to select which protocols you wish to use that will fit into the available memory.
Before customizing your firmware it would be good to review the protocol on the [Protocol Details](Protocol_Details.md) page and to identify the protocols you would like to support on your module.
At the same time make a note of RF modules required by your protocols. For example, if you do not wish to use the FlySky or the Husan protocols then you do not need to compile support the the A7105 RF Module into your firmware. Similarly, if you have no need to bind with ASSAN RC receivers then you do not need to compile the ASSAN protocol into your firmware.
If you plan to use the PPM communication interface with your transmitter, then you need to perform protocol selection with the 16 position switch on your module. This will limit the available protocols you can usefully include on your firmware to 15. You should make a list of your 15 chosen protocols, sub protocols and options like this:
Switch Position|Protocol|Sub-Protocol|Option|Notes
---------------|--------|------------|------|-----
1.|DSM|DSM2|2|6 channels @ 22ms
2.|DSM|DSMX|6|6 channels @ 11ms
....|...|...|...|...
....|...|...|...|...
15.|FRSKYX|CH_16| |FrSky X receiver 16 chan
With the above information (required RF modules, selected protocols and 16 pos switch mapping) you are ready to customize your firmware.
All customization is done by editing the ```_Config.h ``` file in the Multiprotocol Arduino project.
In the Arduino IDE and click on the down arrow on the far right of the tab bar to show a list of project files (see the red circle on the screenshot below). Scroll down and select the _Config.h file.
<img src="images/Arduino.png" width="600" height="400" />
Comment out any of the RF modules that you do not need by typing ```// ``` at the begining of the line that reads :
```#define <RF Module name>_INSTALLED ``` . The following line shows the CC2500 module removed
> ```#define A7105_INSTALLED ```
> ```#define CYRF6936_INSTALLED ```
> **```//#define CC2500_INSTALLED ```**
> ```#define NFR24L01_INSTALLED ```
Scroll down to the available protocols and comment out all the protocols you will not require. The following example shows the DEVO protocol commented out.
> ```#ifdef CYRF6936_INSTALLED ```
> **``` // #define DEVO_CYRF6936_INO ```**
> ``` #define DSM_CYRF6936_INO ```
> ``` #define J6PRO_CYRF6936_INO ```
> ``` #endif ```
If you have a Taranis Tx and you plan on using Serial mode with telemetry find and uncomment the INVERT_TELEMETRY line below:
> ```//Uncomment to invert the polarity of the telemetry serial signal.```
> ```//For ER9X and ERSKY9X it must be commented. For OpenTX it must be uncommented.```
> ```#define INVERT_TELEMETRY 1```
Scroll down to the bottom of the file and list your switch mapping to your desired **protocol/sub-protocol/options**. You typically only need to change the three relevant columns. On models that require a rebind on every start-up (like Syma quads) you can change the **```NO_AUTOBIND ```** to **```AUTOBIND ```**.
You can now compile the firmware by clicking on the check mark (Tooltip: Verify) on the menu bar. If everything goes according to plan you should see something like the following line in the lower pane of the window:
> Sketch uses 32,464 bytes (99%) of program storage space. Maximum is 32,768 bytes.
> Global variables use 1,219 bytes (59%) of dynamic memory, leaving 829 bytes for local variables. Maximum is 2,048 bytes.
if you see something like the following, your firmware is still too big and you need to deselect additional protocols:
> Sketch uses 34,096 bytes (104%) of program storage space. Maximum is 32,768 bytes.
> Global variables use 1,236 bytes (60%) of dynamic memory, leaving 812 bytes for local variables. Maximum is 2,048 bytes.
> Sketch too big; see http://www.arduino.cc/en/Guide/Troubleshooting#size for tips on reducing it.
If there is another error carefully read the error to see the approximate line number where you made a typing error.
###Connecting the programmer
To complete this step you need an USBASP programmer like the one shown below and a 10-pin to 6-pin programming cable.
<img src="images/USBasp_Programmer.jpeg" width="200" height="200" />
1. Before you connect the programmer make sure that you have selected the 3.3V mode and not the 5V mode. The RF Modules are not 5V tolerant and you will harm with 5V. On most programmers this is done by moving a jumper on the programmer.
1. Please re-read item 1. above before going on.
1. Turn the rotary switch on the DIY Multiprotocol module to the 0 position. If you do not have a switch (if you are using only Serial mode) then it the same as being in the 0 position. The upload will not work if the switch is in any other position.
1. Connect the 6-pin programming connector to the 6-pin ASP IVR connector on the DIY Multiprotocol board. Be sure to match the ground pin of the programmer connector to the ground pin on the board (see the images below for the pin layout and the location of the ground pin on the board) {insert pictures AVR ISP Pinout.png and images of boards with ground pin marked}
1. You are now ready to plug in the USB programmer to the computer
1. You are now ready to flash the firmware. In the Arduino IDE click **Sketch -> Upload Using Programmer**.
2. If you get an error that indicates a valid microprocessor was not found there is something wrong with:
- your connections,
- your programmer, or
- your board
- Google around with the specific error message to get suggestions of how to fix it. The most common cause is problems with the connection setup and in some cases problems with the cheap programmers from Chinese sources.
1. The final step is to flash the fuses of the microprocessor. These correct fuses will do a few things:
- Prevent the EEPROM from being erased each time the firmware is flashed. This will preserve your Tx ID and save you from having to rebind all your models after an update of the firmware
- Configure the clock source of the board - this is very important if you built the board from components. The ATMega328P microprocessor is configured at the factory to use an internal 8Mhz clock. The DIY Multiprotocol boards have a much more accurate 16MHz external crystal and the fuses will tell the MCU to use this clock source. (If you were able to flash the board but after setting the fuses the board no longer responds, it is very likely that you have a problem with your external clock.)
- Set the program counter to point at the right place when the module is powered up. The fuses configure the MCU to use a bootloader or not. If you compiled the firmware without a bootloader then the fuses must be set accordingly.
1. In the Arduino IDE ensure that the **4-in-1 Multi** is selected under **Tools -> Board:** click on **Tools -> Burn Bootloader**. Do not worry if it returns the error that no bootloader was found (in the case of the 4-in-1 board), it has burned the fuses. If you IDE was set to provide verbose compilation and uploading output, you should be able to see the final value of the fuses in the Arduino IDE.
If the output indicates that the fuses have been successfully written give yourself a pat on the back. Well done, you have successfully programmed your DIY Multiprotocol module and you are ready to go on to the final step [Setting up your Transmitter](TransmitterSetup.md) before you can begin to fly!!!!
<a name="Programming_Arduino_Pro_Mini"></a>
##Programming Arduino Pro-Mini Boards <a name="Programming_Arduino_Pro_Mini"></a>
Use this method only for Arduino Pro Mini boards with bootloader.
1. Use an external FTDI adapter like one of these options:
<img src="images/FTDI_Cable.jpeg" width="200" height="150"> <img src="images/FTDI_Adapter.jpeg" width="150" height="150">
1. The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages.
1. Under the **Tools -> Board:** select the **Arduino Pro-Mini**
1. Under **Tools -> Processor** select the **Atmega328p (5V, 16Mhz)**
1. Under **Tools -> Port** select your the serial port your programmer is connected to (it should appear on the the list)
1. Scroll back to the section [Customize the firmware to your hardware and your needs](#CustomizeFirmareToYourNeeds) above and follow the instructions remembering that you can simply use the Upload button in the Arduino IDE to upload firmware using the Arduino bootloader:
- From the Arduino environment, you can use Upload button which will compile and upload to the module: Sketch->Upload (Ctrl+U)
To change the fuses you will need to use an external programmer (like USBasp mentioned above) and a flash tool that fits over the MCU and connects to the required pins, like this one:
[<img src="http://www.hobbyking.com/hobbyking/store/catalog/27195.jpg" />](http://www.hobbyking.com/hobbyking/store/__27195__Atmel_Atmega_Socket_Firmware_Flashing_Tool.html)
It connects to the USBASP programmer and connects directly to the pins on the microcontroller and it will allow you to set fuses and to program the Pro-Mini like the 4-in-1 boards above, without using the bootloader.
Follow the instructions in [Advanced Topics - Manually Setting Fuses](Advanced_Manually_Setting_ATmega328_Fuses.md) to set the fuses.
If building the board from scratch was your chosen strategy we suspect that you would already know how to do this. If not, Google is your friend, try something like “how to flash fuses on Arduino pro-mini”.

150
docs/Compiling_STM32.md Normal file
View File

@ -0,0 +1,150 @@
# Compliling and Programming (STM32)
**If you are Compling for the Arduino ATmega328p version of the Multiprotocol Module please go to the dedicated [Compiling and Programming ATmega328](Compiling.md) page.**
Multiprotocol source can be compiled using the Arduino IDE using STM32 Core (Maple) and Arduino ARM-Cortex-M3 libraries.
###Install the Arduino IDE and the Multiprotocol project
1. Download the Arduino IDE. The currently supported Arduino version is 1.6.5. available for [Windows]( https://www.arduino.cc/download_handler.php?f=/arduino-1.6.5-windows.exe) and [Mac OSX](http://arduino.cc/download_handler.php?f=/arduino-1.6.5-macosx.zip)
1. Download the [STM32 Core](https://github.com/rogerclarkmelbourne/Arduino_STM32/archive/master.zip) and copy the Arduino_STM32 folder to:
- OSX: ```Arduino.app/Contents/Java/hardware``` (you can open Arduino.app by Ctl Clicking on Arduino.app and selecting "Show Package Contents")
- Windows: ```C:\Program Files (x86)\Arduino\hardware```
1. Download the zip file with the Multiprotocol module source code from [here](https://github.com/midelic/DIY-Multiprotocol-TX-Module/archive/multi-STM32.zip)
1. Unzip and copy the source code folder ```Multiprotocol``` to a folder of your choosing
1. Click on the ```Multiprotocol.ino file``` in the ```Multiprotocol``` folder and the Arduino environment should appear and the Multiprotocol project will be loaded.
###Prepare the Arduino IDE:
1. In order to compile successfully you need also to modify a maple library file. In ```....\hardware\Arduino_STM32\STM32F1\cores\maple\libmaple\usart_f1.c``` comment out the 2 functions as shown below. This is required to have low-level access to the USART interrupt.
> ```//void __irq_usart2(void) { usart_irq(&usart2_rb, USART2_BASE); } ```
> ```//void __irq_usart3(void) { usart_irq(&usart3_rb, USART3_BASE); } ```
1. Run the IDE, and on the **Tools** menu, select **Board** and then **Boards manager**. Click on the Arduino DUE (32 Bits ARM-Cortex M3) from the list of available boards. You must do this step, it installs the arm-none-eabi-g++ toolchain!
1. Close and reopen the Arduino IDE and load the Multiprotocol project.
1. Click on the **Verify** button to test compile the before you make any changes. If there are errors check the process above and be sure to have the right version of the Arduino IDE.
## Common process for OSX and Windows
###Customize the firmware to your hardware and your needs
On all modules with STM32F103 microcontroller, the program flash memory on the microcontroller is large enough to accommodate all the protocols. You do not have to make choices on which protocols to upload. Also, it is likely that you used the Banggood 4-in-1 RF module and you will therefore have access to all the RF modules. However, you can follow these instructions to select only a subset protocols.
If you plan to use the PPM mode then you should follow the instructions to customize the protocol selection switch to protocol mapping.
Before customizing your firmware it would be good to review the protocol on the [Protocol Details](Protocol_Details.md) page and to identify the protocols you would like to support on your module.
At the same time make a note of RF modules required by your protocols. For example, if you do not wish to use the FlySky or the Husan protocols then you do not need to compile support the the A7105 RF Module into your firmware. Similarly, if you have no need to bind with ASSAN RC receivers then you do not need to compile the ASSAN protocol into your firmware.
If you plan to use the PPM communication interface with your transmitter, then you need to perform protocol selection with the 16 position switch on your module. This will limit the available protocols you can usefully access in PPM mode on your module to 15 (this limitation does not apply to Serial mode). You should make a list of your 15 chosen protocols, sub protocols and options like this:
Switch Position|Protocol|Sub-Protocol|Option|Notes
---------------|--------|------------|------|-----
1.|DSM|DSM2|2|6 channels @ 22ms
2.|DSM|DSMX|6|6 channels @ 11ms
....|...|...|...|...
....|...|...|...|...
15.|FRSKYX|CH_16| |FrSky X receiver 16 chan
With the above information (required RF modules, selected protocols and 16 pos switch mapping) you are ready to customize your firmware.
All customization is done by editing the ```_Config.h ``` file in the Multiprotocol Arduino project.
In the Arduino IDE and click on the down arrow on the far right of the tab bar to show a list of project files (see the red circle on the screenshot below). Scroll down and select the _Config.h file.
<img src="images/Arduino.png" width="600" height="400" />
It is unlikely that you would need to do this, but you can comment out any of the RF modules that you do not need by typing ```// ``` at the begining of the line that reads :
```#define <RF Module name>_INSTALLED ``` . The following line shows the CC2500 module removed
> ```#define A7105_INSTALLED ```
> ```#define CYRF6936_INSTALLED ```
> **```//#define CC2500_INSTALLED ```**
> ```#define NFR24L01_INSTALLED ```
Again it is unlikely that you would want to do this, but you can scroll down to the available protocols and comment out all the protocols you will not require. The following example shows the DEVO protocol commented out.
> **```#ifdef CYRF6936_INSTALLED ```
> **``` // #define DEVO_CYRF6936_INO ```**
> ``` #define DSM_CYRF6936_INO ```
> ``` #define J6PRO_CYRF6936_INO ```
> ``` #endif ```**
Look for the line containing ```#define INVERT_TELEMETRY``` and make sure that it is uncommented:
> ```#define INVERT_TELEMETRY ```
Scroll down to the bottom of the file and list your switch mapping to your desired **protocol/sub-protocol/options**. You typically only need to change the three relevant columns. On models that require a rebind on every start-up (like Syma quads) you can change the **```NO_AUTOBIND ```** to **```AUTOBIND ```**.
Finally, if you have not already done so, specify the correct board for the compiler. Under **Tools** -> **Board:** select the **Generic STM32F103C series** board. You can now compile the firmware by clicking on the check mark (Tooltip: Verify) on the menu bar. If everything goes according to plan you should see something like the following line in the lower pane of the window:
> Sketch uses 32,464 bytes (99%) of program storage space. Maximum is 32,768 bytes.
> Global variables use 1,219 bytes (59%) of dynamic memory, leaving 829 bytes for local variables. Maximum is 2,048 bytes.
If you get an error carefully read the error to see the approximate line number where the error occured and correct it.
###Preparing for STM32 microcontroller for firmware flashing
There are two option for flashing the firmware. The first (and strongly recommended) is flashing it while it is plugged into and powered by the transmitter. The second is flashing it out of the transmitter (the power is supplied by the FTDI cable). The second option is very risky because if the 3.3V bridge jumper is not removed after flashing it will fry your RF module - **you have been warned**.
####Option 1: Flashing with Tx power
1. Put the module in the Tx
1. Place a jumper over the BOOT0 pins
1. Connect your 3.3V/5V FTDI cable (USB - TTL serial) to Multiprotocol serial port (RX,TX,GND,5V).The multimodule RX pin connected to FTDI TX pin and multi TX pin connected to FTDI RX pin.Connect only TX and RX pins(2 pins),the power will be supplied by TX.
1. In arduino IDE under the **Tools** -> **Board:** check that you have selected the **Generic STM32F103C series** board
1. Under **Tools** -> **Upload Method:** select **Serial**
1. Click "Upload" and the sketch will be uploaded normally.This is valid for all arduino versions.
1. Once the firmware has uploaded, remove the BOOT0 jumper.
####Option 2: Flashing without Tx power
The key difference of this method is that the 3.3V FTDI cable must also provide power to the 5V circuitry during the flashing process. To do this, a jumper must be enabled connecting the 3.3V VCC to the 5V line.
**If the module is powered through the transmitter and this jumper is enabled, then it will feed 5V throughout the 3.3V circuit and this will fry your RF modules.**
1. Set BOOT0 jumper
1. Set the 3.3V jumper.This step only for 3.3V USB-serial!!!.Skip this step if using 5V USB-serial.
1. Connect your 3.3V FTDI cable (USB - TTL serial) to Multiprotocol serial port (RX,TX,GND,5V).If set 3.3V jumper ,3.3V supply from USB-serial goes to 5V pin.
1. In arduino IDE under the **Tools** -> **Board:** check that you have selected the **Generic STM32F103C series** board
1. Under **Tools** -> **Upload Method:** select **Serial**.
1. Click "Upload" and the sketch will be uploaded normally.
1. Once the firmware has uploaded:
- Remove the 3.3V jumper!!!!
- Remove the BOOT0 jumper
- Check that you removed the 3.3V jumper
###Flashing binary file:
If you want to flash a pre-compiled binary file (like the Release .bin files) you need specialized software and the FTDI cable.
1. Set BOOT0 jumper
1. Connect your 3.3V FTDI cable (USB - TTL serial) to Multiprotocol serial port (RX,TX,GND,5V)
1. The other steps regarding power supply the same as previous recommandation regarding jumpers.
For uploading binaries(.bin files) there is a specialized software you need to install on your computer.
#### Windows:
Download the ST Flash Loader Demonstrator from here: http://www.st.com/content/st_com/en/products/development-tools/software-development-tools/stm32-software-development-tools/stm32-programmers/flasher-stm32.html
Run the ST Flash Loader program. There are many tutorials on the web on how to use this program.For example
[here](http://www.scienceprog.com/flashing-programs-to-stm32-embedded-bootloader)
#### OSX:
To be checked.
###Report issues for the STM32 board
You can report your problem using the [GitHub issue](https://github.com/midelic/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question.
Please provide the following information:
- Multiprotocol code version
- STM32 version
- TX type
- Using PPM or Serial, if using er9x or ersky9x the version in use
- Different led status (multimodule and model)
- Explanation of the behavior and reproduction steps

Binary file not shown.

After

Width:  |  Height:  |  Size: 87 KiB

View File

@ -0,0 +1,28 @@
#Documentation ToDos
1. Documentation on all the FlySky boards: (MikeB?)
- SKY board erSky9x
- AR9X board erSky9x
- 9Xtreme board erSky9x
- AR9X UNI board
1. Add to the troubleshooting page
1. Add how to do custom protocol setup on er9x and OpenTx
1. Document the OrangeRx Transmitter module (Mikeb?)
1. enabling Serial on the DIY PCB page
1. lots of pictures mentioned between the {} markers
2. Add how to wire the antenna switcher in the "solder your own board and use 4-in-1 Rf module (add pictures of the wires from the ATmega pins to PE1 and PE2)
1. Someone to add the Build the board from scratch if it is still relevant
#Proposal for renaming options to make things simpler
Multiprotocol Transmitter Module or Multiprotocol Module is not only becoming quite a mouthful but we use module on two different levels. (for example the CC2500 module and the DIY Multiprotocol Module). It is nevertheless very descriptive. Without throwing the proverbial "baby out with the bathwater" I suggest that we set expectations that **MPTM** can be interchangeably used for Multiprotocol Module. If we use the term interchangeably we can see if it begins to stick. I do not suggest that we change any of the github or rcgroups pages.
In addition to this it would be very useful if we could bucket the different MPTM options according to how they are built. For example:
- **Ready-made:** Banggood 4-in-1 module : Readymade Mulitprotocol Module or Readymade Multiprotocol Transmitter Module or Readymade MPTM or Banggood MPTM
- **DIY:** Modules made from PCBs : DIY Multiprotocol Module, DIY ATmega Multiprotocol Module, DIY STM32 Multiprotocol Module or DIY STM32 MPTM
- **Scratchbuild:** Modules made from scratch:
- Option 1: Perfboard Multiprotocol Module or Perfboard MPTM
- Option 2: Scratchbuild Multiprotocol Module or Scratchbuild MPTM
1. Move to atmega specific and add ftdi to stm32 AVR ISP programmer like the popular USBASP programming dongle that is 3.3V safe - available from many sellers on ebay. There are reports that some of the cheap programmers are not safe to use with 3.3V units (like this unit). Look for USBAsp programmers with the “LC Technologies” label. {Pascal to confirm these reports are true} Also, you will need a 10-pin to 6-pin connector to connect the USBASP to the board.

19
docs/Hardware.md Normal file
View File

@ -0,0 +1,19 @@
# Hardware Options for your MPTM
The choice of **Multiprotocol Transmitter Module (MPTM)** hardware is the single biggest choice you will make. Due to the growing popularity of this project the number of hardware choices is growing almost monthly.
There are currently four common hardware options. They are:
1. A ready-made MPTM from Banggood.com (see [here](http://www.banggood.com/2_4G-CC2500-A7105-Flysky-Frsky-Devo-DSM2-Multiprotocol-TX-Module-With-Antenna-p-1048377.html)) that integrates the microprocessor with all four supported RF modules and a hardware antenna switcher.
[<img src="images/4-in-1_Module_BG.jpeg" width="200" height="200" />](Module_BG_4-in-1.md)
1. A DIY MPTM made using one of the PCBs that are available and soldering on your own components. The picture below shows an example of one before RF modules have been soldered on.
[<img src="images/Multiprotocol_3.2.jpeg" width="150" height="200" />](Module_Build_yourself_PCB.md)
1. A MPTM based on the OrangeRx DSM transmitter module that natively supports the CYRF6936 RF module. This module can be improved with Mulitprotocol firmware.
[<img src="images/OrangeRx_Module.jpg" width="250" height="200" />](Module_OrangeRx.md)
1. A scratchbuilt MPTM using perfboard, an Arduino Pro-Mini and the desired RF modules.
Unless you are handy with a soldering iron and you have access to electronic test equipment (like an oscilloscope) you should consider only Option 1. For a price of about $44 you can get everything you need, neatly assembled
[<img src="images/Module_perfboard1.jpeg" width="150" height="200" /> <img src="images/Module_perfboard2.jpeg" width="150" height="200" />](Module_Build_From_Scratch.md)
Click on any of the images above to understand more about each option.

22
docs/Models.md Normal file
View File

@ -0,0 +1,22 @@
#Model Setup
This is the page to document model or receiver specific setup instructions.
The complete list of models the protocols they use are documented [here](https://docs.google.com/spreadsheets/d/1nBHzT3VWF6ShAhOqRB5y0Bcc7aXFuRFFlQkHn1RIM84/edit#gid=0)
The Deviation project (on which this project was based) have a useful list of models [here](http://www.deviationtx.com/wiki/supported_models).
#Syma X5C
<img src="http://img2.cheapdrone.co.uk/images/upload/2014/12/X5C%203/SKU115108-7.jpg" Width="200" Height="200" />
##Binding
There are no special binding instructions. The model powers up in Autobind mode and expects the bind sequence from the transmitter within the first 4-5 seconds.
##Tx Setup
{How to setup the transmitter switches for rates, flip, picture and video}
#Inductrix (Horizon Hobby)
<img src="https://s7d5.scene7.com/is/image/horizonhobby/BLH8700_a0" Width="200" Height="200" />
##Binding
{Enter bind instructions here - Which DSM mode works best?}
##Tx Setup
{How to setup the transmitter optimally for leveling and acro mode}

47
docs/Module_BG_4-in-1.md Normal file
View File

@ -0,0 +1,47 @@
#4-in-1 Banggood module
Currently the form factor of this module is designed for the JR-style module bay. Many of the popular RC transmitters use the JR-style module bay: FrSky Taranis, FlySky Th9x, Turnigy 9X/R/Pro {other transmitters that come to mind?}
##What you need
1. The ready-made module is available from Banggood.com [here](http://www.banggood.com/2_4G-CC2500-A7105-Flysky-Frsky-Devo-DSM2-Multiprotocol-TX-Module-With-Antenna-p-1048377.html)
<img src="images/4-in-1_Module_BG.jpeg" width="200" height="200" />
1. A module case that fits your receiver like the one [here](https://www.xtremepowersystems.net/proddetail.php?prod=XPS-J1CASE)
<img src="https://www.xtremepowersystems.net/prodimages/j1case.jpg" width="200" height="180" />
or you can 3D print your own from a selection on Thingiverse (example [here](http://www.thingiverse.com/thing:1661833)).
<img src="http://thingiverse-production-new.s3.amazonaws.com/renders/0a/a8/2e/9b/1f/fa4e1c11282f5ef9cbf555bb84d3bd61_preview_featured.jpg" width="200" height="200" />
1. 3x2 header pins (to solder onto the board for programming)
1. AVR ISP programmer like the popular USBASP programming dongle that is 3.3V safe - available from many sellers on [ebay.](http://www.ebay.com/sch/i.html?_odkw=usbasp+progammer&_osacat=0&_from=R40&_trksid=p2045573.m570.l1313.TR3.TRC2.A0.H0.Xusbasp+progammer+3.3V.TRS1&_nkw=usbasp+progammer+3.3V&_sacat=0) There are reports that some of the cheap programmers are not safe to use with 3.3V units (like this unit). Look for USBAsp programmers with the “LC Technologies” label. {Pascal to confirm these reports are true} Also, you will need a 10-pin to 6-pin connector to connect the USBASP to the board.
##Build instructions
The assembly process is trivial but it does depend on:
- The communication interface between your transmitter and the module, and
- The version of the module you have
###Common steps
1. Solder the 3x2 header pins onto the module as shown below {insert picture of module with pins}. These header pins are required to program the microcontroller.
1. Fit the module into the module case. This may require some careful filing or sanding of the module to ensure a nice fit.
###PPM interface
If you are only planning on using the PPM interface with transmitter you are ready to program the module as described in Compiling and Programming the module.
###Enabling Serial interface
If you have a transmitter that can support serial communication with the board then you need to wire up the board appropriately. There are two versions of the module and the steps are slightly different.
Check which module you have and based on the pictures below. If you purchased the module after June 2016 then it is likely that you have V2 module.
#### **Version 2 (V2) module**
Solder two bridges over the pads shown in the picture below.
<img src="images/4-in-1_Module_BG_SerialJumpers.jpeg" width="300" height="340" />
<img src="images/V2_Serial_Enable.jpeg" width="340" height="340" />
You are now ready to go over to [Compiling and Programming](Compiling.md).
#### **Version 1 (V1) module**
Solder bridges and resistors as illustrated in the picture below.
<img src="images/V1_Serial_Enable.jpeg" width="500" height="340" />
You are now ready to go over to [Compiling and Programming](Compiling.md).

View File

@ -0,0 +1,17 @@
#Build from stratch
If you can help to fully document this page, or just add additional detail please let us know on the rcgroups [forum](http://www.rcgroups.com/forums/showthread.php?t=2165676).
## Bill of materials
If this is the option you are following, then you must have a pretty good idea of what you are doing. Check the BOM for the DIY PCB version of the hardware as a starting point. You can find the link [here](Module_Build_yourself_PCB.md).
The Arduino Pro-Mini is available many places online. Check Sparkfun (the original developers of the Pro-Mini) page [here](https://www.sparkfun.com/products/11113)
You will require a second Arduino or a FTDI (USB to TTL serial) cable to program the Pro-Mini. Like the one [here](https://www.sparkfun.com/products/9717). **Make sure you get only a 3.3V FTDI cable - or you will fry your 3.3V RF modules when you connect it up.**
##Reference Schematic <a name="Schematic"></a>
Here is the schematic you can use to troubleshoot the module
<img src="images/DIY_Mulitprotocol_Module_Schematic.jpeg" width="1000" height="500" />
##Compiling and programming
Follow the instruction on the [Compiling and programming page](Compiling.md)

View File

@ -0,0 +1,91 @@
#DIY MPTM by soldering components on a PCB
Currently the form factor of this module is designed for the JR-style module bay. Many of the popular RC transmitters use the JR-style module bay: FrSky Taranis, FlySky Th9x, Turnigy 9X/R/Pro
##What you need
First you must choose the PCB onto which to solder all the components. There are two PCB options:
- ATmega (8-bit) powered PCB V2.3d supporting individual RF modules
- STM32 (32-bit) powered PCB supporting the 4-in-1 RF module
The **ATmega-based board** has been designed to accept individual RF modules. This way you can select just the module or modules you want. The downside is that each module requires its own antenna. It can become cumbersome with 4 antennas protruding from the module. It is possible to soder the 4-in-1 module to the PCB using thin insulated wire. This 4-in-1 module requires only one antenna. Finally, the Atmega board has a 32k flash memory. This is big enough to accommodate more than 15 protocols, but it cannot accommodate all the available protocols.
<img src="images/MPTM_with_RF_modules.jpeg" width="150" height="120" />
The **STM32-based** board has been designed to accept the 4-in-1 RF module with the antenna switcher (shown below). This means only one antenna. The STM32F103 processesor also has a much larger flash memory.
<img src="images/Board_PCB_STM32.jpeg" width="100" height="125" /> <img src="images/Multi_4-in-1_RF_module.jpg" width="100" height="125" />
###ATmega board V2.3d
1. ATmega (8-bit) powered PCB V2.3d available from OSHPark [here](https://oshpark.com/shared_projects/Ztus1ah8).
2. Individual RF modules The modules are available here:
- [CC2500](http://www.banggood.com/2_4G-500K-CC2500-Long-Range-Wireless-Transceiver-Module-p-1075492.html) for FrSkyV, FrSkyD, FrSkyX and SFHSS
- CYRF6936 {Can someone please give me a source} for DSM, DEVO, J6Pro
- [A7105](http://www.banggood.com/A7105-Wireless-RF-2_4GHz-Transceiver-Module-3_3V-Power-Supply-Module-p-909404.html) for Flysky, Hubsan
- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-16+32mm-Without-Antenna-p-922601.html?utm_source=tradetracker&utm_medium=tradetracker_SE&utm_campaign=tradetracker&utm_content=227736) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols
- The 4-in-1 RF module (available [here](http://www.banggood.com/DIY-2_4G-CC2500-NRF24L01-A7105-CYRF6936-Multi-RF-4-IN-1-Wireless-Module-p-1046308.html)) can also be connected with solder wires. To enable the antenna switcher the PE1 and PE2 pads must be soldered to ATmega pins, check the [schematic](#V23D_Schematic)
1. Electronics component BOM is [here](BOM_DIY_ATmega.md). This BOM is inclusive, you many not need all the parts depending on your needs.
The schematic for the board is [here](#V23D_Schematic). Please note that is is the general schematic - there will be some minor differences (like solder jumpers) between this and the board.
###STM32 powered PCB
1. STM32 (32-bit) powered PCB supporting the 4-in-1 RF module available from OSHPark [here](https://oshpark.com/shared_projects/toBXcpNK).
2. The 4-in-1 RF module is available [here](http://www.banggood.com/DIY-2_4G-CC2500-NRF24L01-A7105-CYRF6936-Multi-RF-4-IN-1-Wireless-Module-p-1046308.html)
1. The BOM for this board is available [here](BOM_DIY_STM32.md). The github project page for the STM32 module is [here](https://github.com/midelic/DIY-Multiprotocol-TX-Module).
The schematic for the board is [here](#STM32_Schematic)
###Common parts
1. A module case that fits your receiver like the one [here](https://www.xtremepowersystems.net/proddetail.php?prod=XPS-J1CASE)
<img src="https://www.xtremepowersystems.net/prodimages/j1case.jpg" width="200" height="180" />
or you can 3D print your own from a selection on Thingiverse (example [here](http://www.thingiverse.com/thing:1661833) or [here](http://www.thingiverse.com/thing:1691786)).
<img src="http://thingiverse-production-new.s3.amazonaws.com/renders/0a/a8/2e/9b/1f/fa4e1c11282f5ef9cbf555bb84d3bd61_preview_featured.jpg" width="200" height="200" />
1. A 2.4GHz antenna and pigtail
1. AVR ISP programmer like the popular USBASP programming dongle that is 3.3V safe - available from many sellers on [ebay.](http://www.ebay.com/sch/i.html?_odkw=usbasp+progammer&_osacat=0&_from=R40&_trksid=p2045573.m570.l1313.TR3.TRC2.A0.H0.Xusbasp+progammer+3.3V.TRS1&_nkw=usbasp+progammer+3.3V&_sacat=0) There are reports that some of the cheap programmers are not safe to use with 3.3V units (like this unit). Look for USBAsp programmers with the “LC Technologies” label. {Pascal to confirm these reports are true} Also, you will need a 10-pin to 6-pin connector to connect the USBASP to the board.
##Build instructions
If you got this far you already know what you are doing!!
###Common steps
1. Solder all the parts according to the BOM part numbering and the images for your board (see OSHPARK for the images)
1. Fit the module into the module case. This may require some careful filing or sanding of the module to ensure a nice fit.
###PPM interface
If you are only planning on using the PPM interface with transmitter you are ready to program the module as described in Compiling and Programming the module.
###Enabling Serial interface
If you have a transmitter that can support serial communication with the board then you need to solder some jumpers.
#### **ATmega V2.3d board**
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).
**It is most likely J-2 will be the only one needing to be shorted for the serial method of sending model protocols.**
You are now ready to go over to [Compiling and Programming](Compiling.md).
#### **STM32 board**
Solder bridges and resistors as illustrated in the picture below. {need to get info from midelic}
<img src="" width="500" height="340" />
You are now ready to go over to [Compiling and Programming STM32](Compiling_STM32.md).
#Reference Schematic <a name="Schematic"></a>
Here is the schematic you can use to troubleshoot the module
## <a name="V23D_Schematic"></a> PCB V2.3d Schematic
<img src="images/DIY_Mulitprotocol_Module_Schematic.jpeg" width="1000" height="500" />
## <a name="STM32_Schematic"></a> PCB STM32 Schematic
<img src="http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a9220887-113-multi-STM32.png" width="1000" height="500" />

3
docs/Module_OrangeRx.md Normal file
View File

@ -0,0 +1,3 @@
#OrangeRx Transmitter module
{need someone to do this if it is important}

57
docs/PPM_Setup.md Normal file
View File

@ -0,0 +1,57 @@
#PPM Setup
The Multiprotocol Module is compatible with any transmitter that is able to generate a PPM (Pulse Postion Modulation) output. This includes all transmitters with a module bay or a trainer port. It supports up to 16 channels from a PPM frame in the normal or inverted format (sometimes called positive or negative format in some transmitters).
If you want the best performance you can set the number of channels and framerate corresponding to the number of channels of the specific receiver/model.
##PPM Connections
If you do not have a module bay, there are only three wires you need to connect to get PPM to work. (The pins are numbered from top to bottom)
- PPM on pin 1
- vbat on pin 3
- ground on pin 4
Note: vbat should be between 6V and 13V when using the 4-in-1 and 2.3 PCB boards. If you built a module from scratch it depends on the voltage regulator you chose.
##Enabling PPM mode in your transmitter
1. Enable the default Tx mode to be AETR. If you do not want to change the default channel order on your Tx you must remember to change the channel order for each new model using the module to AETR under the Model Mixer menu.
1. The default PPM settings is 8 channels with a frame period of 22.5 ms (sometimes called the frame rate). If you want to optimize performance you should change the channels to the actual number of channels required by your model. The corresponding frame period should be set to (number of channels + 1) * 2.5 ms. For example:
- A 4 channel model the frame period is (4 + 1)*2.5 = 12.5 ms.
- A 6 channel model the frame period is (6 + 1)*2.5 = 17.5ms.
## Protocol selection in PPM mode
To select the protocol simply switch off the transmitter and rotate the protocol selection switch on the module to the desired position.
**Note that the dial selection must be done before the module receives power - this is not necessarily the same time that the transmitter is powered up. The transmitter often only provides power to the module once it has passed switch checks and throttle position checks.**
The default mapping of protocols to switch positions can be viewed on the Protocol Details page found [here](Protocol_Details.md#DefaultMapping)
The mapping of protocols to protocol selection switch positions can be changed in configuration settings as described on the [Compiling and Programming page](Compiling.md).
##Binding in PPM mode
In PPM mode follow the standard transmitter - receiver binding process:
1. Switch off the transmitter
1. Switch on the receiving device in bind mode (if it is not already autobind). Check the documentation for your device.
1. Press and hold the bind button on the back of the module as you power up the transmitter. Hold the button down until the transmitter powers up the module. The red LED on the module should be flashing at about 5Hz - indicating bind mode.
1. Watch the receiver for the completion of the bind process
1. This is a model supporting autobind (binds every time it powers up) then you should be ready to go
1. For traditional RC receivers with a bind memory - power down the receiver and the Tx and then power up the Tx and the Rx to confirm bind.
If you are having trouble binding to a consumer quad check the section below on [Getting your Bind Timing right](Bind_Timing.md). For more details on setting up specific receivers or models, check out the [Protocol Details page](Protocol_Details.md).
##Telemetry in PPM mode
Telemetry is available as a serial stream on the TX pin of the Atmega328p in the FrSky HUB format. The serial parameters are based on the protocol selected by the protocol selection dial.
Protocol|Serial Parameters
--------|-----------------
Hubsan|9600bps 8n1
FrSkyD|9600bps 8n1
FrSkyX|57,600bps 8n1
DSM2/X|125,000bps 8n1
The serial stream is also available on pin 5 of the Module connector (pins numbered from top to bottom) on the [4-in-1 module]() and the [V2.3d modules]() provided the Tx jumper has been soldered. See the linked module documentation for what this means.
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.

447
docs/Protocol_Details.md Normal file
View File

@ -0,0 +1,447 @@
#Protocols details
Here are detailed descriptions of every supported protocols (sorted by RF modules) as well as the available options for each protocol.
If you want to see a list of models that use these protocols see the [Models](Models.md) page.
## Default Mapping of Protocols <a name="DefaultMapping"></a>
Here is the default mapping of protocols to the 16-position protocol selection switch on the module. You can customize these when you compile your own firmware as described in [Compiling and Programming.](Compiling.md)
**Note that the protocol must be selected before the unit is turned on.**
Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module
----|--------|------------|------|-----|---------|------|---------
0|Select serial||||||
1|FLYSKY|Flysky|0|High|No|0|A7105
2|HUBSAN|-|0|High|No|0|A7105
3|FRSKYD|-|0|High|No|-41|CC2500
4|HISKY|Hisky|0|High|No|0|NRF24L01
5|V2X2|-|0|High|No|0|NRF24L01
6|DSM|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
10|SYMAX|SYMAX|0|High|No|0|NRF24L01
11|SLT|-|0|High|No|0|NRF24L01
12|CX10|BLUE|0|High|No|0|NRF24L01
13|CG023|CG023|0|High|No|0|NRF24L01
14|BAYANG|-|0|High|No|0|NRF24L01
15|SYMAX|SYMAX5C|0|High|No|0|NRF24L01
## Useful notes and definitions
- **Extended limits supported** - A command range of -125%..+125% will be transmitted. Otherwise the default is -100%..+100% only.
- **Autobind protocol** - The transmitter will automatically initiate a bind sequence on power up. This is for models where the receiver expects to rebind every time it is powered up. In these protocols you do not need to press the bind button at power up to bind, it will be done automatically.
- **Channel Order** - The channel order assumed in all the documentation is AETR and it is highly recommended that you keep it this way. You can change this in the compilation settings. However, please indicate your channel order in all questions and posts on the forum pages.
***
#A7105 RF Module
##FLYSKY
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be AETR.
###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
##FRSKYV = FrSky 1 way
Models: FrSky receivers V8R4, V8R7 and V8FR.
Extended limits supported
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4
---|---|---|---
CH1|CH2|CH3|CH4
##FRSKYD
Models: FrSky receivers D4R and D8R. DIY RX-F801 and RX-F802 receivers.
Extended limits supported
Telemetry enabled for A0, A1, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
##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. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
###Sub_protocol CH_16
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. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
***
#CYRF6936 RF Module
##DEVO
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be EATR.
Bind procedure using serial:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode).
- Turn on RX (RX LED fast blink).
- Turn on TX (RX LED solid, TX LED fast blink).
- Wait for bind on the TX to complete (TX LED solid).
- Make sure to set the RX_Num value for model match.
- Change option to 1 to use the global ID.
- Do not touch option/RX_Num anymore.
Bind procedure using PPM:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on RX (RX LED fast blink).
- Turn the dial to the model number running protocol DEVO on the module.
- Press the bind button and turn on the TX. TX is now in autobind mode.
- Release bind button after 1 second: RX LED solid, TX LED fast blink.
- Wait for bind on the TX to complete (TX LED solid).
- Press the bind button for 1 second. TX/RX is now in fixed ID mode.
- To verify that the TX is in fixed mode: power cycle the TX, the module LED should be solid ON (no blink).
- Note: Autobind/fixed ID mode is linked to the dial number. Which means that you can have multiple dial numbers set to the same protocol DEVO with different RX_Num and have different bind modes at the same time. It enables PPM users to get model match under DEVO.
##DSM
###Sub_protocol 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
Note that the RX ouput will be TAER.
###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
##ASSAN
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
The transmitter must be close to the receiver while binding.
##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 then press a direction to enter headless mode (like stock TX), OPT2=switch 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
Model: FQ777-124
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 (DR): +100%=full range, Throttle Hold (THOLD): +100%=hold, Idle Up (IDLEUP): +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
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol X800
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol H26D
###Sub_protocol E010
Only 1 TX ID available
##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|RATES|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.

399
docs/README-old.md Normal file
View File

@ -0,0 +1,399 @@
# Legacy Documentation
Multiprotocol is a 2.4GHz transmitter which enables any TX to control lot of different models available on the market.
The source code is partly based on the Deviation TX project, thanks to all the developpers for their great job on protocols.
[Forum link on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) for additional information or requesting a new protocol integration.
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159)
**To download the latest compiled version (hex file), click on [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases) on the top menu.**
##Contents
[Compatible TX](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compatible-tx)
[Protocols](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#protocols)
[Hardware](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#hardware)
[Compilation and programmation](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compilation-and-programmation)
[Troubleshooting](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#troubleshooting)
##Compatible TX
###Using standard PPM output (trainer port)
The multiprotocol TX module can be used on any TX with a trainer port.
Channels order is AETR by default but can be changed in the _Config.h.
The protocol selection is done via a dip switch, rotary dip switch or scsi ID selector.
![Screenshot](http://media.digikey.com/photos/CTS%20Photos/206-4,%20206-4ST_sml.jpg)
![Screenshot](http://media.digikey.com/photos/Grayhill%20Photos/94HBB16T_sml.jpg)
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8637216-7-thumb-SCSI%20ID%20selector.jpg?d=1453737244)
You can access to up to 15 different protocols and associated settings.
Settings per selection are located in _Config.h:
- Protocol and type: many main protocols have variants
- RX Num: number your different RXs and make sure only one model will react to the commands
- Power: High or low, enables to lower the power setting of your TX (indoor for example).
- Option: -127..+127 allowing to set specific protocol options. Like for Hubsan to set the video frequency.
- 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](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.
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8520065-194-thumb-IMG_20151217_002215%20%28Medium%29.jpg?d=1450308588)
Options are:
- Protocol and type: many main protocols have variants
- RX Num: number your different RXs and make sure only one model will react to the commands
- Power: High or low, enables to lower the power setting of your TX (indoor for example).
- Option: -127..+127 allowing to set specific protocol options. Like for Hubsan to set the video frequency.
- Bind: bind a RX/model
- Autobind: Yes or No. At the model selection (or power applied to the TX) a bind sequence will be initiated
- Range: test range by setting the transmission power to the lowest value
Notes:
- Using this solution does not need any modification of the TX since it uses the TX module slot PPM pin for serial transfer.
- There are 2 versions of serial protocol either 8 or 16 channels. 16 channels is the latest and only available version going forward. Make sure to use the right version based on your version of er9x/ersky9x.
- Channels order is AETR by default but can be changed in _Config.h.
###Telemetry
There are 4 protocols supporting telemetry: Hubsan, DSM, FrSkyD and FrSkyX.
Hubsan displays the battery voltage and TX RSSI.
DSM displays TX RSSI and full telemetry.
FrSkyD displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub).
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 for Hubsan, FrSkyD, FrSkyX and DSM format for DSM2/X.
You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter (HC05/HC06) along with an app on your phone/tablet ([app example](https://play.google.com/store/apps/details?id=biz.onomato.frskydash&hl=fr)) to display telemetry information and setup alerts.
### If used in Serial mode
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).
##Protocols
###TX ID
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
To bind a model in PPM Mode press the physical bind button, apply power and then release.
In Serial Mode you have 2 options:
- use the GUI, access the model protocol page and long press on Bind. This operation can be done at anytime.
- press the physical bind button, apply power and then release. It will request a bind of the first loaded model protocol.
Notes:
- the physical bind button is only effective at power up. Pressing the button later has no effects.
- a bind in progress is indicated by the LED fast blinking. Make sure to bind during this period.
###Protocol selection
####Using the dial for PPM input
PPM is only allowing access to a subset of existing protocols.
The protocols, subprotocols and all other settings can be personalized by modifying the **_Config.h** file.
The default association dial position / protocol in every release is listed below.
Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module
----|--------|------------|------|-----|---------|------|---------
0|Select serial||||||
1|FLYSKY|Flysky|0|High|No|0|A7105
2|HUBSAN|-|0|High|No|0|A7105
3|FRSKYD|-|0|High|No|-41|CC2500
4|HISKY|Hisky|0|High|No|0|NRF24L01
5|V2X2|-|0|High|No|0|NRF24L01
6|DSM|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
10|SYMAX|SYMAX|0|High|No|0|NRF24L01
11|SLT|-|0|High|No|0|NRF24L01
12|CX10|BLUE|0|High|No|0|NRF24L01
13|CG023|CG023|0|High|No|0|NRF24L01
14|BAYANG|-|0|High|No|0|NRF24L01
15|SYMAX|SYMAX5C|0|High|No|0|NRF24L01
Note:
- The dial selection must be done before the power is applied.
####Using serial input with er9x/ersky9x
Serial is allowing access to all existing protocols & sub_protocols listed below.
#####A7105 RF module
Protocol|Sub_protocol
--------|------------
Flysky|
|Flysky
|V9x9
|V6x6
|V912
Hubsan|
#####CC2500 RF module
Protocol|Sub_protocol
--------|------------
FrSkyV|
FrSkyD|
FrSkyX|
|CH_16
|CH_8
SFHSS|
#####CYRF6936 RF module
Protocol|Sub_protocol
--------|------------
DSM|
|DSM2
|DSMX
Devo|
J6Pro|
#####NRF24L01 RF module
Protocol|Sub_protocol
--------|------------
Hisky|
|Hisky
|HK310
V2x2|
YD717|
|YD717
|SKYWLKR
|SYMAX4
|XINXUN
|NIHUI
KN|
|WLTOYS
|FEILUN
SymaX|
|SYMAX
|SYMAX5C
SLT|
CX10|
|GREEN
|BLUE
|DM007
|Q282
|JC3015_1
|JC3015_2
|MK33041
|Q242
CG023|
|CG023
|YD829
|H8_3D
Bayang|
ESky|
MT99XX|
|MT
|H7
|YZ
|LS
MJXQ|
|WLH08
|X600
|X800
|H26D
|E010
Shenqi|
FY326|
FQ777|
ASSAN|
HONTAI|
|HONTAI
|JJRCX1
|X5C1
Note:
- The dial should be set to 0 for serial. Which means all protocol selection pins should be left unconnected.
###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 FrSkyV, FrSkyD, FrSkyX and SFHSS
- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM, DEVO, J6Pro
- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols
RF modules can be installed for protocols need only. Example: if you only need the Hubsan protocol then install only a A7105 on your board.
You also need some [antennas](http://www.banggood.com/2_4GHz-3dBi-RP-SMA-Connector-Booster-Wireless-Antenna-Modem-Router-p-979407.html) and [cables](http://www.banggood.com/10cm-PCI-UFL-IPX-to-RPSMA-Female-Jack-Pigtail-Cable-p-924933.html).
###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 Mini based on Atmega328p can also be used.
####Using stripboard:
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214655-87-thumb-uploadfromtaptalk1405598143749.jpg?d=1441459923)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214656-102-thumb-uploadfromtaptalk1405598152484.jpg?d=1441459924)
####Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621):
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226720-197-thumb-IMG_20150715_230603155.jpg?d=1441816457)
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226719-72-thumb-IMG_20150715_230024065.jpg?d=1441816456)
####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):
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7566755-3-thumb-i.png?d=1423810885)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952726-108-thumb-image-62c29cf2.jpg?d=1433909893)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159)
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.
![Screenshot](https://644db4de3505c40a0444-327723bce298e3ff5813fb42baeefbaa.ssl.cf1.rackcdn.com/b637193364a5e228dc8ab6ad90c0ca3c.png)
![Screenshot](https://644db4de3505c40a0444-327723bce298e3ff5813fb42baeefbaa.ssl.cf1.rackcdn.com/97b87a89b75785d70b354e5b033f5209.png)
[OSH Park link](https://oshpark.com/shared_projects/Ztus1ah8) if you want to order.
####Buy a ready to use and complete Multi module
![Screenshot](http://img.banggood.com/thumb/view/oaupload/banggood/images/1D/EB/19bb6434-4616-411e-b8fa-a4c21d9dca24.jpg)
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: ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8895038-170-4in1%20module.jpg)
- 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
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8443844-119-multiprotocol_diagram_rotary_serial_2.jpg)
Notes:
- Attention: All modules are 3.3V only, never power them with 5V.
- For serial, the dial switch is not needed and the bind button optionnal
###Radio integration
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)):
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462144-54-thumb-Multi_case_9XR.jpg?d=1448575289)
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462145-106-thumb-Multi_case_v1.jpg?d=1448575293)
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
Multiprotocol source can be compiled using the Arduino IDE.
The currently supported Arduino version is [1.6.10](https://www.arduino.cc/download_handler.php?f=/arduino-1.6.10-windows.exe).
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.
The dial must be set to 0 before flashing!
From the Arduino environment, you can use this shortcut to compile and upload to the module: Skecth->Upload Using Programmer (Ctrl+Maj+U)
To flash the latest provided hex file under [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases), you can use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/), set the microcontroller to m328p and flash it.
###Upload the code using FTDI (USB serial to TTL)
Use this method only for Arduino Pro Mini boards with bootloader.
Use an external FTDI adapter like [this one](http://www.banggood.com/FT232RL-FTDI-USB-To-TTL-Serial-Converter-Adapter-Module-For-Arduino-p-917226.html).
The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages.
From the Arduino environment, you can use Upload button which will compile and upload to the module: Skecth->Upload (Ctrl+U)
To upload the latest provided hex file under [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases), you can use a tool like [XLoader](http://russemotto.com/xloader/), set the microcontroller to Atmega328 and upload it.
###Set fuses
Use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/) to set the fuses of the Atmega328 to:
- Extended Fuse 0x05 (or 0xFD which is the same)
- High Fuse 0xD2
- Low Fuse 0xFF
This will make sure your ATMEGA328 is well configured and the global TX ID is not erased at each updates.
##Troubleshooting
###LED status
- off: program not running or a protocol selected with the associated module not installed.
- 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
####Input Mode - PPM
- The protocol/mode selection must be done before the power is applied.
- 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 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
Make sure to follow this procedure: press the bind button, apply power and then release it after 1sec. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328.
For serial, the preffered method is to bind via the GUI protocol page.
If your module is always/sometime binding at power up without pressing the button:
- Arduino Pro Mini with an external status LED: to work around this issue connect a 10K resistor between D13 and 3.3V.
- 4in1 module V1 (check 4in1 pictures): to solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
###Report issues
You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question.
Please provide the following information:
- Multiprotocol code version
- TX type
- Using PPM or Serial, if using er9x or ersky9x the version in use
- Different led status (multimodule and model)
- Explanation of the behavior and reproduction steps

76
docs/Transmitters.md Normal file
View File

@ -0,0 +1,76 @@
# Compatible Transmitters
Any Tx that provides a PPM output (like a trainer port, or a RF module bay) is compatible with the DIY Multiprotocol module. In practice, most of the documentation on this site is focused on building modules that slip into your transmitters module bay.
{insert picures of different modules}
There are two different options for the interface between the Mulitprotocol Module and the transmitter: PPM and Serial. The considerations are different for each.
- **PPM** is more generic, easy to implement and will work with most transmitters.
- **Serial** requires custom firmware on the transmitter but brings added functionality including telemetry and protocol selection through the Tx interface
##PPM
The DIY Mulitprotocol module supports industry standard PPM interface that works with all transmitters with either a module bay, and/or a trainer port. Even the older 72MHz FM radios support this standard.
When using the standard PPM Tx output, the protocol selection is achieved through a 16 position rotary switch on the module. This enables 15 protocol/sub-protocol/options combinations to be selected. Binding is achieved by pressing a bind button on the back of the module (see picture below)
<img src="images/4-in-1_Module_PPM_Controls.jpg" width="150" height="180" />
Since the module supports literally hundreds of protocol/sub-protocol/options combinations, you must select which of these will map to the 15 positions on the switch. Refer to the [Compiling and Programming](Compiling.md) page for information on how to do his.
Telemetry is available as a serial output on the TX pin of the Atmega328p using the FrSky hub format for Hubsan, FrSkyD, FrSkyX and DSM format for DSM2/X. The serial paramets depends on the protocol:
Protocol|Serial Parameters
--------|-----------------
Hubsan|9600bps 8n1
FrSkyD|9600bps 8n1
FrSkyX|57,600bps 8n1
DSM2/X|125,000bps 8n1
You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter to send it to a tablet/phone. See [Advanced Topics - Bluetooth Telemetry](Advanced_Bluetooth_Telemetry.md)
For transmitter setup using the PPM protocol go to the [PPM Setup page](PPM_Setup.md)
##Serial
Transmitters that run er9X, erSky9X or OpenTx firmwares - like the FrSky Taranis and FlySky TH9X/Turnigy 9X/R family of transmitters - have the option of using a fast, two-way serial, communication protocol between the Tx and the DIY Multiprotocol module. Using this serial communication protocol has some significant advantages:
1. selecting the specific radio protocol (e.g. DSM) and the sub protocol (e.g. DSMX) directly in the menu system of the Tx (see the picture below)
1. binding through the menu on the Tx
1. range checking through the menu on the Tx
1. enabling two-way telemetry for telemetry capable receivers and protocols.
<img src="images/OpenTx_Multi_Menu.jpg" width="470" height="180" /> <img src="images/er9X_Multi_Menu.jpg" width="250" height="180" />
This serial protocol does not require any hardware modifications, but **will** require updating the firmware on your radio.
To enable serial telemetry **may** require modifications to your Tx. See the table below.
Transmitters and firmware combinations that support the Serial protocol are:
Transmitter|Firmware Options|Telemetry Enabled
:----------|:---------------|:----------------
[FrSky Taranis/Plus/9XE](Tx-Taranis.md)| [erSky9x](http://www.er9x.com), [OpenTx 2.1.8 Multi](http://plaisthos.de/opentx/)|Yes - native
[Turnigy 9X/9xR](Tx-FlyskyTH9X.md)|[er9x](http://www.er9x.com)|[Mod required](http://blog.oscarliang.net/turnigy-9x-advance-mod/), No DSM telem
[Turnigy 9XR-Pro](Tx-Taranis.md)|[erSky9x](http://www.er9x.com)|Yes - native
[FrSky TH9x](Tx-FlyskyTH9X.md)|[er9x](http://www.er9x.com) |[Mod required](http://blog.oscarliang.net/turnigy-9x-advance-mod/), No DSM telem
SKY board|[erSky9x](http://www.er9x.com)|Yes - native
AR9X board|[erSky9x](http://www.er9x.com)|Yes - native
9Xtreme board|[erSky9x](http://www.er9x.com)|Yes - native
AR9X UNI board|[erSky9x](http://www.er9x.com)|Yes - native
Click on your transmitter above to view specific setup instructions.
Other Notes:
- er9X and erSky9X firmware already supports Multiprotocol Module as a standard feature. At time of writing it looks like that the next major release of OpenTx - OpenTx 2.2 - will have DIY Mulitprotocol support as a standard feature.
- Owners of Walkera Devo transmitters should look at the [Deviation-Tx](http://www.deviationtx.com) project for how to achieve the same end goal with your transmitters.
- 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/).
- 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).

40
docs/Troubleshooting.md Normal file
View File

@ -0,0 +1,40 @@
# Troubleshooting
##LED status
###Green LED
- Off: no power to the module
- On: module is powered up
###Red LED (bind LED)
- Off: program not running or a protocol selected with the associated module not installed
- Flash(on=0.1s,off=1s): invalid protocol selected (excluded from compilation or invalid protocol number)
- Fast blink(on=0.1s,off=0.1s): bind in progress
- Slow blink(on=0.5s,off=0.5s): serial has been selected but no valid signal has been seen on the RX pin.
- On: Module is in normal operation mode (transmitting control signals).
##Protocol selection
###Input Mode - PPM
- The protocol/mode selection must be done before the power is applied
- Check the Green LED to see when power is applied. Often power is not applied to the module until the transmitter has performed safety checks (like switch and throttle position settings)
- Check that at least one of the protocal selection to GND.
###Input Mode - Serial
- 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 [hardware page for your board] (Hardware.md).
- Protocol selection dial must be in the 0 position or leave all 4 selection pins unconnected.
##Bind
Make sure to follow this procedure: press the bind button, apply power and then release after the red LED starts flashing. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328.
For serial, the preffered method is to bind via the GUI protocol page.
If your module is always/sometime binding at power up without pressing the button:
- Arduino Pro Mini with an external status LED: to work around this issue connect a 10K resistor between D13 and 3.3V.
- 4in1 module V1 (check 4in1 pictures): to solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
##Report issues
You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question.
Please provide the following information:
- Multiprotocol code version
- TX type
- Using PPM or Serial, if using er9x or ersky9x the version in use
- Different led status (multimodule and model)
- Explanation of the behavior and reproduction steps

38
docs/Tx-FlyskyTH9X.md Normal file
View File

@ -0,0 +1,38 @@
#Flysky TH9X family of transmitters
This page is relevant to the following transmitters:
* FlySky TH9X
* Turnigy 9X, Turnigy 9XR
* EURGLE
## Features
The Multiprotocol module can be used in the Flysky family of transmitters in either PPM mode or in Serial mode. To operate in Serial mode, a version of er9X supporting the Multiprotocol Module must be installed on the Tx.
## PPM Mode
Please refer to the [PPM Setup](PPM_Setup.md) page.
## Serial Mode
Serial mode is only supported by the er9X firmware. Loading this firmware is beyond the scope of this document but it is well covered in tutorial and video tutorials online. {mikeb - any favourite tutorials or video tuts that I an add here}
###Enabling Serial Mode
1. Confirm that the Multiprotocol Module has the required physical connections between the pins on the back of the Tx and the ATMega328 microprocessor. This may require some soldering and depends on which version of the DIY Multiprotocol module you have. Check out your modules hardware page under the section [Enabling your module for Serial{gvzb19 to insert}](### insert link) for details.
1. Plug in your DIY Multiprotocol module into the transmitter module bay. If you have a rotary protocol selection switch, turn the switch to position 0 to put the unit into Serial mode.
1. Ensure throttle is down and all switches are in the start position and power up the Tx. The red LED on the DIY Multiprotocol module should be flashing with a period of about 1 second indicating that it has not established a valid serial link with the Tx. This is expected as we have not set up the Tx yet.
1. Create a new model
1. In the Model Settings menu scroll down to change the RF settings to MULTI {mikeb - can you write this line }
1. The red LED on the Multiprotocol module should briefly flash and then go off. This confirms that the DIY Multiprotocol module has established serial communication with the Tx. If the red LED on the module continues to flash at a period of about 1 seconds then it signals that serial communication has not been established. Check your settings under the model menu as described above and check that the protocol selection switch on the module is at 0 (enable Serial mode). If there is still no communication, power down and power up the Tx. Finally check that you have correctly enabled your module for serial as described on the hardware page for your module under the heading [Enabling your module for Serial{gvzb19 to insert}](### insert link)
###Protocol Selection in Serial mode
To select the protocol:
1. In the Model Setting menu, scroll through the available options under the MULTI option {mikeb to confirm}.
1. Depending on which protocol you have selected you may be required to select a sup-protocol and options. For example, the FrSky protocol has three sub-protocols FrSky_V, FrSky_D and FrSky_X. In some cases the sub-protocols have options that could specify the number of channels, packet frame rate or fine frequency tuning. Check out the [Protocol Details](Protocol_Details.md) page for detailed information and suggestions regarding the sub-protocols and options. The picture below shows the settings in the erSky Model Setup menu for FrSkyX subprotocol with {mike to insert} options:
{mikeb to send simple picture}
###Binding in Serial mode
1. Switch on the model or put the receiver into bind mode
1. On the transmitter go to the Model Settings menu and scroll down to the [Bind] menu option and press Enter.
1. Press Enter again to exit Bind mode
For many consumer models consider checking the Autobind option. This will initiate the bind sequence as soon as the module is powered up by the transmitter.
If you are struggling to get a bind please see the [Getting the bind timing right page](Bind_Timing.md)

43
docs/Tx-NewTrasmitter.md Normal file
View File

@ -0,0 +1,43 @@
# Transmitter Setup
Describe the transmitters this applies to.
Describe the firmware required for the transmitters. The transmitters covered here are:
1. [tx1](###)
1. [tx2](###)
Does it work in PPM and/or Serial mode?
## PPM Mode
Please refer to the [PPM Setup](PPM_Setup.md) page.
##Serial mode
###Enabling Serial Mode
To operate in serial mode, you need one of these firmwares:
1. OpenTx supporting the DIY Multiprotocol mdule (2.18 Multi or 2.2)
1. erSky9x
Check and upload a supported firmware. The latest available version at time of writing are:
- OpenTx 2.1.8 Multi and the hex files are available [here](http://plaisthos.de/opentx/)
- erSky9x Revision 218 and the hex files are available [here](http://www.er9x.com).
Tutorials for uploading new firmware using the SD Card are available [here](http://www.dronetrest.com/t/how-to-upgrade-firmware-for-frsky-taranis-x9d/959) or the CompanionTx software (recommended) are available [here](http://open-txu.org/home/undergraduate-courses/fund-of-opentx/part-2-flashing-opentx/).
**Note: in the tutorials substitute the shown firmwares with the fimware donwloaded from the links above.**
First confirm that the DIY Multiprotocol module has the required physical connections between the pins on the back of the Tx and the ATMega328 microprocessor. This may require some soldering and depends on which version of the DIY Multiprotocol module you have. Check out this [Enabling Your Module for Serial] page for details.
Plug in your DIY Multiprotocol module into the Taranis module bay. If you have a rotary protocol selection switch, turn the switch to position 0 to put the unit into Serial mode. Ensure throttle is down and all switches are in the start position and power up the Taranis. The red LED on the DIY Multiprotocol module should be flashing with a period of about 1s indicating that it has not established a valid serial link with the Tx. This is expected as we have not set up the Tx yet.
Create a new model (make sure channel order is AETR) and on the first Model Settings page scroll down to disable the internal RF and enable the external RF by selecting MULTI as the external RF. Your Taranis settings should look like this: {insert picture of Taranis screen showing external RF settings}
The Red LED on the DIY Multiprotocol module should briefly flash and then go off. This confirms that the DIY Multiprotocol module has established serial communication with the Tx. If the red LED on the module continues to flash at a period of about 1s then it signals that serial communication has not been established. Check your settings under the model menu as described above and check that the protocol selection switch on the module is at 0 (zero). If there is still no communication, power down and power up the Tx. Finally check that you have correctly enabled your module for serial as described here [Enabling Your Module for Serial]
###Protocol Selection in Serial mode
To select the protocol, scroll through the available options under the Model Settings menu. Depending on which protocol you have selected you may be required to select a sup-protocol and options. For example, the DSM protocol has two sub-protocols DSM2 and DSMX. Each of these sub-protocols have options that specify the number of channels and the packet frame rate.
The following picture shows DSM DSMX Option 6 (6 channels and 11ms frame rate). Check out the [Available Protocols] page for detailed information and suggestions regarding the sub-protocols and options.
###Binding in Serial mode
1. Switch on the model or put the receiver into bind mode
1. On the transmitter go to the Model Settings menu and scroll down to the [Bind] menu option.

49
docs/Tx-Taranis.md Normal file
View File

@ -0,0 +1,49 @@
# FrSky Taranis Setup
This page contains setup instructions for the FrSky Taranis family of transmitters. These include the Trananis X9D, Taranis X9D Plus and Taranis X9E. It may also be relevant to the following transmitters: Turnigy 9XR Pro, Sky board-based, AR9X board-based, 9Xtreme board-based and AR9X Uni board-based.
<img src="http://www.frsky-rc.com/product/images/pic/1456723548.jpg" width="300" height="200" />
<img src="http://www.frsky-rc.com/product/images/pic/1456723588.jpg" width="300" height="200" />
The instructions below are relevant to the following firmwares:
1. Taranis with erSky9X available [here](http://www.er9x.com)
1. Taranis with OpenTx available [here](http://plaisthos.de/opentx/)
The DIY Multiprotocol module can be used with all transmitters and firmwares in PPM mode. Taranis transmitters running erSky9X or OpenTX (Version 2.1.8 Multi or Version 2.2) fully support Serial mode.
## PPM Mode
Please refer to the [PPM Setup](PPM_Setup.md) page.
##Serial mode
###Enabling Serial Mode
To operate in serial mode, you need one of these firmwares:
1. erSky9x
1. OpenTx supporting the DIY Multiprotocol Module (Version 2.18 Multi or Version 2.2)
Check and upload a supported firmware. The latest available version at time of writing are:
- erSky9x Revision 218 and the hex files are available [here](http://www.er9x.com).
- OpenTx 2.1.8 Multi and the hex files are available [here](http://plaisthos.de/opentx/)
Tutorials for uploading new firmware using the SD Card are available [here](http://www.dronetrest.com/t/how-to-upgrade-firmware-for-frsky-taranis-x9d/959) or the CompanionTx or eepe software (recommended) are available [here](http://open-txu.org/home/undergraduate-courses/fund-of-opentx/part-2-flashing-opentx/).
**Note: In these tutorials, substitute the firmwares from the links to the supported firmwares above.**
First, confirm that the DIY Multiprotocol module has the required physical connections between the pins on the back of the Tx and the ATMega328 microprocessor. This may require some soldering and depends on which version of the DIY Multiprotocol module you have. Check out the specific pages for your module hardware (under the section "Enabling Serial") linked [here](Hardware.md) for details.
1. Plug in your DIY Multiprotocol module into the Taranis module bay.
2. If you have a rotary protocol selection switch, turn the switch to position 0 to put the unit into Serial mode.
2. Ensure throttle is down and all switches are in the start position and power up the Taranis. The red LED on the DIY Multiprotocol module should be flashing with a period of about 1s indicating that it has not established a valid serial link with the Tx. This is expected as we have not set up the Tx yet.
3. Create a new model (make sure channel order is AETR) and on the first Model Settings page scroll down to disable the internal RF and enable the external RF by selecting MULTI as the external RF. Your Taranis settings should look like this: {insert picture of Taranis screen showing external RF settings} The Red LED on the DIY Multiprotocol module should briefly flash and then go off. This confirms that the DIY Multiprotocol module has established serial communication with the Tx.
4. If the red LED on the module continues to flash at a period of about 1s then it signals that serial communication has not been established. Check your settings under the model menu as described above and check that the protocol selection switch on the module is at 0 (zero). If there is still no communication, power down and power up the Tx. Finally check that you have correctly enabled your module for serial as described in specific pages for your module hardware (under the section "Enabling Serial") linked [here](Hardware.md)
###Protocol Selection in Serial mode
To select the protocol, scroll through the available options under the Model Settings menu. Depending on which protocol you have selected you may be required to select a sup-protocol and options. For example, the DSM protocol has two sub-protocols DSM2 and DSMX. Each of these sub-protocols have options that specify the number of channels and the packet frame rate.
The following picture shows DSM DSMX Option 6 (6 channels and 11ms frame rate). Check out the [Protocol Details](Protocol_Details.md) page for detailed information and suggestions regarding the sub-protocols and options.
###Binding in Serial mode
1. Switch on the model or put the receiver into bind mode
1. On the transmitter go to the Model Settings menu and scroll down to the [Bind] menu option and press Enter.
1. Press Enter again to exit Bind mode
For many consumer models consider checking the Autobind option. This will initiate the bind sequence as soon as the module is powered up by the transmitter.
If you are struggling to get a bind please see the [Getting the bind timing right page](Bind_Timing.md)

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 520 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 321 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

BIN
docs/images/Arduino.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 318 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 238 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 87 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

BIN
docs/images/FTDI_Cable.jpeg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 8.4 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 134 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 104 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 8.0 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 86 KiB

Some files were not shown because too many files have changed in this diff Show More