Correct pins...

This commit is contained in:
pascallanger 2016-09-19 23:43:14 +02:00
parent 174e6ad637
commit fcd47ecec6
6 changed files with 414 additions and 430 deletions

View File

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

View File

@ -428,6 +428,7 @@ uint16_t ReadDsm()
CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84\xC9\x2C\x06\x93\x86\xB9\x9E", 16); CYRF_ConfigDataCode((const uint8_t *)"\x98\x88\x1B\xE4\x30\x79\x03\x84\xC9\x2C\x06\x93\x86\xB9\x9E", 16);
CYRF_SetTxRxMode(RX_EN); //Receive mode CYRF_SetTxRxMode(RX_EN); //Receive mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); //Prepare to receive CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); //Prepare to receive
bind_counter=300;
phase++; // change from BIND_CHECK to BIND_READ phase++; // change from BIND_CHECK to BIND_READ
return 2000; return 2000;
case DSM_BIND_READ: case DSM_BIND_READ:
@ -458,7 +459,12 @@ uint16_t ReadDsm()
while ((uint16_t)micros()-start < 100) // Wait max 100 µs while ((uint16_t)micros()-start < 100) // Wait max 100 µs
if((CYRF_ReadRegister(CYRF_0F_XACT_CFG) & 0x20) == 0) if((CYRF_ReadRegister(CYRF_0F_XACT_CFG) & 0x20) == 0)
break; break;
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x0C); // Read if( --bind_counter == 0 )
{
phase++; // Exit if no answer has been received for some time
return 7000 ;
}
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x0C); // Read mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); // Prepare to receive
return 7000; return 7000;
case DSM_CHANSEL: case DSM_CHANSEL:

View File

@ -181,194 +181,188 @@ struct PPM_Parameters
//*** Pinouts *** //*** Pinouts ***
//******************* //*******************
#define TELEMETRY_SERIAL_TX_pin 2 // TX
#define TELEMETRY_SERIAL_TX_port PORTD #define SERIAL_TX_pin 1 // PD1
#define TELEMETRY_SERIAL_TX_ddr DDRD #define SERIAL_TX_port PORTD
#define DEBUG_TX_pin 1 #define SERIAL_TX_ddr DDRD
#define DEBUG_TX_port PORTD #define SERIAL_TX_output SERIAL_TX_ddr |= _BV(SERIAL_TX_pin)
#define DEBUG_TX_ddr DDRD #define SERIAL_TX_on SERIAL_TX_port |= _BV(SERIAL_TX_pin)
#define MODE_DIAL1_PIN 2 #define SERIAL_TX_off SERIAL_TX_port &= ~_BV(SERIAL_TX_pin)
#define MODE_DIAL1_PORT PORTB #ifdef DEBUG_TX
#define MODE_DIAL2_PIN 3 #define DEBUG_TX_on SERIAL_TX_ON
#define MODE_DIAL2_PORT PORTB #define DEBUG_TX_off SERIAL_TX_OFF
#define MODE_DIAL3_PIN 4 #define DEBUG_TX_toggle SERIAL_TX_port ^= _BV(SERIAL_TX_pin)
#define MODE_DIAL3_PORT PORTB #else
#define MODE_DIAL4_PIN 0 #define DEBUG_TX_on
#define MODE_DIAL4_PORT PORTC #define DEBUG_TX_off
#define LED_pin 5 //D13 = PB5 #define DEBUG_TX_toggle
#define LED_port PORTB #endif
#define LED_ddr DDRB
#define BIND_pin 5 //D13 = PB5 // Dial
#define BIND_port PORTB #define MODE_DIAL1_pin 2
#define BIND_ipr PINB #define MODE_DIAL1_port PORTB
#define BIND_ddr DDRB #define MODE_DIAL2_pin 3
#define MODE_DIAL2_port PORTB
#define MODE_DIAL3_pin 4
#define MODE_DIAL3_port PORTB
#define MODE_DIAL4_pin 0
#define MODE_DIAL4_port PORTC
// PPM
#define PPM_pin 3 //D3 = PD3 #define PPM_pin 3 //D3 = PD3
#define PPM_port PORTD #define PPM_port PORTD
#ifdef XMEGA
#define SDI_pin 6 //SDIO-D6 // SDIO
#define SDI_port PORTD
#define SDI_ipr PIND
#define SDI_ddr DDRD
#else
#define SDI_pin 5 //D5 = PD5 #define SDI_pin 5 //D5 = PD5
#define SDI_port PORTD #define SDI_port PORTD
#define SDI_ipr PIND #define SDI_ipr PIND
#define SDI_ddr DDRD #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)) != 0x00
#define SDI_0 (SDI_ipr & _BV(SDI_pin)) == 0x00
#endif #endif
#define SCLK_pin 4 //D4 = PD4 #define SDI_input SDI_ddr &= ~_BV(SDI_pin)
#define SCLK_port PORTD #define SDI_output SDI_ddr |= _BV(SDI_pin)
#define SCLK_ddr DDRD
#define A7105_CS_pin 2 //D2 = PD2 //SDO
#define A7105_CS_port PORTD
#define A7105_CS_ddr DDRD
#define SDO_pin 6 //D6 = PD6 #define SDO_pin 6 //D6 = PD6
#define SDO_port PORTD #define SDO_port PORTD
#define SDO_ipr PIND #define SDO_ipr PIND
#ifdef XMEGA
#define SDO_1 (SDO_port.IN & _BV(SDO_pin)) != 0x00
#define SDO_0 (SDO_port.IN & _BV(SDO_pin)) == 0x00
#else
#define SDO_1 (SDO_ipr & _BV(SDO_pin)) != 0x00
#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 //D7
#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_pin 7 //D7 = PD7
#define CC25_CSN_port PORTD #define CC25_CSN_port PORTD
#define CC25_CSN_ddr DDRD #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_pin 0 //D8 = PB0
#define NRF_CSN_port PORTB #define NRF_CSN_port PORTB
#define NRF_CSN_ddr DDRB #define NRF_CSN_ddr DDRB
#define CYRF_CSN_pin 1 //D9 = PB1 #define NRF_CSN_output NRF_CSN_ddr |= _BV(NRF_CSN_pin)
#define CYRF_CSN_port PORTB #define NRF_CSN_on NRF_CSN_port |= _BV(NRF_CSN_pin)
#define CYRF_CSN_ddr DDRB #define NRF_CSN_off NRF_CSN_port &= ~_BV(NRF_CSN_pin)
#define CYRF_RST_pin 5 //D9 = PB1
#define CYRF_RST_port PORTC
#define CYRF_RST_ddr DDRC
#define CTRL1_pin 1 //A1 = PC1
#define CTRL1_port PORTC
#define CTRL1_ddr DDRC
#define CTRL2_pin 2 //A2 = PC2
#define CTRL2_port PORTC
#define CTRL2_ddr DDRC
//
#ifdef XMEGA
#define CTRL1_on
#define CTRL1_off
#define CTRL2_on
#define CTRL2_off
#else
#define CTRL1_on CTRL1_port |= _BV(CTRL1_pin)
#define CTRL1_off CTRL1_port &= ~_BV(CTRL1_pin)
#define CTRL2_on CTRL2_port |= _BV(CTRL2_pin)
#define CTRL2_off CTRL2_port &= ~_BV(CTRL2_pin)
#endif
//
#ifdef XMEGA
#define A7105_CS_on A7105_CS_port.OUTSET = _BV(A7105_CS_pin) //D4
#define A7105_CS_off A7105_CS_port.OUTCLR = _BV(A7105_CS_pin) //D4
#else
#define A7105_CS_on A7105_CS_port |= _BV(A7105_CS_pin) //D2
#define A7105_CS_off A7105_CS_port &= ~_BV(A7105_CS_pin) //D2
#endif
//
#ifdef XMEGA
#define SCK_on SCLK_port.OUTSET = _BV(SCLK_pin) //D7
#define SCK_off SCLK_port.OUTCLR = _BV(SCLK_pin) //D7
#else
#define SCK_on SCLK_port |= _BV(SCLK_pin) //D4
#define SCK_off SCLK_port &= ~_BV(SCLK_pin) //D4
#endif
//
#ifdef XMEGA
#define SDI_on SDI_port.OUTSET = _BV(SDI_pin) //D5
#define SDI_off SDI_port.OUTCLR = _BV(SDI_pin) //D5
#else
#define SDI_on SDI_port |= _BV(SDI_pin) //D5
#define SDI_off SDI_port &= ~_BV(SDI_pin) //D5
#endif
//
#ifdef XMEGA
#define SDI_1 (SDI_port.IN & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (SDI_port.IN & _BV(SDI_pin)) == 0x00 //D5
#else
#define SDI_1 (SDI_ipr & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (SDI_ipr & _BV(SDI_pin)) == 0x00 //D5
#endif
//
#define SDI_SET_INPUT SDI_ddr &= ~_BV(SDI_pin) //D5
#define SDI_SET_OUTPUT SDI_ddr |= _BV(SDI_pin) //D5
//
#ifdef XMEGA
#define CC25_CSN_on CC25_CSN_port.OUTSET = _BV(CC25_CSN_pin) //D7
#define CC25_CSN_off CC25_CSN_port.OUTCLR = _BV(CC25_CSN_pin) //D7
#else
#define CC25_CSN_on CC25_CSN_port |= _BV(CC25_CSN_pin) //D7
#define CC25_CSN_off CC25_CSN_port &= ~_BV(CC25_CSN_pin) //D7
#endif
//
#ifdef XMEGA
#define NRF_CSN_on
#define NRF_CSN_off
#define NRF_CE_on #define NRF_CE_on
#define NRF_CE_off #define NRF_CE_off
#else
#define NRF_CSN_on NRF_CSN_port |= _BV(NRF_CSN_pin) //D8 // CYRF6936
#define NRF_CSN_off NRF_CSN_port &= ~_BV(NRF_CSN_pin) //D8
#define NRF_CE_on
#define NRF_CE_off
#endif
//
#ifdef XMEGA #ifdef XMEGA
#define CYRF_CSN_pin 4 //D4
#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_on CYRF_CSN_port.OUTSET = _BV(CYRF_CSN_pin)
#define CYRF_CSN_off CYRF_CSN_port.OUTCLR = _BV(CYRF_CSN_pin) #define CYRF_CSN_off CYRF_CSN_port.OUTCLR = _BV(CYRF_CSN_pin)
#else #else
#define CYRF_CSN_on CYRF_CSN_port |= _BV(CYRF_CSN_pin) //D9 #define CYRF_CSN_pin 1 //D9 = PB1
#define CYRF_CSN_off CYRF_CSN_port &= ~_BV(CYRF_CSN_pin) //D9 #define CYRF_CSN_port PORTB
#define CYRF_RST_HI CYRF_RST_port |= _BV(CYRF_RST_pin) //A5 #define CYRF_CSN_ddr DDRB
#define CYRF_RST_LO CYRF_RST_port &= ~_BV(CYRF_RST_pin) //A5 #define CYRF_CSN_output CYRF_CSN_ddr |= _BV(CYRF_CSN_pin)
#define CYRF_RST_pin 5 #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 #endif
//
//RF Switch
#ifdef XMEGA #ifdef XMEGA
#define SDO_1 (SDO_port.IN & _BV(SDO_pin)) == _BV(SDO_pin) //D6 #define PE1_on
#define SDO_0 (SDO_port.IN & _BV(SDO_pin)) == 0x00 //D6 #define PE1_off
#define PE2_on
#define PE2_off
#else #else
#define SDO_1 (SDO_ipr & _BV(SDO_pin)) == _BV(SDO_pin) //D6 #define PE1_pin 1 //A1 = PC1
#define SDO_0 (SDO_ipr & _BV(SDO_pin)) == 0x00 //D6 #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 #endif
//
//
// LED // LED
#ifdef XMEGA #ifdef XMEGA
#define LED_ON LED_port.OUTCLR = _BV(LED_pin) #define LED_pin 1 //PD1
#define LED_OFF LED_port.OUTSET = _BV(LED_pin) #define LED_port PORTD
#define LED_TOGGLE LED_port.OUTTGL = _BV(LED_pin) #define LED_ddr DDRD
#define LED_SET_OUTPUT LED_port.DIRSET = _BV(LED_pin) #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)) != 0x00 ) #define IS_LED_on ( (LED_port.OUT & _BV(LED_pin)) != 0x00 )
#else #else
#define LED_ON LED_port |= _BV(LED_pin) #define LED_pin 5 //D13 = PB5
#define LED_OFF LED_port &= ~_BV(LED_pin) #define LED_port PORTB
#define LED_TOGGLE LED_port ^= _BV(LED_pin) #define LED_ddr DDRB
#define LED_SET_OUTPUT LED_ddr |= _BV(LED_pin) #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)) != 0x00 ) #define IS_LED_on ( (LED_port & _BV(LED_pin)) != 0x00 )
#endif #endif
//BIND //BIND
#ifdef XMEGA #ifdef XMEGA
#define IS_BIND_BUTTON_on ( (PORTD.IN & _BV(2)) == 0x00 ) #define BIND_pin 2 //PD2
#define BIND_port PORTD
#define IS_BIND_BUTTON_on ( (BIND_port.IN & _BV(BIND_pin)) == 0x00 )
#else #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_INPUT BIND_ddr &= ~_BV(BIND_pin)
#define BIND_SET_PULLUP BIND_port |= _BV(BIND_pin) #define BIND_SET_PULLUP BIND_port |= _BV(BIND_pin)
#define IS_BIND_BUTTON_on ( (BIND_ipr & _BV(BIND_pin)) == 0x00 ) #define IS_BIND_BUTTON_on ( (BIND_ipr & _BV(BIND_pin)) == 0x00 )
#define BIND_SET_OUTPUT BIND_ddr |= _BV(BIND_pin) #define BIND_SET_OUTPUT BIND_ddr |= _BV(BIND_pin)
#endif #endif
// TX
#ifdef DEBUG_TX
#define TX_ON DEBUG_TX_port |= _BV(DEBUG_TX_pin)
#define TX_OFF DEBUG_TX_port &= ~_BV(DEBUG_TX_pin)
#define TX_TOGGLE DEBUG_TX_port ^= _BV(DEBUG_TX_pin)
#define TX_SET_OUTPUT DEBUG_TX_ddr |= _BV(DEBUG_TX_pin)
#else
#define TX_ON
#define TX_OFF
#define TX_TOGGLE
#define TX_SET_OUTPUT
#endif
// Macros // Macros
#define NOP() __asm__ __volatile__("nop") #define NOP() __asm__ __volatile__("nop")
#define BV(bit) (1 << bit) #define BV(bit) (1 << bit)
@ -674,4 +668,3 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
2047 +125% 2047 +125%
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
*/ */

View File

@ -33,7 +33,7 @@
#undef ENABLE_PPM // Disable PPM for orange module #undef ENABLE_PPM // Disable PPM for orange module
#undef A7105_INSTALLED // Disable A7105 for orange module #undef A7105_INSTALLED // Disable A7105 for orange module
#undef CC2500_INSTALLED // Disable CC2500 for orange module #undef CC2500_INSTALLED // Disable CC2500 for orange module
#undef NFR24L01_INSTALLED // Disable NRF for orange module #undef NRF24L01_INSTALLED // Disable NRF for orange module
#endif #endif
//Global constants/variables //Global constants/variables
@ -172,47 +172,46 @@ void setup()
TCC1.CTRLA = 0x0B ; // Event3 (prescale of 16) TCC1.CTRLA = 0x0B ; // Event3 (prescale of 16)
#else #else
// General pinout // General pinout
// all inputs
DDRB=DDRC=DDRD=0x00;
// outputs // outputs
SDI_output;
SCLK_output;
#ifdef A7105_INSTALLED #ifdef A7105_INSTALLED
A7105_CS_ddr |= _BV(A7105_CS_pin); A7105_CSN_output;
#endif #endif
SDI_SET_OUTPUT;
SCLK_ddr |= _BV(SCLK_pin);
#ifdef CC2500_INSTALLED #ifdef CC2500_INSTALLED
CC25_CSN_ddr |= _BV(CC25_CSN_pin); CC25_CSN_output;
#endif #endif
CTRL1_ddr |= _BV(CTRL1_pin);
CTRL2_ddr |= _BV(CTRL2_pin);
#ifdef CYRF6936_INSTALLED #ifdef CYRF6936_INSTALLED
CYRF_RST_ddr |= _BV(CYRF_RST_pin); CYRF_RST_output;
CYRF_CSN_ddr |= _BV(CYRF_CSN_pin); CYRF_CSN_output;
#endif #endif
#ifdef NRF24L01_INSTALLED #ifdef NRF24L01_INSTALLED
NRF_CSN_ddr |= _BV(NRF_CSN_pin); NRF_CSN_output;
#endif #endif
PE1_output;
PE2_output;
SERIAL_TX_output;
//pullup on dial (D10=PB2,D11=PB3,D12=PB4) and bind button // pullups
MODE_DIAL1_PORT |= _BV(MODE_DIAL1_PIN); MODE_DIAL1_port |= _BV(MODE_DIAL1_pin);
MODE_DIAL2_PORT |= _BV(MODE_DIAL2_PIN); MODE_DIAL2_port |= _BV(MODE_DIAL2_pin);
MODE_DIAL3_PORT |= _BV(MODE_DIAL3_PIN); MODE_DIAL3_port |= _BV(MODE_DIAL3_pin);
MODE_DIAL4_PORT |= _BV(MODE_DIAL4_PIN); MODE_DIAL4_port |= _BV(MODE_DIAL4_pin);
BIND_port |= _BV(BIND_pin); BIND_port |= _BV(BIND_pin);
#ifdef DEBUG_TX
TX_SET_OUTPUT;
#endif
// Timer1 config // Timer1 config
TCCR1A = 0; TCCR1A = 0;
TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer
// Random
random_init(); random_init();
#endif #endif
// Set Chip selects // Set Chip selects
#ifdef A7105_INSTALLED #ifdef A7105_INSTALLED
A7105_CS_on; A7105_CSN_on;
#endif #endif
#ifdef CC2500_INSTALLED #ifdef CC2500_INSTALLED
CC25_CSN_on; CC25_CSN_on;
@ -225,7 +224,7 @@ void setup()
#endif #endif
// Set SPI lines // Set SPI lines
SDI_on; SDI_on;
SCK_off; SCLK_off;
// Set servos positions // Set servos positions
for(uint8_t i=0;i<NUM_CHN;i++) for(uint8_t i=0;i<NUM_CHN;i++)
@ -248,15 +247,15 @@ void setup()
mode_select = MODE_SERIAL ; // force serial mode mode_select = MODE_SERIAL ; // force serial mode
#else #else
mode_select = mode_select =
((MODE_DIAL1_PORT & MODE_DIAL1_PIN) ? 1 : 0) + ((MODE_DIAL1_port & MODE_DIAL1_pin) ? 1 : 0) +
((MODE_DIAL2_PORT & MODE_DIAL2_PIN) ? 2 : 0) + ((MODE_DIAL2_port & MODE_DIAL2_pin) ? 2 : 0) +
((MODE_DIAL3_PORT & MODE_DIAL3_PIN) ? 4 : 0) + ((MODE_DIAL3_port & MODE_DIAL3_pin) ? 4 : 0) +
((MODE_DIAL4_PORT & MODE_DIAL4_PIN) ? 8 : 0); ((MODE_DIAL4_port & MODE_DIAL4_pin) ? 8 : 0);
#endif #endif
// Update LED // Update LED
LED_OFF; LED_off;
LED_SET_OUTPUT; LED_output;
//Init RF modules //Init RF modules
modules_reset(); modules_reset();
@ -290,8 +289,8 @@ void setup()
//Configure PPM interrupt //Configure PPM interrupt
#if PPM_pin == 2 #if PPM_pin == 2
EICRA |= _BV(ISC01); // The rising edge of INT1 pin D3 generates an interrupt request EICRA |= _BV(ISC01); // The rising edge of INT0 pin D2 generates an interrupt request
EIMSK |= _BV(INT0); // INT1 interrupt enable EIMSK |= _BV(INT0); // INT0 interrupt enable
#elif PPM_pin == 3 #elif PPM_pin == 3
EICRA |= _BV(ISC11); // The rising edge of INT1 pin D3 generates an interrupt request EICRA |= _BV(ISC11); // The rising edge of INT1 pin D3 generates an interrupt request
EIMSK |= _BV(INT1); // INT1 interrupt enable EIMSK |= _BV(INT1); // INT1 interrupt enable
@ -299,7 +298,6 @@ void setup()
#error PPM pin can only be 2 or 3 #error PPM pin can only be 2 or 3
#endif #endif
#if defined(TELEMETRY) #if defined(TELEMETRY)
PPM_Telemetry_serial_init(); // Configure serial for telemetry PPM_Telemetry_serial_init(); // Configure serial for telemetry
#endif #endif
@ -383,7 +381,7 @@ void Update_All()
update_aux_flags(); update_aux_flags();
if(IS_CHANGE_PROTOCOL_FLAG_on) if(IS_CHANGE_PROTOCOL_FLAG_on)
{ // Protocol needs to be changed { // Protocol needs to be changed
LED_OFF; //led off during protocol init LED_off; //led off during protocol init
modules_reset(); //reset all modules modules_reset(); //reset all modules
protocol_init(); //init new protocol protocol_init(); //init new protocol
} }
@ -439,10 +437,10 @@ static void update_led_status(void)
} }
else else
if(IS_BIND_DONE_on) if(IS_BIND_DONE_on)
LED_OFF; //bind completed -> led on LED_off; //bind completed -> led on
else else
blink+=BLINK_BIND_TIME; //blink fastly during binding blink+=BLINK_BIND_TIME; //blink fastly during binding
LED_TOGGLE; LED_toggle;
} }
} }
@ -504,21 +502,21 @@ static void protocol_init()
else else
BIND_DONE; BIND_DONE;
CTRL1_on; //NRF24L01 antenna RF3 by default PE1_on; //NRF24L01 antenna RF3 by default
CTRL2_off; //NRF24L01 antenna RF3 by default PE2_off; //NRF24L01 antenna RF3 by default
switch(protocol) // Init the requested protocol switch(protocol) // Init the requested protocol
{ {
#if defined(FLYSKY_A7105_INO) #if defined(FLYSKY_A7105_INO)
case MODE_FLYSKY: case MODE_FLYSKY:
CTRL1_off; //antenna RF1 PE1_off; //antenna RF1
next_callback = initFlySky(); next_callback = initFlySky();
remote_callback = ReadFlySky; remote_callback = ReadFlySky;
break; break;
#endif #endif
#if defined(HUBSAN_A7105_INO) #if defined(HUBSAN_A7105_INO)
case MODE_HUBSAN: case MODE_HUBSAN:
CTRL1_off; //antenna RF1 PE1_off; //antenna RF1
if(IS_BIND_BUTTON_FLAG_on) random_id(10,true); // Generate new ID if bind button is pressed. if(IS_BIND_BUTTON_FLAG_on) random_id(10,true); // Generate new ID if bind button is pressed.
next_callback = initHubsan(); next_callback = initHubsan();
remote_callback = ReadHubsan; remote_callback = ReadHubsan;
@ -526,39 +524,39 @@ static void protocol_init()
#endif #endif
#if defined(FRSKYD_CC2500_INO) #if defined(FRSKYD_CC2500_INO)
case MODE_FRSKYD: case MODE_FRSKYD:
CTRL1_off; //antenna RF2 PE1_off; //antenna RF2
CTRL2_on; PE2_on;
next_callback = initFrSky_2way(); next_callback = initFrSky_2way();
remote_callback = ReadFrSky_2way; remote_callback = ReadFrSky_2way;
break; break;
#endif #endif
#if defined(FRSKYV_CC2500_INO) #if defined(FRSKYV_CC2500_INO)
case MODE_FRSKYV: case MODE_FRSKYV:
CTRL1_off; //antenna RF2 PE1_off; //antenna RF2
CTRL2_on; PE2_on;
next_callback = initFRSKYV(); next_callback = initFRSKYV();
remote_callback = ReadFRSKYV; remote_callback = ReadFRSKYV;
break; break;
#endif #endif
#if defined(FRSKYX_CC2500_INO) #if defined(FRSKYX_CC2500_INO)
case MODE_FRSKYX: case MODE_FRSKYX:
CTRL1_off; //antenna RF2 PE1_off; //antenna RF2
CTRL2_on; PE2_on;
next_callback = initFrSkyX(); next_callback = initFrSkyX();
remote_callback = ReadFrSkyX; remote_callback = ReadFrSkyX;
break; break;
#endif #endif
#if defined(SFHSS_CC2500_INO) #if defined(SFHSS_CC2500_INO)
case MODE_SFHSS: case MODE_SFHSS:
CTRL1_off; //antenna RF2 PE1_off; //antenna RF2
CTRL2_on; PE2_on;
next_callback = initSFHSS(); next_callback = initSFHSS();
remote_callback = ReadSFHSS; remote_callback = ReadSFHSS;
break; break;
#endif #endif
#if defined(DSM_CYRF6936_INO) #if defined(DSM_CYRF6936_INO)
case MODE_DSM: case MODE_DSM:
CTRL2_on; //antenna RF4 PE2_on; //antenna RF4
next_callback = initDsm(); next_callback = initDsm();
//Servo_data[2]=1500;//before binding //Servo_data[2]=1500;//before binding
remote_callback = ReadDsm; remote_callback = ReadDsm;
@ -581,14 +579,14 @@ static void protocol_init()
} }
} }
#endif //ENABLE_PPM #endif //ENABLE_PPM
CTRL2_on; //antenna RF4 PE2_on; //antenna RF4
next_callback = DevoInit(); next_callback = DevoInit();
remote_callback = devo_callback; remote_callback = devo_callback;
break; break;
#endif #endif
#if defined(J6PRO_CYRF6936_INO) #if defined(J6PRO_CYRF6936_INO)
case MODE_J6PRO: case MODE_J6PRO:
CTRL2_on; //antenna RF4 PE2_on; //antenna RF4
next_callback = initJ6Pro(); next_callback = initJ6Pro();
remote_callback = ReadJ6Pro; remote_callback = ReadJ6Pro;
break; break;
@ -790,7 +788,7 @@ void modules_reset()
#ifdef CYRF6936_INSTALLED #ifdef CYRF6936_INSTALLED
CYRF_Reset(); CYRF_Reset();
#endif #endif
#ifdef NFR24L01_INSTALLED #ifdef NRF24L01_INSTALLED
NRF24L01_Reset(); NRF24L01_Reset();
#endif #endif
@ -971,7 +969,7 @@ void SPI_Write(uint8_t command)
{ {
uint8_t n=8; uint8_t n=8;
SCK_off;//SCK start low SCLK_off;//SCK start low
XNOP(); XNOP();
SDI_off; SDI_off;
XNOP(); XNOP();
@ -982,11 +980,11 @@ void SPI_Write(uint8_t command)
else else
SDI_off; SDI_off;
XNOP(); XNOP();
SCK_on; SCLK_on;
XNOP(); XNOP();
XNOP(); XNOP();
command = command << 1; command = command << 1;
SCK_off; SCLK_off;
XNOP(); XNOP();
} }
while(--n) ; while(--n) ;
@ -1001,11 +999,11 @@ uint8_t SPI_Read(void)
result=result<<1; result=result<<1;
if(SDO_1) if(SDO_1)
result |= 0x01; result |= 0x01;
SCK_on; SCLK_on;
XNOP(); XNOP();
XNOP(); XNOP();
NOP(); NOP();
SCK_off; SCLK_off;
XNOP(); XNOP();
XNOP(); XNOP();
} }

View File

@ -588,11 +588,10 @@ void initTXSerial( uint8_t speed)
{ {
TIMSK0 = 0 ; // Stop all timer 0 interrupts TIMSK0 = 0 ; // Stop all timer 0 interrupts
#ifdef INVERT_SERIAL #ifdef INVERT_SERIAL
TELEMETRY_SERIAL_TX_port &= ~_BV(TELEMETRY_SERIAL_TX_pin); SERIAL_TX_off;
#else #else
TELEMETRY_SERIAL_TX_port |= _BV(TELEMETRY_SERIAL_TX_pin); SERIAL_TX_on;
#endif #endif
TELEMETRY_SERIAL_TX_ddr |= _BV(TELEMETRY_SERIAL_TX_pin) ; // TxD pin is an output
UCSR0B &= ~(1<<TXEN0) ; UCSR0B &= ~(1<<TXEN0) ;
SerialControl.speed = speed ; SerialControl.speed = speed ;
@ -706,13 +705,9 @@ ISR(TIMER0_COMPA_vect)
uint8_t byte ; uint8_t byte ;
byte = GPIOR0 ; byte = GPIOR0 ;
if ( byte & 0x01 ) if ( byte & 0x01 )
{ SERIAL_TX_on;
TELEMETRY_SERIAL_TX_port |= _BV(TELEMETRY_SERIAL_TX_pin);
}
else else
{ SERIAL_TX_off;
TELEMETRY_SERIAL_TX_port &= ~_BV(TELEMETRY_SERIAL_TX_pin);
}
byte /= 2 ; // Generates shorter code than byte >>= 1 byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR0 = byte ; GPIOR0 = byte ;
if ( --GPIOR1 == 0 ) if ( --GPIOR1 == 0 )
@ -731,13 +726,9 @@ ISR(TIMER0_COMPB_vect)
uint8_t byte ; uint8_t byte ;
byte = GPIOR2 ; byte = GPIOR2 ;
if ( byte & 0x01 ) if ( byte & 0x01 )
{ SERIAL_TX_on;
TELEMETRY_SERIAL_TX_port |= _BV(TELEMETRY_SERIAL_TX_pin);
}
else else
{ SERIAL_TX_off;
TELEMETRY_SERIAL_TX_port &= ~_BV(TELEMETRY_SERIAL_TX_pin);
}
byte /= 2 ; // Generates shorter code than byte >>= 1 byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR2 = byte ; GPIOR2 = byte ;
if ( --GPIOR1 == 0 ) if ( --GPIOR1 == 0 )
@ -786,13 +777,9 @@ ISR(TIMER0_OVF_vect)
byte = GPIOR2 ; byte = GPIOR2 ;
} }
if ( byte & 0x01 ) if ( byte & 0x01 )
{ SERIAL_TX_on;
TELEMETRY_SERIAL_TX_port |= _BV(TELEMETRY_SERIAL_TX_pin);
}
else else
{ SERIAL_TX_off;
TELEMETRY_SERIAL_TX_port &= ~_BV(TELEMETRY_SERIAL_TX_pin);
}
byte /= 2 ; // Generates shorter code than byte >>= 1 byte /= 2 ; // Generates shorter code than byte >>= 1
if ( GPIOR1 > 2 ) if ( GPIOR1 > 2 )
{ {

View File

@ -152,7 +152,7 @@ const PPM_Parameters PPM_prot[15]= {
/* 3 */ {MODE_FRSKYD, 0 , 0 , P_HIGH , NO_AUTOBIND , 40 }, // option=fine freq tuning /* 3 */ {MODE_FRSKYD, 0 , 0 , P_HIGH , NO_AUTOBIND , 40 }, // option=fine freq tuning
/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 6 */ {MODE_DSM , DSM2_22 , 0 , P_HIGH , NO_AUTOBIND , 2 }, // option=2=6 channels @ 22ms /* 6 */ {MODE_DSM , DSM2_22 , 0 , P_HIGH , NO_AUTOBIND , 6 }, // option=6 channels @ 22ms
/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 },