mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-07-12 09:47:54 +00:00
maj
This commit is contained in:
parent
349e5a6404
commit
f12ff1c58d
@ -23,19 +23,25 @@ void A7105_WriteData(uint8_t len, uint8_t channel)
|
||||
uint8_t i;
|
||||
A7105_CSN_off;
|
||||
SPI_Write(A7105_RST_WRPTR);
|
||||
SPI_Write(0x05);
|
||||
SPI_Write(A7105_05_FIFO_DATA);
|
||||
for (i = 0; i < len; i++)
|
||||
SPI_Write(packet[i]);
|
||||
A7105_CSN_on;
|
||||
A7105_WriteReg(0x0F, channel);
|
||||
if(protocol!=MODE_FLYSKY)
|
||||
{
|
||||
A7105_Strobe(A7105_STANDBY); //Force standby mode, ie cancel any TX or RX...
|
||||
A7105_SetTxRxMode(TX_EN); //Switch to PA
|
||||
}
|
||||
A7105_WriteReg(A7105_0F_PLL_I, channel);
|
||||
A7105_Strobe(A7105_TX);
|
||||
}
|
||||
|
||||
void A7105_ReadData(uint8_t len=16) {
|
||||
void A7105_ReadData(uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
A7105_Strobe(0xF0); //A7105_RST_RDPTR
|
||||
A7105_Strobe(A7105_RST_RDPTR);
|
||||
A7105_CSN_off;
|
||||
SPI_Write(0x45);
|
||||
SPI_Write(0x40 | A7105_05_FIFO_DATA); //bit 6 =1 for reading
|
||||
for (i=0;i<len;i++)
|
||||
packet[i]=SPI_SDI_Read();
|
||||
A7105_CSN_on;
|
||||
@ -62,13 +68,19 @@ uint8_t A7105_ReadReg(uint8_t address)
|
||||
//------------------------
|
||||
void A7105_SetTxRxMode(uint8_t mode)
|
||||
{
|
||||
if(mode == TX_EN) {
|
||||
if(mode == TX_EN)
|
||||
{
|
||||
A7105_WriteReg(A7105_0B_GPIO1_PIN1, 0x33);
|
||||
A7105_WriteReg(A7105_0C_GPIO2_PIN_II, 0x31);
|
||||
} else if (mode == RX_EN) {
|
||||
}
|
||||
else
|
||||
if (mode == RX_EN)
|
||||
{
|
||||
A7105_WriteReg(A7105_0B_GPIO1_PIN1, 0x31);
|
||||
A7105_WriteReg(A7105_0C_GPIO2_PIN_II, 0x33);
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
//The A7105 seems to some with a cross-wired power-amp (A7700)
|
||||
//On the XL7105-D03, TX_EN -> RXSW and RX_EN -> TXSW
|
||||
//This means that sleep mode is wired as RX_EN = 1 and TX_EN = 1
|
||||
@ -83,21 +95,22 @@ uint8_t A7105_Reset()
|
||||
{
|
||||
uint8_t result;
|
||||
|
||||
A7105_WriteReg(0x00, 0x00);
|
||||
A7105_WriteReg(A7105_00_MODE, 0x00);
|
||||
delayMilliseconds(1);
|
||||
A7105_SetTxRxMode(TXRX_OFF); //Set both GPIO as output and low
|
||||
result=A7105_ReadReg(0x10) == 0x9E; //check if is reset.
|
||||
result=A7105_ReadReg(A7105_10_PLL_II) == 0x9E; //check if is reset.
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
return result;
|
||||
}
|
||||
|
||||
void A7105_WriteID(uint32_t ida) {
|
||||
void A7105_WriteID(uint32_t ida)
|
||||
{
|
||||
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
|
||||
SPI_Write(A7105_06_ID_DATA); //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;
|
||||
}
|
||||
|
||||
@ -138,7 +151,7 @@ void A7105_SetPower()
|
||||
power=A7105_RANGE_POWER;
|
||||
if(prev_power != power)
|
||||
{
|
||||
A7105_WriteReg(0x28, power);
|
||||
A7105_WriteReg(A7105_28_TX_TEST, power);
|
||||
prev_power=power;
|
||||
}
|
||||
}
|
||||
@ -148,121 +161,100 @@ void A7105_Strobe(uint8_t address) {
|
||||
SPI_Write(address);
|
||||
A7105_CSN_on;
|
||||
}
|
||||
|
||||
#ifdef HUBSAN_A7105_INO
|
||||
const uint8_t PROGMEM HUBSAN_A7105_regs[] = {
|
||||
0xFF, 0x63, 0xFF, 0x0F, 0xFF, 0xFF, 0xFF ,0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x05, 0x04, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x2B, 0xFF, 0xFF, 0x62, 0x80, 0xFF, 0xFF, 0x0A, 0xFF, 0xFF, 0x07,
|
||||
0x17, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x47, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF
|
||||
0xFF, 0xFF
|
||||
};
|
||||
#endif
|
||||
#ifdef FLYSKY_A7105_INO
|
||||
const uint8_t PROGMEM FLYSKY_A7105_regs[] = {
|
||||
0xff, 0x42, 0x00, 0x14, 0x00, 0xff, 0xff ,0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50,
|
||||
0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f,
|
||||
0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00,
|
||||
0x01, 0x0f, 0xff
|
||||
0x01, 0x0f
|
||||
};
|
||||
const uint8_t PROGMEM AFHDS2A_regs[] = {
|
||||
0xFF , 0x42 | (1<<5), 0x00, 0x25, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, 0x05, 0x00, 0x50, // 00 - 0f
|
||||
0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x4f, 0x62, 0x80, 0xFF, 0xFF, 0x2a, 0x32, 0xc3, 0x1f, // 10 - 1f
|
||||
0x1e, 0xFF, 0x00, 0xFF, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, // 20 - 2f
|
||||
#endif
|
||||
#ifdef AFHDS2A_A7105_INO
|
||||
const uint8_t PROGMEM AFHDS2A_A7105_regs[] = {
|
||||
0xFF, 0x42 | (1<<5), 0x00, 0x25, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, 0x05, 0x00, 0x50, // 00 - 0f
|
||||
0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x4f, 0x62, 0x80, 0xFF, 0xFF, 0x2a, 0x32, 0xc3, 0x1f, // 10 - 1f
|
||||
0x1e, 0xFF, 0x00, 0xFF, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, // 20 - 2f
|
||||
0x01, 0x0f // 30 - 31
|
||||
};
|
||||
static const uint8_t PROGMEM JOYSWAY_regs[] = {
|
||||
0x00, 0x62, -1, 0x0f, 0x00, -1 , -1 , 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0xf5, 0x00, 0x15,
|
||||
0x9e, 0x4b, 0x00, 0x03, 0x56, 0x2b, 0x12, 0x4a, 0x02, 0x80, 0x80, 0x00, 0x0e, 0x91, 0x03, 0x0f,
|
||||
0x16, 0x2a, 0x00, -1, -1, -1, 0x3a, 0x06, 0x1f, 0x47, 0x80, 0x01, 0x05, 0x45, 0x18, 0x00,
|
||||
0x01, 0x0f, 0x00
|
||||
};
|
||||
#endif
|
||||
|
||||
#define ID_NORMAL 0x55201041
|
||||
#define ID_PLUS 0xAA201041
|
||||
void A7105_Init(uint8_t protocol)
|
||||
void A7105_Init(void)
|
||||
{
|
||||
uint8_t *A7105_Regs;
|
||||
uint8_t *A7105_Regs=0;
|
||||
|
||||
if(protocol==INIT_FLYSKY || protocol==INIT_FLYSKY_AFHDS2A)
|
||||
{
|
||||
A7105_WriteID(0x5475c52A);//0x2Ac57554
|
||||
if(protocol==INIT_FLYSKY_AFHDS2A)
|
||||
A7105_Regs=(uint8_t*)AFHDS2A_regs;
|
||||
#ifdef HUBSAN_A7105_INO
|
||||
if(protocol==MODE_HUBSAN)
|
||||
{
|
||||
A7105_WriteID(ID_NORMAL);
|
||||
A7105_Regs=(uint8_t*)HUBSAN_A7105_regs;
|
||||
}
|
||||
else
|
||||
A7105_Regs=(uint8_t*)FLYSKY_A7105_regs;
|
||||
}
|
||||
else if(protocol==INIT_JOYSWAY)
|
||||
#endif
|
||||
{
|
||||
A7105_WriteID(0x5475c52A);//0x2Ac57554
|
||||
#ifdef FLYSKY_A7105_INO
|
||||
if(protocol==MODE_FLYSKY)
|
||||
A7105_Regs=(uint8_t*)FLYSKY_A7105_regs;
|
||||
else
|
||||
#endif
|
||||
{
|
||||
#ifdef AFHDS2A_A7105_INO
|
||||
A7105_Regs=(uint8_t*)AFHDS2A_A7105_regs;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < 0x32; i++)
|
||||
{
|
||||
A7105_WriteID(0x5475c52a);//0x2Ac57554
|
||||
A7105_Regs=(uint8_t*)JOYSWAY_regs;
|
||||
uint8_t val=pgm_read_byte_near(&A7105_Regs[i]);
|
||||
if( val != 0xFF)
|
||||
A7105_WriteReg(i, val);
|
||||
}
|
||||
else
|
||||
{ // HUBSAN
|
||||
A7105_WriteID(ID_NORMAL);
|
||||
A7105_Regs=(uint8_t*)HUBSAN_A7105_regs;
|
||||
}
|
||||
for (uint8_t i = 0; i < 0x33; i++){
|
||||
if( pgm_read_byte_near(&A7105_Regs[i]) != 0xFF)
|
||||
A7105_WriteReg(i, pgm_read_byte_near(&A7105_Regs[i]));
|
||||
}
|
||||
if(protocol==INIT_JOYSWAY)
|
||||
A7105_Strobe(A7105_PLL);
|
||||
else
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
|
||||
//IF Filter Bank Calibration
|
||||
A7105_WriteReg(A7105_02_CALC,1);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
// A7105_ReadReg(A7105_22_IF_CALIB_I);
|
||||
// A7105_ReadReg(A7105_24_VCO_CURCAL);
|
||||
if(protocol==INIT_JOYSWAY) {
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
//VCO Current Calibration
|
||||
A7105_WriteReg(A7105_24_VCO_CURCAL,0x13); //Recommended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(A7105_25_VCO_SBCAL_I,0x09); //Recommended calibration from A7105 Datasheet
|
||||
A7105_WriteID(binding_idx);
|
||||
}
|
||||
|
||||
if(protocol==INIT_FLYSKY || protocol==INIT_FLYSKY_AFHDS2A)
|
||||
if(protocol!=MODE_HUBSAN)
|
||||
{
|
||||
//VCO Current Calibration
|
||||
A7105_WriteReg(A7105_24_VCO_CURCAL,0x13); //Recommended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(A7105_24_VCO_CURCAL,0x13); //Recommended calibration from A7105 Datasheet
|
||||
//VCO Bank Calibration
|
||||
A7105_WriteReg(A7105_26_VCO_SBCAL_II,0x3b); //Recommended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(A7105_26_VCO_SBCAL_II,0x3b); //Recommended calibration from A7105 Datasheet
|
||||
}
|
||||
|
||||
//VCO Bank Calibrate channel 0
|
||||
if(protocol==INIT_JOYSWAY) {
|
||||
A7105_Strobe(A7105_PLL);
|
||||
A7105_WriteReg(A7105_02_CALC,1);
|
||||
}
|
||||
else {
|
||||
A7105_WriteReg(A7105_0F_CHANNEL, 0);
|
||||
A7105_WriteReg(A7105_02_CALC,2);
|
||||
}
|
||||
A7105_WriteReg(A7105_0F_CHANNEL, 0);
|
||||
A7105_WriteReg(A7105_02_CALC,2);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
// A7105_ReadReg(A7105_25_VCO_SBCAL_I);
|
||||
|
||||
if(protocol==INIT_JOYSWAY) {
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
//VCO Current Calibration
|
||||
A7105_WriteReg(A7105_24_VCO_CURCAL,0x13); //Recommended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(A7105_25_VCO_SBCAL_I,0x09); //Recommended calibration from A7105 Datasheet
|
||||
}
|
||||
else {
|
||||
//VCO Bank Calibrate channel A0
|
||||
A7105_WriteReg(A7105_0F_CHANNEL, 0xa0);
|
||||
A7105_WriteReg(A7105_02_CALC, 2);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
// A7105_ReadReg(A7105_25_VCO_SBCAL_I);
|
||||
//VCO Bank Calibrate channel A0
|
||||
A7105_WriteReg(A7105_0F_CHANNEL, 0xa0);
|
||||
A7105_WriteReg(A7105_02_CALC, 2);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
// A7105_ReadReg(A7105_25_VCO_SBCAL_I);
|
||||
|
||||
//Reset VCO Band calibration
|
||||
if(protocol==INIT_FLYSKY)
|
||||
A7105_WriteReg(A7105_25_VCO_SBCAL_I,0x08);
|
||||
if(protocol==INIT_FLYSKY_AFHDS2A)
|
||||
A7105_WriteReg(A7105_25_VCO_SBCAL_I,0x0A);
|
||||
}
|
||||
//Reset VCO Band calibration
|
||||
if(protocol!=MODE_HUBSAN)
|
||||
A7105_WriteReg(A7105_25_VCO_SBCAL_I,protocol==MODE_FLYSKY?0x08:0x0A);
|
||||
|
||||
A7105_SetTxRxMode(TX_EN);
|
||||
A7105_SetPower();
|
||||
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
}
|
||||
#endif
|
||||
#endif
|
@ -20,6 +20,12 @@
|
||||
#define EVEN_ODD 0x00
|
||||
//#define EVEN_ODD 0x01
|
||||
|
||||
static uint8_t PROGMEM A7105_regs[] = {
|
||||
0x00, 0x62, 0xFF, 0x0f, 0x00, 0xFF , 0xFF , 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0xf5, 0x00, 0x15,
|
||||
0x9e, 0x4b, 0x00, 0x03, 0x56, 0x2b, 0x12, 0x4a, 0x02, 0x80, 0x80, 0x00, 0x0e, 0x91, 0x03, 0x0f,
|
||||
0x16, 0x2a, 0x00, 0xFF, 0xFF, 0xFF, 0x3a, 0x06, 0x1f, 0x47, 0x80, 0x01, 0x05, 0x45, 0x18, 0x00,
|
||||
0x01, 0x0f, 0x00
|
||||
};
|
||||
static void joysway_build_packet()
|
||||
{
|
||||
int i;
|
||||
@ -29,10 +35,10 @@ static void joysway_build_packet()
|
||||
//Center = 0x5d9
|
||||
//1 % = 5
|
||||
packet[0] = phase == 0 ? 0xdd : 0xff;
|
||||
packet[1] = (binding_idx >> 24) & 0xff;
|
||||
packet[2] = (binding_idx >> 16) & 0xff;
|
||||
packet[3] = (binding_idx >> 8) & 0xff;
|
||||
packet[4] = (binding_idx >> 0) & 0xff;
|
||||
packet[1] = (MProtocol_id >> 24) & 0xff;
|
||||
packet[2] = (MProtocol_id >> 16) & 0xff;
|
||||
packet[3] = (MProtocol_id >> 8) & 0xff;
|
||||
packet[4] = (MProtocol_id >> 0) & 0xff;
|
||||
packet[5] = 0x00;
|
||||
static const int chmap[4] = {6, 7, 10, 11};
|
||||
for (i = 0; i < 4; i++) {
|
||||
@ -56,7 +62,7 @@ static uint16_t joysway_cb()
|
||||
A7105_WriteID(0x5475c52a);
|
||||
hopping_frequency_no = 0x0a;
|
||||
} else if (phase == 2) {
|
||||
A7105_WriteID(binding_idx);
|
||||
A7105_WriteID(MProtocol_id);
|
||||
hopping_frequency_no = 0x30;
|
||||
} else {
|
||||
if ((phase & 0x01) ^ EVEN_ODD) {
|
||||
@ -78,8 +84,44 @@ static uint16_t joysway_cb()
|
||||
}
|
||||
|
||||
static uint16_t JOYSWAY_Setup() {
|
||||
binding_idx = MProtocol_id_master | 0xf8000000;
|
||||
A7105_Init(INIT_JOYSWAY);
|
||||
int i;
|
||||
u8 if_calibration1;
|
||||
//u8 vco_calibration0;
|
||||
//u8 vco_calibration1;
|
||||
|
||||
counter = 0;
|
||||
next_ch = 0x30;
|
||||
|
||||
for (i = 0; i < 0x33; i++) {
|
||||
uint8_t val=pgm_read_byte_near(&A7105_Regs[i]);
|
||||
if( val != 0xFF)
|
||||
A7105_WriteReg(i, val);
|
||||
}
|
||||
A7105_WriteID(0x5475c52a);
|
||||
|
||||
A7105_Strobe(A7105_PLL);
|
||||
|
||||
//IF Filter Bank Calibration
|
||||
A7105_WriteReg(0x02, 1);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
|
||||
//VCO Current Calibration
|
||||
A7105_WriteReg(0x24, 0x13); //Recomended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(0x25, 0x09); //Recomended calibration from A7105 Datasheet
|
||||
|
||||
A7105_WriteID(MProtocol_id);
|
||||
A7105_Strobe(A7105_PLL);
|
||||
A7105_WriteReg(0x02, 1);
|
||||
while(A7105_ReadReg(A7105_02_CALC)); // Wait for calibration to end
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
A7105_WriteReg(0x24, 0x13); //Recomended calibration from A7105 Datasheet
|
||||
A7105_WriteReg(0x25, 0x09); //Recomended calibration from A7105 Datasheet
|
||||
|
||||
A7105_SetTxRxMode(TX_EN);
|
||||
A7105_SetPower();
|
||||
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
return 2400;
|
||||
}
|
||||
#endif
|
||||
|
351
Multiprotocol/AFHDS2A_a7105.ino
Normal file
351
Multiprotocol/AFHDS2A_a7105.ino
Normal file
@ -0,0 +1,351 @@
|
||||
/*
|
||||
This project is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Multiprotocol is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
// Last sync with hexfet new_protocols/flysky_a7105.c dated 2015-09-28
|
||||
|
||||
#ifdef AFHDS2A_A7105_INO
|
||||
|
||||
#define AFHDS2A_TXPACKET_SIZE 38
|
||||
#define AFHDS2A_RXPACKET_SIZE 37
|
||||
#define AFHDS2A_NUMFREQ 16
|
||||
|
||||
enum{
|
||||
AFHDS2A_PACKET_STICKS,
|
||||
AFHDS2A_PACKET_SETTINGS,
|
||||
AFHDS2A_PACKET_FAILSAFE,
|
||||
};
|
||||
|
||||
enum{
|
||||
AFHDS2A_BIND1,
|
||||
AFHDS2A_BIND2,
|
||||
AFHDS2A_BIND3,
|
||||
AFHDS2A_BIND4,
|
||||
AFHDS2A_DATA,
|
||||
};
|
||||
|
||||
static void AFHDS2A_calc_channels()
|
||||
{
|
||||
uint8_t idx = 0;
|
||||
uint32_t rnd = MProtocol_id;
|
||||
while (idx < AFHDS2A_NUMFREQ)
|
||||
{
|
||||
uint8_t i;
|
||||
uint8_t count_1_42 = 0, count_43_85 = 0, count_86_128 = 0, count_129_168 = 0;
|
||||
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
|
||||
|
||||
uint8_t next_ch = ((rnd >> (idx%32)) % 0xa8) + 1;
|
||||
// Keep the distance 2 between the channels - either odd or even
|
||||
if (((next_ch ^ MProtocol_id) & 0x01 )== 0)
|
||||
continue;
|
||||
// Check that it's not duplicate and spread uniformly
|
||||
for (i = 0; i < idx; i++)
|
||||
{
|
||||
if(hopping_frequency[i] == next_ch)
|
||||
break;
|
||||
if(hopping_frequency[i] <= 42)
|
||||
count_1_42++;
|
||||
else if (hopping_frequency[i] <= 85)
|
||||
count_43_85++;
|
||||
else if (hopping_frequency[i] <= 128)
|
||||
count_86_128++;
|
||||
else
|
||||
count_129_168++;
|
||||
}
|
||||
if (i != idx)
|
||||
continue;
|
||||
if ((next_ch <= 42 && count_1_42 < 5)
|
||||
||(next_ch >= 43 && next_ch <= 85 && count_43_85 < 5)
|
||||
||(next_ch >= 86 && next_ch <=128 && count_86_128 < 5)
|
||||
||(next_ch >= 129 && count_129_168 < 5))
|
||||
hopping_frequency[idx++] = next_ch;
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(TELEMETRY)
|
||||
// telemetry sensors ID
|
||||
enum{
|
||||
AFHDS2A_SENSOR_RX_VOLTAGE = 0x00,
|
||||
AFHDS2A_SENSOR_RX_ERR_RATE = 0xfe,
|
||||
AFHDS2A_SENSOR_RX_RSSI = 0xfc,
|
||||
AFHDS2A_SENSOR_RX_NOISE = 0xfb,
|
||||
AFHDS2A_SENSOR_RX_SNR = 0xfa,
|
||||
};
|
||||
|
||||
static void AFHDS2A_update_telemetry()
|
||||
{
|
||||
// AA | TXID | rx_id | sensor id | sensor # | value 16 bit big endian | sensor id ......
|
||||
// max 7 sensors per packet
|
||||
#if defined AFHDS2A_TELEMETRY
|
||||
if (option & 0x80) {
|
||||
// forward telemetry to TX, skip rx and tx id to save space
|
||||
pkt[0]= TX_RSSI;
|
||||
for(int i=9;i < AFHDS2A_RXPACKET_SIZE; i++)
|
||||
pkt[i-8]=packet[i];
|
||||
|
||||
telemetry_link=2;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
for(uint8_t sensor=0; sensor<7; sensor++)
|
||||
{
|
||||
uint8_t index = 9+(4*sensor);
|
||||
switch(packet[index])
|
||||
{
|
||||
case AFHDS2A_SENSOR_RX_VOLTAGE:
|
||||
v_lipo = packet[index+3]<<8 | packet[index+2];
|
||||
telemetry_link=1;
|
||||
break;
|
||||
/*case AFHDS2A_SENSOR_RX_ERR_RATE:
|
||||
// packet[index+2];
|
||||
break;*/
|
||||
case AFHDS2A_SENSOR_RX_RSSI:
|
||||
RSSI_dBm = -packet[index+2];
|
||||
break;
|
||||
case 0xff:
|
||||
return;
|
||||
/*default:
|
||||
// unknown sensor ID
|
||||
break;*/
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void AFHDS2A_build_bind_packet()
|
||||
{
|
||||
uint8_t ch;
|
||||
memcpy( &packet[1], rx_tx_addr, 4);
|
||||
memset( &packet[5], 0xff, 4);
|
||||
packet[10]= 0x00;
|
||||
for(ch=0; ch<AFHDS2A_NUMFREQ; ch++)
|
||||
packet[11+ch] = hopping_frequency[ch];
|
||||
memset( &packet[27], 0xff, 10);
|
||||
packet[37] = 0x00;
|
||||
switch(phase)
|
||||
{
|
||||
case AFHDS2A_BIND1:
|
||||
packet[0] = 0xbb;
|
||||
packet[9] = 0x01;
|
||||
break;
|
||||
case AFHDS2A_BIND2:
|
||||
case AFHDS2A_BIND3:
|
||||
case AFHDS2A_BIND4:
|
||||
packet[0] = 0xbc;
|
||||
if(phase == AFHDS2A_BIND4)
|
||||
{
|
||||
memcpy( &packet[5], &rx_id, 4);
|
||||
memset( &packet[11], 0xff, 16);
|
||||
}
|
||||
packet[9] = phase-1;
|
||||
if(packet[9] > 0x02)
|
||||
packet[9] = 0x02;
|
||||
packet[27]= 0x01;
|
||||
packet[28]= 0x80;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void AFHDS2A_build_packet(uint8_t type)
|
||||
{
|
||||
memcpy( &packet[1], rx_tx_addr, 4);
|
||||
memcpy( &packet[5], rx_id, 4);
|
||||
switch(type)
|
||||
{
|
||||
case AFHDS2A_PACKET_STICKS:
|
||||
packet[0] = 0x58;
|
||||
for(uint8_t ch=0; ch<14; ch++)
|
||||
{
|
||||
packet[9 + ch*2] = Servo_data[CH_AETR[ch]]&0xFF;
|
||||
packet[10 + ch*2] = (Servo_data[CH_AETR[ch]]>>8)&0xFF;
|
||||
}
|
||||
break;
|
||||
case AFHDS2A_PACKET_FAILSAFE:
|
||||
packet[0] = 0x56;
|
||||
for(uint8_t ch=0; ch<14; ch++)
|
||||
{
|
||||
/*if((Model.limits[ch].flags & CH_FAILSAFE_EN))
|
||||
{
|
||||
packet[9 + ch*2] = Servo_data[CH_AETR[ch]] & 0xff;
|
||||
packet[10+ ch*2] = (Servo_data[CH_AETR[ch]] >> 8) & 0xff;
|
||||
}
|
||||
else*/
|
||||
{
|
||||
packet[9 + ch*2] = 0xff;
|
||||
packet[10+ ch*2] = 0xff;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case AFHDS2A_PACKET_SETTINGS:
|
||||
packet[0] = 0xaa;
|
||||
packet[9] = 0xfd;
|
||||
packet[10]= 0xff;
|
||||
uint16_t val_hz=5*(option & 0x7f)+50; // option value should be between 0 and 70 which gives a value between 50 and 400Hz
|
||||
if(val_hz<50 || val_hz>400) val_hz=50; // default is 50Hz
|
||||
packet[11]= val_hz;
|
||||
packet[12]= val_hz >> 8;
|
||||
if(sub_protocol == PPM_IBUS || sub_protocol == PPM_SBUS)
|
||||
packet[13] = 0x01; // PPM output enabled
|
||||
else
|
||||
packet[13] = 0x00;
|
||||
packet[14]= 0x00;
|
||||
for(uint8_t i=15; i<37; i++)
|
||||
packet[i] = 0xff;
|
||||
packet[18] = 0x05; // ?
|
||||
packet[19] = 0xdc; // ?
|
||||
packet[20] = 0x05; // ?
|
||||
if(sub_protocol == PWM_SBUS || sub_protocol == PPM_SBUS)
|
||||
packet[21] = 0xdd; // SBUS output enabled
|
||||
else
|
||||
packet[21] = 0xde; // IBUS
|
||||
break;
|
||||
}
|
||||
packet[37] = 0x00;
|
||||
}
|
||||
|
||||
#define AFHDS2A_WAIT_WRITE 0x80
|
||||
uint16_t ReadAFHDS2A()
|
||||
{
|
||||
static uint8_t packet_type = AFHDS2A_PACKET_STICKS;
|
||||
static uint16_t packet_counter=0;
|
||||
uint8_t data_rx;
|
||||
uint16_t start;
|
||||
switch(phase)
|
||||
{
|
||||
case AFHDS2A_BIND1:
|
||||
case AFHDS2A_BIND2:
|
||||
case AFHDS2A_BIND3:
|
||||
AFHDS2A_build_bind_packet();
|
||||
A7105_WriteData(AFHDS2A_TXPACKET_SIZE, packet_count%2 ? 0x0d : 0x8c);
|
||||
if(!(A7105_ReadReg(A7105_00_MODE) & (1<<5 | 1<<6)))
|
||||
{ // FECF+CRCF Ok
|
||||
A7105_ReadData(AFHDS2A_RXPACKET_SIZE);
|
||||
if(packet[0] == 0xbc && packet[9] == 0x01)
|
||||
{
|
||||
uint8_t temp=50+RX_num*4;
|
||||
uint8_t i;
|
||||
for(i=0; i<4; i++)
|
||||
{
|
||||
rx_id[i] = packet[5+i];
|
||||
eeprom_write_byte((EE_ADDR)(temp+i),rx_id[i]);
|
||||
}
|
||||
phase = AFHDS2A_BIND4;
|
||||
packet_count++;
|
||||
return 3850;
|
||||
}
|
||||
}
|
||||
packet_count++;
|
||||
phase |= AFHDS2A_WAIT_WRITE;
|
||||
return 1700;
|
||||
case AFHDS2A_BIND1|AFHDS2A_WAIT_WRITE:
|
||||
case AFHDS2A_BIND2|AFHDS2A_WAIT_WRITE:
|
||||
case AFHDS2A_BIND3|AFHDS2A_WAIT_WRITE:
|
||||
//Wait for TX completion
|
||||
start=micros();
|
||||
while ((uint16_t)micros()-start < 700) // Wait max 700µs, using serial+telemetry exit in about 120µs
|
||||
if(!(A7105_ReadReg(A7105_00_MODE) & 0x01))
|
||||
break;
|
||||
A7105_SetTxRxMode(RX_EN);
|
||||
A7105_Strobe(A7105_RX);
|
||||
phase &= ~AFHDS2A_WAIT_WRITE;
|
||||
phase++;
|
||||
if(phase > AFHDS2A_BIND3)
|
||||
phase = AFHDS2A_BIND1;
|
||||
return 2150;
|
||||
case AFHDS2A_BIND4:
|
||||
AFHDS2A_build_bind_packet();
|
||||
A7105_WriteData(AFHDS2A_TXPACKET_SIZE, packet_count%2 ? 0x0d : 0x8c);
|
||||
packet_count++;
|
||||
bind_phase++;
|
||||
if(bind_phase>=4)
|
||||
{
|
||||
packet_counter=0;
|
||||
packet_type = AFHDS2A_PACKET_STICKS;
|
||||
hopping_frequency_no=1;
|
||||
phase = AFHDS2A_DATA;
|
||||
BIND_DONE;
|
||||
}
|
||||
return 3850;
|
||||
case AFHDS2A_DATA:
|
||||
AFHDS2A_build_packet(packet_type);
|
||||
if((A7105_ReadReg(A7105_00_MODE) & 0x01)) // Check if something has been received...
|
||||
data_rx=0;
|
||||
else
|
||||
data_rx=1; // Yes
|
||||
A7105_WriteData(AFHDS2A_TXPACKET_SIZE, hopping_frequency[hopping_frequency_no++]);
|
||||
if(hopping_frequency_no >= AFHDS2A_NUMFREQ)
|
||||
hopping_frequency_no = 0;
|
||||
if(!(packet_counter % 1313))
|
||||
packet_type = AFHDS2A_PACKET_SETTINGS;
|
||||
else if(!(packet_counter % 1569))
|
||||
packet_type = AFHDS2A_PACKET_FAILSAFE;
|
||||
else
|
||||
packet_type = AFHDS2A_PACKET_STICKS; // todo : check for settings changes
|
||||
if(!(A7105_ReadReg(A7105_00_MODE) & (1<<5 | 1<<6)) && data_rx==1)
|
||||
{ // RX+FECF+CRCF Ok
|
||||
A7105_ReadData(AFHDS2A_RXPACKET_SIZE);
|
||||
if(packet[0] == 0xaa)
|
||||
{
|
||||
if(packet[9] == 0xfc)
|
||||
packet_type=AFHDS2A_PACKET_SETTINGS; // RX is asking for settings
|
||||
#if defined(TELEMETRY)
|
||||
else
|
||||
{
|
||||
// Read TX RSSI
|
||||
int16_t temp=256-(A7105_ReadReg(A7105_1D_RSSI_THOLD)*8)/5; // value from A7105 is between 8 for maximum signal strength to 160 or less
|
||||
if(temp<0) temp=0;
|
||||
else if(temp>255) temp=255;
|
||||
TX_RSSI=temp;
|
||||
AFHDS2A_update_telemetry();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
packet_counter++;
|
||||
phase |= AFHDS2A_WAIT_WRITE;
|
||||
return 1700;
|
||||
case AFHDS2A_DATA|AFHDS2A_WAIT_WRITE:
|
||||
//Wait for TX completion
|
||||
start=micros();
|
||||
while ((uint16_t)micros()-start < 700) // Wait max 700µs, using serial+telemetry exit in about 120µs
|
||||
if(!(A7105_ReadReg(A7105_00_MODE) & 0x01))
|
||||
break;
|
||||
A7105_SetTxRxMode(RX_EN);
|
||||
A7105_Strobe(A7105_RX);
|
||||
phase &= ~AFHDS2A_WAIT_WRITE;
|
||||
return 2150;
|
||||
}
|
||||
return 3850; // never reached, please the compiler
|
||||
}
|
||||
|
||||
uint16_t initAFHDS2A()
|
||||
{
|
||||
A7105_Init();
|
||||
|
||||
AFHDS2A_calc_channels();
|
||||
packet_count = 0;
|
||||
bind_phase = 0;
|
||||
if(IS_AUTOBIND_FLAG_on)
|
||||
phase = AFHDS2A_BIND1;
|
||||
else
|
||||
{
|
||||
phase = AFHDS2A_DATA;
|
||||
//Read RX ID from EEPROM based on RX_num, RX_num must be uniq for each RX
|
||||
uint8_t temp=50+RX_num*4;
|
||||
for(uint8_t i=0;i<4;i++)
|
||||
rx_id[i]=eeprom_read_byte((EE_ADDR)(temp+i));
|
||||
}
|
||||
hopping_frequency_no = 0;
|
||||
return 50000;
|
||||
}
|
||||
#endif
|
20
Multiprotocol/Build_orangetx.cmd
Normal file
20
Multiprotocol/Build_orangetx.cmd
Normal file
@ -0,0 +1,20 @@
|
||||
@echo off
|
||||
if "%AVR32_HOME%"=="" (
|
||||
echo.
|
||||
echo You must install winavr to compile Multi for OrangeTX: https://sourceforge.net/projects/winavr/
|
||||
echo.
|
||||
pause
|
||||
exit /b
|
||||
)
|
||||
if exist MultiOrange.cpp.orangetx ren *.orangetx *.
|
||||
if exist .dep (make clean)
|
||||
md .dep
|
||||
make
|
||||
if exist MultiOrange.hex (
|
||||
objcopy -I ihex MultiOrange.hex -O binary MultiOrange.bin
|
||||
echo.
|
||||
echo Compilation OK.
|
||||
echo Use MultiOrange.hex to program your OrangeTX module.
|
||||
echo.
|
||||
)
|
||||
pause
|
@ -126,8 +126,8 @@ static void __attribute__((unused)) CG023_send_packet(uint8_t bind)
|
||||
| GET_FLAG(Servo_AUX4,H8_3D_FLAG_RTH); // 180/360 flip mode on H8 3D
|
||||
packet[18] = GET_FLAG(Servo_AUX5,H8_3D_FLAG_CALIBRATE)
|
||||
| GET_FLAG(Servo_AUX5,H8_3D_FLAG_CALIBRATE2)
|
||||
| GET_FLAG(Servo_AUX6, H8_3D_FLAG_SNAPSHOT)
|
||||
| GET_FLAG(Servo_AUX7, H8_3D_FLAG_VIDEO);
|
||||
| GET_FLAG(Servo_AUX6,H8_3D_FLAG_SNAPSHOT)
|
||||
| GET_FLAG(Servo_AUX7,H8_3D_FLAG_VIDEO);
|
||||
}
|
||||
uint8_t sum = packet[9];
|
||||
for (uint8_t i=10; i < H8_3D_PACKET_SIZE-1; i++)
|
||||
|
@ -184,7 +184,7 @@ uint16_t initFlySky()
|
||||
uint8_t chanoffset;
|
||||
uint8_t temp;
|
||||
|
||||
A7105_Init(INIT_FLYSKY); //flysky_init();
|
||||
A7105_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;
|
||||
|
@ -1,314 +0,0 @@
|
||||
// adaptation de https://github.com/goebish/deviation/blob/c5dd9fcc1441fc05fe9effa4c378886aeb3938d4/src/protocol/flysky_afhds2a_a7105.c
|
||||
#ifdef AFHDS2A_A7105_INO
|
||||
#define EEPROMadress 0 // rx ID 32bit
|
||||
#define SERVO_HZ 50 //Frequency's servo 0=50 1=400 2=5
|
||||
|
||||
#define TXPACKET_SIZE 38
|
||||
#define RXPACKET_SIZE 37
|
||||
#define NUMFREQ 16
|
||||
|
||||
static uint8_t txid[4];
|
||||
static uint8_t rxid[4];
|
||||
static uint8_t packet_type;
|
||||
static uint8_t bind_reply;
|
||||
|
||||
|
||||
enum{
|
||||
PACKET_STICKS,
|
||||
PACKET_SETTINGS,
|
||||
PACKET_FAILSAFE,
|
||||
};
|
||||
|
||||
enum{
|
||||
BIND1,
|
||||
BIND2,
|
||||
BIND3,
|
||||
BIND4,
|
||||
DATA1,
|
||||
};
|
||||
enum {
|
||||
PWM_IBUS = 0,
|
||||
PPM_IBUS,
|
||||
PWM_SBUS,
|
||||
PPM_SBUS
|
||||
};
|
||||
|
||||
|
||||
static void build_packet(uint8_t type) {
|
||||
switch(type) {
|
||||
case PACKET_STICKS:
|
||||
packet[0] = 0x58;
|
||||
memcpy( &packet[1], txid, 4);
|
||||
memcpy( &packet[5], rxid, 4);
|
||||
for(uint8_t ch=0; ch<14; ch++) {
|
||||
packet[9 + ch*2] = Servo_data[CH_AETR[ch]]&0xFF;
|
||||
packet[10 + ch*2] = (Servo_data[CH_AETR[ch]]>>8)&0xFF;
|
||||
}
|
||||
packet[37] = 0x00;
|
||||
break;
|
||||
|
||||
case PACKET_FAILSAFE:
|
||||
packet[0] = 0x56;
|
||||
memcpy( &packet[1], txid, 4);
|
||||
memcpy( &packet[5], rxid, 4);
|
||||
for(uint8_t ch=0; ch<14; ch++) {
|
||||
if(ch==0) {
|
||||
// if(ch < Model.num_channels && (Model.limits[ch].flags & CH_FAILSAFE_EN)) {
|
||||
packet[9 + ch*2] = Servo_data[AUX11] & 0xff;
|
||||
packet[10+ ch*2] = (Servo_data[AUX11] >> 8) & 0xff;
|
||||
}
|
||||
else {
|
||||
packet[9 + ch*2] = 0xff;
|
||||
packet[10+ ch*2] = 0xff;
|
||||
}
|
||||
}
|
||||
packet[37] = 0x00;
|
||||
break;
|
||||
|
||||
case PACKET_SETTINGS:
|
||||
packet[0] = 0xaa;
|
||||
memcpy( &packet[1], txid, 4);
|
||||
memcpy( &packet[5], rxid, 4);
|
||||
packet[9] = 0xfd;
|
||||
packet[10]= 0xff;
|
||||
packet[11]= SERVO_HZ & 0xff;
|
||||
packet[12]= (SERVO_HZ >> 8) & 0xff;
|
||||
if(option == PPM_IBUS || option == PPM_SBUS)
|
||||
packet[13] = 0x01; // PPM output enabled
|
||||
else
|
||||
packet[13] = 0x00;
|
||||
packet[14]= 0x00;
|
||||
for(uint8_t i=15; i<37; i++)
|
||||
packet[i] = 0xff;
|
||||
packet[18] = 0x05; // ?
|
||||
packet[19] = 0xdc; // ?
|
||||
packet[20] = 0x05; // ?
|
||||
if(option == PWM_SBUS || option == PPM_SBUS)
|
||||
packet[21] = 0xdd; // SBUS output enabled
|
||||
else
|
||||
packet[21] = 0xde;
|
||||
packet[37] = 0x00;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// telemetry sensors ID
|
||||
enum{
|
||||
SENSOR_RX_VOLTAGE = 0x00,
|
||||
SENSOR_RX_ERR_RATE = 0xfe,
|
||||
SENSOR_RX_RSSI = 0xfc,
|
||||
SENSOR_RX_NOISE = 0xfb,
|
||||
SENSOR_RX_SNR = 0xfa,
|
||||
};
|
||||
|
||||
static void update_telemetry() {
|
||||
// AA | TXID | RXID | sensor id | sensor # | value 16 bit big endian | sensor id ......
|
||||
// max 7 sensors per packet
|
||||
|
||||
for(uint8_t sensor=0; sensor<7; sensor++) {
|
||||
uint8_t index = 9+(4*sensor);
|
||||
switch(packet[index]) {
|
||||
case SENSOR_RX_VOLTAGE:
|
||||
v_lipo = packet[index+3]<<8 | packet[index+2];
|
||||
telemetry_link=1;
|
||||
break;
|
||||
case SENSOR_RX_ERR_RATE:
|
||||
// packet[index+2];
|
||||
break;
|
||||
case SENSOR_RX_RSSI:
|
||||
RSSI_dBm = -packet[index+2];
|
||||
break;
|
||||
case 0xff:
|
||||
return;
|
||||
default:
|
||||
// unknown sensor ID
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void afhds2a_build_bind_packet() {
|
||||
uint8_t ch;
|
||||
memcpy( &packet[1], txid, 4);
|
||||
memset( &packet[5], 0xff, 4);
|
||||
packet[10]= 0x00;
|
||||
for(ch=0; ch<16; ch++) {
|
||||
packet[11+ch] = hopping_frequency[ch];
|
||||
}
|
||||
memset( &packet[27], 0xff, 10);
|
||||
packet[37] = 0x00;
|
||||
switch(phase) {
|
||||
case BIND1:
|
||||
packet[0] = 0xbb;
|
||||
packet[9] = 0x01;
|
||||
break;
|
||||
case BIND2:
|
||||
case BIND3:
|
||||
case BIND4:
|
||||
packet[0] = 0xbc;
|
||||
if(phase == BIND4) {
|
||||
memcpy( &packet[5], &rxid, 4);
|
||||
memset( &packet[11], 0xff, 16);
|
||||
}
|
||||
packet[9] = phase-1;
|
||||
if(packet[9] > 0x02)
|
||||
packet[9] = 0x02;
|
||||
packet[27]= 0x01;
|
||||
packet[28]= 0x80;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void calc_afhds_channels() {
|
||||
int idx = 0;
|
||||
uint32_t rnd = MProtocol_id;
|
||||
while (idx < NUMFREQ) {
|
||||
int i;
|
||||
int count_1_42 = 0, count_43_85 = 0, count_86_128 = 0, count_129_168=0;
|
||||
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
|
||||
|
||||
uint8_t next_ch = ((rnd >> (idx%32)) % 0xa8) + 1;
|
||||
// Keep the distance 2 between the channels - either odd or even
|
||||
if (((next_ch ^ MProtocol_id) & 0x01 )== 0)
|
||||
continue;
|
||||
// Check that it's not duplicate and spread uniformly
|
||||
for (i = 0; i < idx; i++) {
|
||||
if(hopping_frequency[i] == next_ch)
|
||||
break;
|
||||
if(hopping_frequency[i] <= 42)
|
||||
count_1_42++;
|
||||
else if (hopping_frequency[i] <= 85)
|
||||
count_43_85++;
|
||||
else if (hopping_frequency[i] <= 128)
|
||||
count_86_128++;
|
||||
else
|
||||
count_129_168++;
|
||||
}
|
||||
if (i != idx)
|
||||
continue;
|
||||
if ((next_ch <= 42 && count_1_42 < 5)
|
||||
||(next_ch >= 43 && next_ch <= 85 && count_43_85 < 5)
|
||||
||(next_ch >= 86 && next_ch <=128 && count_86_128 < 5)
|
||||
||(next_ch >= 129 && count_129_168 < 5))
|
||||
{
|
||||
hopping_frequency[idx++] = next_ch;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#define WAIT_WRITE 0x80
|
||||
static uint16_t afhds2a_cb() {
|
||||
switch(phase) {
|
||||
case BIND1:
|
||||
case BIND2:
|
||||
case BIND3:
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
afhds2a_build_bind_packet();
|
||||
A7105_WriteData(38, packet_count%2 ? 0x0d : 0x8c);
|
||||
if(A7105_ReadReg(0) == 0x1b) { // todo: replace with check crc+fec
|
||||
A7105_Strobe(A7105_RST_RDPTR);
|
||||
A7105_ReadData(RXPACKET_SIZE);
|
||||
if(packet[0] == 0xbc) {
|
||||
for(uint8_t i=0; i<4; i++) {
|
||||
rxid[i] = packet[5+i];
|
||||
}
|
||||
eeprom_write_block((const void*)rxid,(EE_ADDR)EEPROMadress,4);
|
||||
if(packet[9] == 0x01)
|
||||
phase = BIND4;
|
||||
}
|
||||
}
|
||||
packet_count++;
|
||||
phase |= WAIT_WRITE;
|
||||
return 1700;
|
||||
case BIND1|WAIT_WRITE:
|
||||
case BIND2|WAIT_WRITE:
|
||||
case BIND3|WAIT_WRITE:
|
||||
A7105_Strobe(A7105_RX);
|
||||
phase &= ~WAIT_WRITE;
|
||||
phase++;
|
||||
if(phase > BIND3)
|
||||
phase = BIND1;
|
||||
return 2150;
|
||||
case BIND4:
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
afhds2a_build_bind_packet();
|
||||
A7105_WriteData(38, packet_count%2 ? 0x0d : 0x8c);
|
||||
packet_count++;
|
||||
bind_reply++;
|
||||
if(bind_reply>=4) {
|
||||
packet_count=0;
|
||||
channel=1;
|
||||
phase = DATA1;
|
||||
BIND_DONE;
|
||||
}
|
||||
phase |= WAIT_WRITE;
|
||||
return 1700;
|
||||
case BIND4|WAIT_WRITE:
|
||||
A7105_Strobe(A7105_RX);
|
||||
phase &= ~WAIT_WRITE;
|
||||
return 2150;
|
||||
case DATA1:
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
build_packet(packet_type);
|
||||
A7105_WriteData(38, hopping_frequency[channel++]);
|
||||
if(channel >= 16)
|
||||
channel = 0;
|
||||
if(!(packet_count % 1313))
|
||||
packet_type = PACKET_SETTINGS;
|
||||
else if(!(packet_count % 1569))
|
||||
packet_type = PACKET_FAILSAFE;
|
||||
else
|
||||
packet_type = PACKET_STICKS; // todo : check for settings changes
|
||||
// got some data from RX ?
|
||||
// we've no way to know if RX fifo has been filled
|
||||
// as we can't poll GIO1 or GIO2 to check WTR
|
||||
// we can't check A7105_MASK_TREN either as we know
|
||||
// it's currently in transmit mode.
|
||||
if(!(A7105_ReadReg(0) & (1<<5 | 1<<6))) { // FECF+CRCF Ok
|
||||
A7105_Strobe(A7105_RST_RDPTR);
|
||||
A7105_ReadData(1);
|
||||
if(packet[0] == 0xaa) {
|
||||
A7105_Strobe(A7105_RST_RDPTR);
|
||||
A7105_ReadData(RXPACKET_SIZE);
|
||||
if(packet[9] == 0xfc) { // rx is asking for settings
|
||||
packet_type=PACKET_SETTINGS;
|
||||
}
|
||||
else {
|
||||
update_telemetry();
|
||||
}
|
||||
}
|
||||
}
|
||||
packet_count++;
|
||||
phase |= WAIT_WRITE;
|
||||
return 1700;
|
||||
case DATA1|WAIT_WRITE:
|
||||
phase &= ~WAIT_WRITE;
|
||||
A7105_Strobe(A7105_RX);
|
||||
return 2150;
|
||||
}
|
||||
return 3850; // never reached, please the compiler
|
||||
}
|
||||
|
||||
static uint16_t AFHDS2A_setup()
|
||||
{
|
||||
A7105_Init(INIT_FLYSKY_AFHDS2A); //flysky_init();
|
||||
for (uint8_t i = 0; i < 4; ++i) {
|
||||
txid[i] = rx_tx_addr[i];
|
||||
}
|
||||
|
||||
calc_afhds_channels();
|
||||
packet_type = PACKET_STICKS;
|
||||
packet_count = 0;
|
||||
bind_reply = 0;
|
||||
if(IS_AUTOBIND_FLAG_on) {
|
||||
phase = BIND1;
|
||||
BIND_IN_PROGRESS;
|
||||
}
|
||||
else {
|
||||
phase = DATA1;
|
||||
eeprom_read_block((void*)rxid,(EE_ADDR)EEPROMadress,4);
|
||||
}
|
||||
channel = 0;
|
||||
return 50000;
|
||||
}
|
||||
#endif
|
@ -293,7 +293,9 @@ uint16_t ReadFrSkyX()
|
||||
seq_last_sent = 0;
|
||||
seq_last_rcvd = 8;
|
||||
counter=0;
|
||||
telemetry_lost=1;
|
||||
#if defined TELEMETRY
|
||||
telemetry_lost=1;
|
||||
#endif
|
||||
}
|
||||
CC2500_Strobe(CC2500_SFRX); //flush the RXFIFO
|
||||
}
|
||||
|
@ -287,7 +287,6 @@ uint16_t ReadHubsan()
|
||||
case BIND_5:
|
||||
case BIND_7:
|
||||
hubsan_build_bind_packet(phase == BIND_7 ? 9 : (phase == BIND_5 ? 1 : phase + 1 - BIND_1));
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
A7105_WriteData(16, channel);
|
||||
phase |= WAIT_WRITE;
|
||||
return 3000;
|
||||
@ -322,7 +321,7 @@ uint16_t ReadHubsan()
|
||||
phase = BIND_1;
|
||||
return 4500; //No signal, restart binding procedure. 12msec elapsed since last write
|
||||
}
|
||||
A7105_ReadData();
|
||||
A7105_ReadData(16);
|
||||
phase++;
|
||||
if (phase == BIND_5)
|
||||
A7105_WriteID(((uint32_t)packet[2] << 24) | ((uint32_t)packet[3] << 16) | ((uint32_t)packet[4] << 8) | packet[5]);
|
||||
@ -333,7 +332,7 @@ uint16_t ReadHubsan()
|
||||
phase = BIND_7;
|
||||
return 15000; //22.5msec elapsed since last write
|
||||
}
|
||||
A7105_ReadData();
|
||||
A7105_ReadData(16);
|
||||
if(packet[1] == 9 && id_data == ID_NORMAL) {
|
||||
phase = DATA_1;
|
||||
A7105_WriteReg(A7105_1F_CODE_I, 0x0F);
|
||||
@ -355,7 +354,6 @@ uint16_t ReadHubsan()
|
||||
if( phase == DATA_1)
|
||||
A7105_SetPower(); //Keep transmit power in sync
|
||||
hubsan_build_packet();
|
||||
A7105_Strobe(A7105_STANDBY);
|
||||
u8 ch;
|
||||
if((phase == DATA_5 && id_data == ID_NORMAL) && sub_protocol == FORMAT_H107) {
|
||||
ch = channel + 0x23;
|
||||
@ -391,7 +389,7 @@ uint16_t ReadHubsan()
|
||||
{
|
||||
if( !(A7105_ReadReg(A7105_00_MODE) & 0x01))
|
||||
{ // data received
|
||||
A7105_ReadData();
|
||||
A7105_ReadData(16);
|
||||
if( hubsan_check_integrity() )
|
||||
{
|
||||
v_lipo=packet[13];// hubsan lipo voltage 8bits the real value is h_lipo/10(0x2A=42 -> 4.2V)
|
||||
@ -399,9 +397,10 @@ uint16_t ReadHubsan()
|
||||
}
|
||||
A7105_Strobe(A7105_RX);
|
||||
// Read TX RSSI
|
||||
RSSI_dBm=256-(A7105_ReadReg(A7105_1D_RSSI_THOLD)*8)/5; // value from A7105 is between 8 for maximum signal strength to 160 or less
|
||||
if(RSSI_dBm<0) RSSI_dBm=0;
|
||||
else if(RSSI_dBm>255) RSSI_dBm=255;
|
||||
int16_t temp=256-(A7105_ReadReg(A7105_1D_RSSI_THOLD)*8)/5; // value from A7105 is between 8 for maximum signal strength to 160 or less
|
||||
if(temp<0) temp=0;
|
||||
else if(temp>255) temp=255;
|
||||
TX_RSSI=temp;
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -420,7 +419,7 @@ uint16_t ReadHubsan()
|
||||
|
||||
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();
|
||||
A7105_Init();
|
||||
|
||||
sessionid = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16);
|
||||
channel = allowed_ch[random(0xfefefefe) % sizeof(allowed_ch)];
|
||||
|
@ -55,10 +55,10 @@ static void __attribute__((unused)) j6pro_build_data_packet()
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t upperbits = 0;
|
||||
uint16_t value;
|
||||
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);
|
||||
@ -76,16 +76,16 @@ static void __attribute__((unused)) j6pro_cyrf_init()
|
||||
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_WriteRegister(CYRF_0F_XACT_CFG, 0x24);
|
||||
//CYRF_SetPower(0x05);
|
||||
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
|
||||
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_WritePreamble(0x333302);
|
||||
|
||||
CYRF_GetMfgData(cyrfmfg_id);
|
||||
//Model match
|
||||
@ -94,36 +94,28 @@ static void __attribute__((unused)) j6pro_cyrf_init()
|
||||
|
||||
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);
|
||||
/* Use when binding */
|
||||
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, 0x80);
|
||||
//CYRF_ConfigRFChannel(0x52);
|
||||
//CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x24);
|
||||
//CYRF_WriteRegister(CYRF_02_TX_CTRL, 0x40);
|
||||
j6pro_build_bind_packet();
|
||||
}
|
||||
|
||||
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);
|
||||
/* Use when already bound */
|
||||
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, 0x24);
|
||||
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sop_idx]);
|
||||
CYRF_ConfigCRCSeed(crc);
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) j6pro_set_radio_channels()
|
||||
@ -136,10 +128,10 @@ static void __attribute__((unused)) j6pro_set_radio_channels()
|
||||
|
||||
uint16_t ReadJ6Pro()
|
||||
{
|
||||
uint32_t start;
|
||||
uint32_t start;
|
||||
|
||||
switch(phase)
|
||||
{
|
||||
{
|
||||
case J6PRO_BIND:
|
||||
cyrf_bindinit();
|
||||
phase = J6PRO_BIND_01;
|
||||
@ -147,9 +139,7 @@ uint16_t ReadJ6Pro()
|
||||
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_WriteRegister(CYRF_0F_XACT_CFG, 0x24);
|
||||
CYRF_WriteDataPacketLen(packet, 0x09);
|
||||
phase = J6PRO_BIND_03_START;
|
||||
return 3000; //3msec
|
||||
@ -160,8 +150,8 @@ uint16_t ReadJ6Pro()
|
||||
break;
|
||||
CYRF_ConfigRFChannel(0x53);
|
||||
CYRF_SetTxRxMode(RX_EN);
|
||||
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
|
||||
//CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
|
||||
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x80);
|
||||
phase = J6PRO_BIND_03_CHECK;
|
||||
return 30000; //30msec
|
||||
case J6PRO_BIND_03_CHECK:
|
||||
@ -201,7 +191,7 @@ uint16_t ReadJ6Pro()
|
||||
case J6PRO_BIND_05_4:
|
||||
case J6PRO_BIND_05_5:
|
||||
case J6PRO_BIND_05_6:
|
||||
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
|
||||
//CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x24);
|
||||
CYRF_WriteDataPacketLen(packet, 0x0f);
|
||||
phase = phase + 1;
|
||||
return 4600; //4.6msec
|
||||
@ -212,7 +202,7 @@ uint16_t ReadJ6Pro()
|
||||
phase = J6PRO_CHAN_1;
|
||||
case J6PRO_CHAN_1:
|
||||
//Keep transmit power updated
|
||||
CYRF_SetPower(0);
|
||||
CYRF_SetPower(0x28);
|
||||
j6pro_build_data_packet();
|
||||
//return 3400;
|
||||
case J6PRO_CHAN_2:
|
||||
@ -237,12 +227,10 @@ uint16_t initJ6Pro()
|
||||
{
|
||||
j6pro_cyrf_init();
|
||||
|
||||
if(IS_AUTOBIND_FLAG_on) {
|
||||
if(IS_AUTOBIND_FLAG_on)
|
||||
phase = J6PRO_BIND;
|
||||
}
|
||||
else {
|
||||
else
|
||||
phase = J6PRO_CHANSEL;
|
||||
}
|
||||
return 2400;
|
||||
}
|
||||
|
||||
|
@ -27,14 +27,14 @@
|
||||
#define MJXQ_ADDRESS_LENGTH 5
|
||||
|
||||
// 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} };
|
||||
const uint8_t PROGMEM MJXQ_map_rfchan[][4] = {
|
||||
{0x0A, 0x46, 0x3A, 0x42},
|
||||
{0x0A, 0x3C, 0x36, 0x3F},
|
||||
{0x0A, 0x43, 0x36, 0x3F} };
|
||||
|
||||
|
||||
#define MJXQ_PAN_TILT_COUNT 16 // for H26D - match stock tx timing
|
||||
@ -90,9 +90,11 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
|
||||
// Servo_AUX5 HEADLESS
|
||||
// Servo_AUX6 RTH
|
||||
// Servo_AUX7 AUTOFLIP // X800, X600
|
||||
// Servo_AUX8 ARM // H26WH
|
||||
switch(sub_protocol)
|
||||
{
|
||||
case H26D:
|
||||
case H26WH:
|
||||
packet[10]=MJXQ_pan_tilt_value();
|
||||
// fall through on purpose - no break
|
||||
case WLH08:
|
||||
@ -107,6 +109,11 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
|
||||
| GET_FLAG(Servo_AUX4, 0x10) //VIDEO
|
||||
| GET_FLAG(!Servo_AUX2, 0x20); // air/ground mode
|
||||
}
|
||||
if (sub_protocol == H26WH) {
|
||||
packet[10] &= ~0x40;
|
||||
packet[14] &= ~0x24;
|
||||
packet[14] |= GET_FLAG(Servo_AUX2, 0x04);
|
||||
}
|
||||
break;
|
||||
case X600:
|
||||
packet[10] = GET_FLAG(!Servo_AUX2, 0x02); //LED
|
||||
@ -139,10 +146,15 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
|
||||
packet[15] = sum;
|
||||
|
||||
// Power on, TX mode, 2byte CRC
|
||||
if (sub_protocol == H26D)
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
else
|
||||
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
|
||||
switch (Model.proto_opts[PROTOOPTS_FORMAT]) {
|
||||
case H26D:
|
||||
case H26WH:
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
break;
|
||||
default:
|
||||
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
|
||||
break;
|
||||
}
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++ / 2]);
|
||||
hopping_frequency_no %= 2 * MJXQ_RF_NUM_CHANNELS; // channels repeated
|
||||
@ -150,10 +162,15 @@ static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
|
||||
if (sub_protocol == H26D)
|
||||
NRF24L01_WritePayload(packet, MJXQ_PACKET_SIZE);
|
||||
else
|
||||
XN297_WritePayload(packet, MJXQ_PACKET_SIZE);
|
||||
switch (Model.proto_opts[PROTOOPTS_FORMAT]) {
|
||||
case H26D:
|
||||
case H26WH:
|
||||
NRF24L01_WritePayload(packet, MJXQ_PACKET_SIZE);
|
||||
break;
|
||||
default:
|
||||
XN297_WritePayload(packet, MJXQ_PACKET_SIZE);
|
||||
break;
|
||||
}
|
||||
|
||||
NRF24L01_SetPower();
|
||||
}
|
||||
@ -162,10 +179,13 @@ static void __attribute__((unused)) MJXQ_init()
|
||||
{
|
||||
uint8_t addr[MJXQ_ADDRESS_LENGTH];
|
||||
memcpy(addr, "\x6d\x6a\x77\x77\x77", MJXQ_ADDRESS_LENGTH);
|
||||
NRF24L01_Initialize();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
|
||||
if (sub_protocol == WLH08)
|
||||
memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS);
|
||||
else
|
||||
if (sub_protocol == H26D || sub_protocol == E010)
|
||||
if (sub_protocol == H26D || sub_protocol == H26WH || sub_protocol == E010)
|
||||
memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS);
|
||||
else
|
||||
{
|
||||
@ -174,11 +194,11 @@ static void __attribute__((unused)) MJXQ_init()
|
||||
}
|
||||
|
||||
|
||||
NRF24L01_Initialize();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
|
||||
if (sub_protocol == H26D)
|
||||
if (sub_protocol == H26D || sub_protocol == H26WH)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, addr, MJXQ_ADDRESS_LENGTH);
|
||||
}
|
||||
else
|
||||
XN297_SetTXAddr(addr, MJXQ_ADDRESS_LENGTH);
|
||||
|
||||
@ -203,20 +223,25 @@ static void __attribute__((unused)) MJXQ_init2()
|
||||
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] );
|
||||
hopping_frequency[i]=pgm_read_byte_near( &MJXQ_map_rfchan[rx_tx_addr[3]%3][i] );
|
||||
}
|
||||
|
||||
static void __attribute__((unused)) MJXQ_initialize_txid()
|
||||
{
|
||||
rx_tx_addr[0]&=0xF8;
|
||||
if (sub_protocol == E010)
|
||||
rx_tx_addr[2]=rx_tx_addr[3]; // Make use of RX_Num
|
||||
if (sub_protocol == H26WH)
|
||||
{
|
||||
memcpy(txid, "\xa4\x03\x00", sizeof(txid));
|
||||
}
|
||||
else if (sub_protocol == E010)
|
||||
{
|
||||
rx_tx_addr[1]=(rx_tx_addr[1]&0xF0)|0x0C;
|
||||
rx_tx_addr[2]&=0xF0;
|
||||
rx_tx_addr[2]<<=4; // Make use of RX_Num
|
||||
}
|
||||
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] );
|
||||
rx_tx_addr[i]=pgm_read_byte_near( &MJXQ_map_txid[rx_tx_addr[3]%3][i] );
|
||||
}
|
||||
|
||||
uint16_t MJXQ_callback()
|
||||
|
@ -69,6 +69,7 @@ uint16_t servo_max_100,servo_min_100,servo_max_125,servo_min_125;
|
||||
// Protocol variables
|
||||
uint8_t cyrfmfg_id[6];//for dsm2 and devo
|
||||
uint8_t rx_tx_addr[5];
|
||||
uint8_t rx_id[4];
|
||||
uint8_t phase;
|
||||
uint16_t bind_counter;
|
||||
uint8_t bind_phase;
|
||||
@ -129,7 +130,7 @@ volatile uint8_t rx_ok_buff[RXBUFFER_SIZE];
|
||||
volatile uint8_t discard_frame = 0;
|
||||
|
||||
// Telemetry
|
||||
#define MAX_PKT 27
|
||||
#define MAX_PKT 29
|
||||
uint8_t pkt[MAX_PKT];//telemetry receiving packets
|
||||
#if defined(TELEMETRY)
|
||||
#ifdef INVERT_TELEMETRY
|
||||
@ -149,6 +150,7 @@ uint8_t pkt[MAX_PKT];//telemetry receiving packets
|
||||
#endif // BASH_SERIAL
|
||||
uint8_t v_lipo;
|
||||
int16_t RSSI_dBm;
|
||||
uint8_t TX_RSSI;
|
||||
uint8_t telemetry_link=0;
|
||||
uint8_t telemetry_counter=0;
|
||||
uint8_t telemetry_lost;
|
||||
@ -479,7 +481,7 @@ void Update_All()
|
||||
#endif //ENABLE_PPM
|
||||
update_led_status();
|
||||
#if defined(TELEMETRY)
|
||||
if((protocol==MODE_FRSKYD) || (protocol==MODE_HUBSAN) || (protocol==MODE_FRSKYX) || (protocol==MODE_DSM) || (protocol==MODE_AFHDS2A) )
|
||||
if((protocol==MODE_FRSKYD) || (protocol==MODE_HUBSAN) || (protocol==MODE_AFHDS2A) || (protocol==MODE_FRSKYX) || (protocol==MODE_DSM) )
|
||||
TelemetryUpdate();
|
||||
#endif
|
||||
}
|
||||
@ -491,7 +493,7 @@ static void update_aux_flags(void)
|
||||
for(uint8_t i=0;i<8;i++)
|
||||
if(Servo_data[AUX1+i]>PPM_SWITCH)
|
||||
Servo_AUX|=1<<i;
|
||||
if(Servo_data[AUX10]>PPM_SWITCH && !( (cur_protocol[0]&0x1F)==MODE_FRSKYD || (cur_protocol[0]&0x1F)==MODE_DSM || (cur_protocol[0]&0x1F)==MODE_AFHDS2A ) ) { CHANGE_PROTOCOL_FLAG_on; } // Rebind voie
|
||||
if(Servo_data[SWITCH_RESET]>PPM_SWITCH && !( (cur_protocol[0]&0x1F)==MODE_FRSKYD || (cur_protocol[0]&0x1F)==MODE_DSM || (cur_protocol[0]&0x1F)==MODE_AFHDS2A ) ) { CHANGE_PROTOCOL_FLAG_on; } // Rebind voie
|
||||
if(IS_CHANGE_PROTOCOL_FLAG_on)
|
||||
{ // Protocol needs to be changed
|
||||
LED_off; //led off during protocol init
|
||||
@ -529,13 +531,16 @@ static void update_led_status(void)
|
||||
|
||||
inline void tx_pause()
|
||||
{
|
||||
#ifndef STM32_BOARD
|
||||
#ifdef TELEMETRY
|
||||
#ifdef ORANGE_TX
|
||||
USARTC0.CTRLA &= ~0x03 ; // Pause telemetry by disabling transmitter interrupt
|
||||
#else
|
||||
#ifndef BASH_SERIAL
|
||||
UCSR0B &= ~_BV(UDRIE0); // Pause telemetry by disabling transmitter interrupt
|
||||
#ifdef TELEMETRY
|
||||
// Pause telemetry by disabling transmitter interrupt
|
||||
#ifdef ORANGE_TX
|
||||
USARTC0.CTRLA &= ~0x03 ;
|
||||
#else
|
||||
#ifndef BASH_SERIAL
|
||||
#ifdef STM32_BOARD
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_TXEIE;
|
||||
#else
|
||||
UCSR0B &= ~_BV(UDRIE0);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
@ -544,23 +549,26 @@ inline void tx_pause()
|
||||
|
||||
inline void tx_resume()
|
||||
{
|
||||
#ifndef STM32_BOARD
|
||||
#ifdef TELEMETRY
|
||||
if(!IS_TX_PAUSE_on)
|
||||
{
|
||||
#ifdef ORANGE_TX
|
||||
cli() ;
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ; // Resume telemetry by enabling transmitter interrupt
|
||||
sei() ;
|
||||
#else
|
||||
#ifndef BASH_SERIAL
|
||||
UCSR0B |= _BV(UDRIE0); // Resume telemetry by enabling transmitter interrupt
|
||||
#ifdef TELEMETRY
|
||||
// Resume telemetry by enabling transmitter interrupt
|
||||
if(!IS_TX_PAUSE_on)
|
||||
{
|
||||
#ifdef ORANGE_TX
|
||||
cli() ;
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xFC) | 0x01 ;
|
||||
sei() ;
|
||||
#else
|
||||
#ifndef BASH_SERIAL
|
||||
#ifdef STM32_BOARD
|
||||
USART3_BASE->CR1 |= USART_CR1_TXEIE;
|
||||
#else
|
||||
resumeBashSerial() ;
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
UCSR0B |= _BV(UDRIE0);
|
||||
#endif
|
||||
#else
|
||||
resumeBashSerial() ;
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -595,6 +603,8 @@ static void protocol_init()
|
||||
tx_tail=0;
|
||||
tx_head=0;
|
||||
#endif
|
||||
TX_RX_PAUSE_off;
|
||||
TX_MAIN_PAUSE_off;
|
||||
#endif
|
||||
|
||||
blink=millis();
|
||||
@ -618,13 +628,6 @@ static void protocol_init()
|
||||
remote_callback = joysway_cb;
|
||||
break;
|
||||
#endif
|
||||
#if defined(AFHDS2A_A7105_INO)
|
||||
case MODE_AFHDS2A:
|
||||
next_callback=AFHDS2A_setup();
|
||||
remote_callback = afhds2a_cb;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if defined(FLYSKY_A7105_INO)
|
||||
case MODE_FLYSKY:
|
||||
PE1_off; //antenna RF1
|
||||
@ -632,6 +635,13 @@ static void protocol_init()
|
||||
remote_callback = ReadFlySky;
|
||||
break;
|
||||
#endif
|
||||
#if defined(AFHDS2A_A7105_INO)
|
||||
case MODE_AFHDS2A:
|
||||
PE1_off; //antenna RF1
|
||||
next_callback = initAFHDS2A();
|
||||
remote_callback = ReadAFHDS2A;
|
||||
break;
|
||||
#endif
|
||||
#if defined(HUBSAN_A7105_INO)
|
||||
case MODE_HUBSAN:
|
||||
PE1_off; //antenna RF1
|
||||
@ -783,6 +793,12 @@ static void protocol_init()
|
||||
remote_callback = inav_cb;
|
||||
break;
|
||||
#endif
|
||||
#if defined(Q303_NRF24L01_INO)
|
||||
case MODE_Q303:
|
||||
next_callback=q303_init();
|
||||
remote_callback = q303_callback;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if defined(HISKY_NRF24L01_INO)
|
||||
case MODE_HISKY:
|
||||
@ -1012,8 +1028,8 @@ void Mprotocol_serial_init()
|
||||
PORTC.PIN3CTRL |= 0x40 ;
|
||||
#endif
|
||||
#elif defined STM32_BOARD
|
||||
Serial1.begin(100000,SERIAL_8E2);//USART2
|
||||
Serial2.begin(100000,SERIAL_8E2);//USART3
|
||||
usart2_begin(100000,SERIAL_8E2);
|
||||
usart3_begin(100000,SERIAL_8E2);
|
||||
USART2_BASE->CR1 |= USART_CR1_PCE_BIT;
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE;//disable
|
||||
USART2_BASE->CR1 &= ~ USART_CR1_TE;//disable transmit
|
||||
@ -1040,7 +1056,7 @@ void Mprotocol_serial_init()
|
||||
#if defined(TELEMETRY)
|
||||
void PPM_Telemetry_serial_init()
|
||||
{
|
||||
if( (protocol==MODE_FRSKYD) || (protocol==MODE_HUBSAN) || (protocol==MODE_AFHDS2A))
|
||||
if( (protocol==MODE_FRSKYD) || (protocol==MODE_HUBSAN) || (protocol==MODE_AFHDS2A) )
|
||||
initTXSerial( SPEED_9600 ) ;
|
||||
if(protocol==MODE_FRSKYX)
|
||||
initTXSerial( SPEED_57600 ) ;
|
||||
@ -1186,14 +1202,14 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
rx_buff[0]=UDR0;
|
||||
if((rx_buff[0]&0xFE)==0x54) // If 1st byte is 0x54 or 0x55 it looks ok
|
||||
{
|
||||
TX_RX_PAUSE_on;
|
||||
tx_pause();
|
||||
#if defined STM32_BOARD
|
||||
uint16_t OCR1B;
|
||||
OCR1B =TCNT1+(6500L);
|
||||
timer.setCompare(TIMER_CH2,OCR1B);
|
||||
timer.attachCompare2Interrupt(ISR_COMPB);
|
||||
#else
|
||||
TX_RX_PAUSE_on;
|
||||
tx_pause();
|
||||
OCR1B = TCNT1+(6500L) ; // Full message should be received within timer of 3250us
|
||||
TIFR1 = OCF1B_bm ; // clear OCR1B match flag
|
||||
SET_TIMSK1_OCIE1B ; // enable interrupt on compare B match
|
||||
@ -1228,9 +1244,9 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
detachInterrupt(2); // Disable interrupt on ch2
|
||||
#else
|
||||
CLR_TIMSK1_OCIE1B; // Disable interrupt on compare B match
|
||||
TX_RX_PAUSE_off;
|
||||
tx_resume();
|
||||
#endif
|
||||
TX_RX_PAUSE_off;
|
||||
tx_resume();
|
||||
}
|
||||
#if not defined (ORANGE_TX) && not defined (STM32_BOARD)
|
||||
cli() ;
|
||||
@ -1252,8 +1268,8 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
detachInterrupt(2); // Disable interrupt on ch2
|
||||
#else
|
||||
CLR_TIMSK1_OCIE1B; // Disable interrupt on compare B match
|
||||
tx_resume();
|
||||
#endif
|
||||
tx_resume();
|
||||
}
|
||||
#endif //ENABLE_SERIAL
|
||||
|
||||
|
@ -55,11 +55,11 @@
|
||||
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
#define BIND_COUNT 345 // 1.5 seconds
|
||||
#define FIRST_PACKET_DELAY 12000
|
||||
#define INAV_BIND_COUNT 345 // 1.5 seconds
|
||||
#define FIRST_INAV_PACKET_DELAY 12000
|
||||
|
||||
#define PACKET_PERIOD 4000 // Timeout for callback in uSec
|
||||
#define INITIAL_WAIT 500
|
||||
#define INAV_PACKET_PERIOD 4000 // Timeout for callback in uSec
|
||||
#define INAV_INITIAL_WAIT 500
|
||||
|
||||
// For code readability
|
||||
enum {
|
||||
@ -96,28 +96,28 @@
|
||||
|
||||
|
||||
enum {
|
||||
RATE_LOW = 0,
|
||||
RATE_MID = 1,
|
||||
RATE_HIGH = 2,
|
||||
INAV_RATE_LOW = 0,
|
||||
INAV_RATE_MID = 1,
|
||||
INAV_RATE_HIGH = 2,
|
||||
};
|
||||
|
||||
enum {
|
||||
FLAG_FLIP = 0x01,
|
||||
FLAG_PICTURE = 0x02,
|
||||
FLAG_VIDEO = 0x04,
|
||||
FLAG_RTH = 0x08,
|
||||
FLAG_HEADLESS = 0x10,
|
||||
INAV_FLAG_FLIP = 0x01,
|
||||
INAV_FLAG_PICTURE = 0x02,
|
||||
INAV_FLAG_VIDEO = 0x04,
|
||||
INAV_FLAG_RTH = 0x08,
|
||||
INAV_FLAG_HEADLESS = 0x10,
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
PHASE_INAV_INIT = 0,
|
||||
PHASE_INIT = 0,
|
||||
PHASE_INAV_BIND,
|
||||
PHASE_INAV_DATA
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
DATA_PACKET = 0,
|
||||
BIND_PACKET = 1,
|
||||
DATA_INAV_PACKET = 0,
|
||||
BIND_INAV_PACKET = 1,
|
||||
};
|
||||
|
||||
static const char * const inav_opts[] = {
|
||||
@ -308,19 +308,19 @@
|
||||
// pack the AETR low bits
|
||||
packet[6] = (aileron & 0x03) | ((elevator & 0x03) << 2) | ((throttle & 0x03) << 4) | ((rudder & 0x03) << 6);
|
||||
|
||||
uint8_t rate = RATE_LOW;
|
||||
uint8_t rate = INAV_RATE_LOW;
|
||||
if (Channels[CHANNEL_RATE] > 0) {
|
||||
rate = RATE_HIGH;
|
||||
rate = INAV_RATE_HIGH;
|
||||
} else if (Channels[CHANNEL_RATE] == 0) {
|
||||
rate = RATE_MID;
|
||||
rate = INAV_RATE_MID;
|
||||
}
|
||||
packet[7] = rate; // rate, deviation channel 5, is mapped to AUX1
|
||||
|
||||
const uint8_t flags = GET_FLAG(CHANNEL_FLIP, FLAG_FLIP)
|
||||
| GET_FLAG(CHANNEL_PICTURE, FLAG_PICTURE)
|
||||
| GET_FLAG(CHANNEL_VIDEO, FLAG_VIDEO)
|
||||
| GET_FLAG(CHANNEL_RTH, FLAG_RTH)
|
||||
| GET_FLAG(CHANNEL_HEADLESS, FLAG_HEADLESS);
|
||||
const uint8_t flags = GET_FLAG(CHANNEL_FLIP, INAV_FLAG_FLIP)
|
||||
| GET_FLAG(CHANNEL_PICTURE, INAV_FLAG_PICTURE)
|
||||
| GET_FLAG(CHANNEL_VIDEO, INAV_FLAG_VIDEO)
|
||||
| GET_FLAG(CHANNEL_RTH, INAV_FLAG_RTH)
|
||||
| GET_FLAG(CHANNEL_HEADLESS, INAV_FLAG_HEADLESS);
|
||||
packet[8] = flags; // flags, deviation channels 6-10 are mapped to AUX2 t0 AUX6
|
||||
|
||||
// map deviation channels 9-12 to RC channels AUX7-AUX10, use 10 bit resolution
|
||||
@ -399,7 +399,7 @@
|
||||
|
||||
static void send_packet(uint8_t packet_type)
|
||||
{
|
||||
if (packet_type == DATA_PACKET) {
|
||||
if (packet_type == DATA_INAV_PACKET) {
|
||||
build_data_packet();
|
||||
} else {
|
||||
build_bind_packet();
|
||||
@ -644,9 +644,9 @@
|
||||
switch (phase) {
|
||||
case PHASE_INAV_INIT:
|
||||
phase = PHASE_INAV_BIND;
|
||||
bind_counter = BIND_COUNT;
|
||||
bind_counter = INAV_BIND_COUNT;
|
||||
bind_acked = 0;
|
||||
return FIRST_PACKET_DELAY;
|
||||
return FIRST_INAV_PACKET_DELAY;
|
||||
break;
|
||||
|
||||
case PHASE_INAV_BIND:
|
||||
@ -660,9 +660,9 @@
|
||||
if (bind_acked == 1) {
|
||||
// bind packet acked, so set bind_counter to zero to enter data phase on next callback
|
||||
bind_counter = 0;
|
||||
return PACKET_PERIOD;
|
||||
return INAV_PACKET_PERIOD;
|
||||
}
|
||||
send_packet(BIND_PACKET);
|
||||
send_packet(BIND_INAV_PACKET);
|
||||
--bind_counter;
|
||||
}
|
||||
break;
|
||||
@ -674,10 +674,10 @@
|
||||
return PACKET_CHKTIME; // packet send not yet complete
|
||||
}*/
|
||||
packet_ack();
|
||||
send_packet(DATA_PACKET);
|
||||
send_packet(DATA_INAV_PACKET);
|
||||
break;
|
||||
}
|
||||
return PACKET_PERIOD;
|
||||
return INAV_PACKET_PERIOD;
|
||||
}
|
||||
|
||||
static uint8_t INAV_setup()
|
||||
@ -696,12 +696,12 @@
|
||||
|
||||
if(IS_AUTOBIND_FLAG_on) {
|
||||
phase = PHASE_INAV_INIT;
|
||||
// PROTOCOL_SetBindState(BIND_COUNT * PACKET_PERIOD / 1000);
|
||||
// PROTOCOL_SetBindState(INAV_BIND_COUNT * INAV_PACKET_PERIOD / 1000);
|
||||
} else {
|
||||
set_data_phase();
|
||||
// BIND_DONE;
|
||||
}
|
||||
return INITIAL_WAIT;
|
||||
return INAV_INITIAL_WAIT;
|
||||
}
|
||||
/*
|
||||
const void *INAV_Cmds(enum ProtoCmds cmd)
|
||||
|
152
Multiprotocol/Nrf24l01_q303.ino
Normal file
152
Multiprotocol/Nrf24l01_q303.ino
Normal file
@ -0,0 +1,152 @@
|
||||
#ifdef Q303_NRF24L01_INO
|
||||
|
||||
#include "iface_nrf24l01.h"
|
||||
|
||||
#define Q303_BIND_COUNT 1200
|
||||
|
||||
#define Q303_PACKET_SIZE 10
|
||||
#define Q303_PACKET_PERIOD 1500 // Timeout for callback in uSec
|
||||
#define Q303_INITIAL_WAIT 500
|
||||
#define Q303_RF_BIND_CHANNEL 0x02
|
||||
#define Q303_NUM_RF_CHANNELS 4
|
||||
|
||||
static uint8_t tx_addr[5];
|
||||
static uint8_t current_chan;
|
||||
uint8_t txid[4] = {0xAE, 0x89, 0x97, 0x87};
|
||||
static uint8_t rf_chans[4] = {0x4A, 0x4C, 0x4E, 0x48};
|
||||
|
||||
// haven't figured out txid<-->rf channel mapping yet
|
||||
// static const struct { uint8_t txid[sizeof(txid)]; uint8_t rfchan[Q303_NUM_RF_CHANNELS]; } q303_tx_rf_map[] = {{{0xAE, 0x89, 0x97, 0x87}, {0x4A, 0x4C, 0x4E, 0x48}}};
|
||||
|
||||
enum {
|
||||
Q303_BIND,
|
||||
Q303_DATA
|
||||
};
|
||||
|
||||
// flags going to packet[8]
|
||||
#define Q303_FLAG_HIGHRATE 0x03
|
||||
#define Q303_FLAG_AHOLD 0x40
|
||||
#define Q303_FLAG_RTH 0x80
|
||||
|
||||
// flags going to packet[9]
|
||||
#define Q303_FLAG_GIMBAL_DN 0x04
|
||||
#define Q303_FLAG_GIMBAL_UP 0x20
|
||||
#define Q303_FLAG_HEADLESS 0x08
|
||||
#define Q303_FLAG_FLIP 0x80
|
||||
#define Q303_FLAG_SNAPSHOT 0x10
|
||||
#define Q303_FLAG_VIDEO 0x01
|
||||
|
||||
static void send_packet(uint8_t bind)
|
||||
{
|
||||
if(bind) {
|
||||
packet[0] = 0xaa;
|
||||
memcpy(&packet[1], txid, 4);
|
||||
memset(&packet[5], 0, 5);
|
||||
}
|
||||
else {
|
||||
aileron = map(Servo_data[AILERON], 1000, 2000, 0, 1000);
|
||||
elevator = 1000 - map(Servo_data[ELEVATOR], 1000, 2000, 0, 1000);
|
||||
throttle = map(Servo_data[THROTTLE], 1000, 2000, 0, 1000);
|
||||
rudder = 1000 - map(Servo_data[RUDDER], 1000, 2000, 0, 1000);
|
||||
|
||||
packet[0] = 0x55;
|
||||
packet[1] = aileron >> 2 ; // 8 bits
|
||||
packet[2] = (aileron & 0x03) << 6 // 2 bits
|
||||
| (elevator >> 4); // 6 bits
|
||||
packet[3] = (elevator & 0x0f) << 4 // 4 bits
|
||||
| (throttle >> 6); // 4 bits
|
||||
packet[4] = (throttle & 0x3f) << 2 // 6 bits
|
||||
| (rudder >> 8); // 2 bits
|
||||
packet[5] = rudder & 0xff; // 8 bits
|
||||
packet[6] = 0x10; // trim(s) ?
|
||||
packet[7] = 0x10; // trim(s) ?
|
||||
packet[8] = 0x03 // high rate (0-3)
|
||||
| GET_FLAG(Servo_AUX1, Q303_FLAG_AHOLD)
|
||||
| GET_FLAG(Servo_AUX6, Q303_FLAG_RTH);
|
||||
packet[9] = 0x40 // always set
|
||||
| GET_FLAG(Servo_AUX5, Q303_FLAG_HEADLESS)
|
||||
| GET_FLAG(Servo_AUX2, Q303_FLAG_FLIP)
|
||||
| GET_FLAG(Servo_AUX3, Q303_FLAG_SNAPSHOT)
|
||||
| GET_FLAG(Servo_AUX4, Q303_FLAG_VIDEO);
|
||||
if(Servo_data[AUX7] < (servo_max_100-PPM_SWITCH))
|
||||
packet[9] |= Q303_FLAG_GIMBAL_DN;
|
||||
else if(Servo_data[AUX7] > PPM_SWITCH)
|
||||
packet[9] |= Q303_FLAG_GIMBAL_UP;
|
||||
// set low rate for first packets
|
||||
if(bind_counter != 0) {
|
||||
packet[8] &= ~0x03;
|
||||
bind_counter--;
|
||||
}
|
||||
}
|
||||
|
||||
// Power on, TX mode, CRC enabled
|
||||
XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP));
|
||||
if (bind) {
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, Q303_RF_BIND_CHANNEL);
|
||||
} else {
|
||||
NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_chans[current_chan++]);
|
||||
current_chan %= Q303_NUM_RF_CHANNELS;
|
||||
}
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
|
||||
NRF24L01_FlushTx();
|
||||
|
||||
XN297_WritePayload(packet, Q303_PACKET_SIZE);
|
||||
}
|
||||
|
||||
static uint16_t q303_callback()
|
||||
{
|
||||
switch (phase) {
|
||||
case Q303_BIND:
|
||||
if (bind_counter == 0) {
|
||||
tx_addr[0] = 0x55;
|
||||
memcpy(&tx_addr[1], txid, 4);
|
||||
XN297_SetTXAddr(tx_addr, 5);
|
||||
phase = Q303_DATA;
|
||||
bind_counter = Q303_BIND_COUNT;
|
||||
BIND_DONE;
|
||||
} else {
|
||||
send_packet(1);
|
||||
bind_counter--;
|
||||
}
|
||||
break;
|
||||
case Q303_DATA:
|
||||
send_packet(0);
|
||||
break;
|
||||
}
|
||||
return Q303_PACKET_PERIOD;
|
||||
}
|
||||
|
||||
static uint16_t q303_init()
|
||||
{
|
||||
// memcpy(txid, q303_tx_rf_map[MProtocol_id % (sizeof(q303_tx_rf_map)/sizeof(q303_tx_rf_map[0]))].txid, sizeof(txid));
|
||||
// memcpy(rf_chans, q303_tx_rf_map[MProtocol_id % (sizeof(q303_tx_rf_map)/sizeof(q303_tx_rf_map[0]))].rfchan, sizeof(rf_chans));
|
||||
|
||||
NRF24L01_Initialize();
|
||||
NRF24L01_SetTxRxMode(TX_EN);
|
||||
|
||||
XN297_SetTXAddr((uint8_t *) "\xCC\xCC\xCC\xCC\xCC", 5);
|
||||
NRF24L01_FlushTx();
|
||||
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_05_RF_CH, Q303_RF_BIND_CHANNEL);
|
||||
NRF24L01_SetBitrate(NRF24L01_BR_250K);
|
||||
NRF24L01_SetPower();
|
||||
|
||||
// this sequence necessary for module from stock tx
|
||||
NRF24L01_ReadReg(NRF24L01_1D_FEATURE);
|
||||
NRF24L01_Activate(0x73); // Activate feature register
|
||||
NRF24L01_ReadReg(NRF24L01_1D_FEATURE);
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
|
||||
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x00); // Set feature bits on
|
||||
NRF24L01_Activate(0x53); // switch bank back
|
||||
|
||||
BIND_IN_PROGRESS;
|
||||
bind_counter = Q303_BIND_COUNT;
|
||||
current_chan = 0;
|
||||
// PROTOCOL_SetBindState(Q303_BIND_COUNT * Q303_PACKET_PERIOD / 1000);
|
||||
phase = Q303_BIND;
|
||||
return Q303_INITIAL_WAIT;
|
||||
}
|
||||
|
||||
#endif
|
89
Multiprotocol/PPM_SERIE.txt
Normal file
89
Multiprotocol/PPM_SERIE.txt
Normal file
@ -0,0 +1,89 @@
|
||||
#define PPM_TEST 3 //test voie valeur
|
||||
|
||||
#define PPM_MIN_COMMAND 1250
|
||||
#define PPM_SWITCH 1550
|
||||
#define PPM_MAX_COMMAND 1750
|
||||
#define isterie 10
|
||||
|
||||
|
||||
#define PPM_Pin 3 //this must be 2 or 3
|
||||
int ppm[18]; //array for storing up to 16 servo signals
|
||||
int maxi = 0, mini = 3000, decal, moy, a,r, val;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200); Serial.println("ready");
|
||||
pinMode(PPM_Pin, INPUT); attachInterrupt(PPM_Pin - 2, read_ppm, CHANGE);
|
||||
|
||||
TCCR1A = 0; //reset timer1
|
||||
TCCR1B = 0;
|
||||
TCCR1B |= (1 << CS11); //set timer1 to increment every 0,5 us
|
||||
}
|
||||
|
||||
void loop() {
|
||||
//You can delete everithing inside loop() and put your own code here
|
||||
int count;
|
||||
if(ppm[PPM_TEST]<mini || ppm[PPM_TEST]>maxi) {
|
||||
maxi = max( maxi, ppm[PPM_TEST]);
|
||||
mini = min( mini, ppm[PPM_TEST]);
|
||||
moy = (maxi + mini)/2;
|
||||
decal = (maxi - moy) / 125 * 100;
|
||||
a = moy + decal;
|
||||
r = moy - decal;
|
||||
}
|
||||
Serial.print(a); Serial.print(" ");
|
||||
Serial.print(r); Serial.print(" ");
|
||||
Serial.print(maxi); Serial.print(" ");
|
||||
Serial.print(mini); Serial.print(" ");
|
||||
Serial.print(moy); Serial.print(" ");
|
||||
if((PPM_SWITCH - isterie) < moy < (PPM_SWITCH + isterie)) {
|
||||
Serial.print(" . Pb istérie PPM middel ");
|
||||
Serial.print(PPM_SWITCH);
|
||||
}
|
||||
else {
|
||||
Serial.print(" . ");
|
||||
|
||||
count = 0;
|
||||
Serial.print(ppm[count]); Serial.print(" "); count++;
|
||||
Serial.print(ppm[count]); Serial.print(" "); count++;
|
||||
Serial.print(ppm[count]); Serial.print(" "); count++;
|
||||
Serial.print(ppm[count]); Serial.print(" "); count++;
|
||||
for( ;count<17;count++) {
|
||||
val=ppm[count];
|
||||
if((moy-2*isterie) < val < (moy+2*isterie)) { Serial.print("2"); }
|
||||
else if(PPM_MAX_COMMAND < val < 2200) { Serial.print("3"); }
|
||||
else if(PPM_MAX_COMMAND < val) { Serial.print("+"); }
|
||||
else if(800 < val < PPM_MIN_COMMAND) { Serial.print("1"); }
|
||||
else { Serial.print("."); }
|
||||
|
||||
}
|
||||
/*
|
||||
while(ppm[count] != 0){ //print out the servo values
|
||||
Serial.print(count); Serial.print(" ");
|
||||
Serial.print(ppm[count]); Serial.print(" ");
|
||||
count++;
|
||||
}
|
||||
*/
|
||||
}
|
||||
Serial.println("");
|
||||
delay(100); //you can even use delays!!!
|
||||
}
|
||||
|
||||
void read_ppm(){ //leave this alone
|
||||
#if F_CPU == 16000000
|
||||
#define PPM_SCALE 1L
|
||||
#elif F_CPU == 8000000
|
||||
#define PPM_SCALE 0L
|
||||
#else
|
||||
#error // 8 or 16MHz only !
|
||||
#endif
|
||||
static unsigned int pulse;
|
||||
static unsigned long counter;
|
||||
static byte channel;
|
||||
|
||||
counter = TCNT1;
|
||||
TCNT1 = 0;
|
||||
|
||||
if(counter < 510 << PPM_SCALE){ pulse = counter; } //must be a pulse if less than 510us
|
||||
else if(counter > 1910 << PPM_SCALE){ channel = 0; } //sync pulses over 1910us
|
||||
else{ ppm[channel] = (counter + pulse) >> PPM_SCALE; channel++; } //servo values between 510us and 2420us will end up here
|
||||
}
|
@ -79,7 +79,7 @@
|
||||
#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
|
||||
@ -290,21 +290,6 @@
|
||||
#define cli() noInterrupts()
|
||||
#define sei() interrupts()
|
||||
#define delayMilliseconds(x) delay(x)
|
||||
//TX Pause
|
||||
#undef TX_MAIN_PAUSE_off
|
||||
#undef TX_MAIN_PAUSE_on
|
||||
#undef IS_TX_MAIN_PAUSE_on
|
||||
#undef TX_RX_PAUSE_off
|
||||
#undef TX_RX_PAUSE_on
|
||||
#undef IS_TX_RX_PAUSE_on
|
||||
#undef IS_TX_PAUSE_on
|
||||
#define TX_MAIN_PAUSE_off
|
||||
#define TX_MAIN_PAUSE_on
|
||||
#define IS_TX_MAIN_PAUSE_on
|
||||
#define TX_RX_PAUSE_off
|
||||
#define TX_RX_PAUSE_on
|
||||
#define IS_TX_RX_PAUSE_on
|
||||
#define IS_TX_PAUSE_on
|
||||
#endif
|
||||
|
||||
//*******************
|
||||
|
@ -215,6 +215,9 @@ FLIP|SNAPSHOT|VIDEO|HEADLESS
|
||||
###INAV
|
||||
En cours de passage
|
||||
|
||||
###MJX
|
||||
####Sub_protocol H26WH
|
||||
|
||||
###NE260
|
||||
Modele: Nine Eagles SoloPro
|
||||
|
||||
@ -224,6 +227,14 @@ CH1|CH2|CH3|CH4
|
||||
---|---|---|---
|
||||
A|E|T|R
|
||||
|
||||
###Q303
|
||||
|
||||
Autobind
|
||||
|
||||
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
|
||||
---|---|---|---|---|---|---|---|---|---|---
|
||||
A|E|T|R|AHOLD|FLIP|SNAPSHOT|VIDEO|HEADLESS|RTH|GIMBAL
|
||||
|
||||
###UDI
|
||||
Modele: Known UDI 2.4GHz protocol variants, all using BK2421
|
||||
* UDI U819 coaxial 3ch helicoper
|
||||
|
@ -15,7 +15,6 @@
|
||||
//**************************
|
||||
// Telemetry serial code *
|
||||
//**************************
|
||||
|
||||
#if defined TELEMETRY
|
||||
|
||||
#if defined SPORT_TELEMETRY
|
||||
@ -62,6 +61,15 @@ void DSM_frame()
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined AFHDS2A_TELEMETRY
|
||||
void AFHDSA_short_frame()
|
||||
{
|
||||
Serial_write(0xAA); // Telemetry packet
|
||||
for (uint8_t i = 0; i < 29; i++) // RSSI value followed by 4*7 bytes of telemetry data
|
||||
Serial_write(pkt[i]);
|
||||
}
|
||||
#endif
|
||||
|
||||
void frskySendStuffed()
|
||||
{
|
||||
Serial_write(START_STOP);
|
||||
@ -94,11 +102,11 @@ void frsky_check_telemetry(uint8_t *pkt,uint8_t len)
|
||||
for (uint8_t i=3;i<len;i++)
|
||||
pktt[i]=pkt[i];
|
||||
telemetry_link=1;
|
||||
telemetry_lost=0;
|
||||
if(pktt[6])
|
||||
telemetry_counter=(telemetry_counter+1)%32;
|
||||
//
|
||||
#if defined SPORT_TELEMETRY && defined FRSKYX_CC2500_INO
|
||||
telemetry_lost=0;
|
||||
if (protocol==MODE_FRSKYX)
|
||||
{
|
||||
if ((pktt[5] >> 4 & 0x0f) == 0x08)
|
||||
@ -131,12 +139,12 @@ void frsky_link_frame()
|
||||
frame[4] = (uint8_t)RSSI_dBm;
|
||||
}
|
||||
else
|
||||
if ((protocol==MODE_HUBSAN) || (protocol==MODE_AFHDS2A))
|
||||
if (protocol==MODE_HUBSAN||protocol==MODE_AFHDS2A)
|
||||
{
|
||||
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[3] = protocol==MODE_HUBSAN?0x00:(uint8_t)RSSI_dBm;
|
||||
frame[4] = TX_RSSI;
|
||||
}
|
||||
frame[5] = frame[6] = frame[7] = frame[8] = 0;
|
||||
frskySendStuffed();
|
||||
@ -414,7 +422,6 @@ void proces_sport_data(uint8_t data)
|
||||
void TelemetryUpdate()
|
||||
{
|
||||
// check for space in tx buffer
|
||||
|
||||
#ifdef BASH_SERIAL
|
||||
uint8_t h ;
|
||||
uint8_t t ;
|
||||
@ -487,12 +494,19 @@ void TelemetryUpdate()
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if(telemetry_link && protocol != MODE_FRSKYX )
|
||||
{ // FrSky + Hubsan + Flysky AFHDS2A
|
||||
frsky_link_frame();
|
||||
telemetry_link=0;
|
||||
return;
|
||||
}
|
||||
#if defined AFHDS2A_TELEMETRY
|
||||
if(telemetry_link == 2 && protocol == MODE_AFHDS2A)
|
||||
{
|
||||
AFHDSA_short_frame();
|
||||
telemetry_link=0;
|
||||
}
|
||||
#endif
|
||||
if(telemetry_link && protocol != MODE_FRSKYX )
|
||||
{ // FrSkyD + Hubsan + AFHDS2A
|
||||
frsky_link_frame();
|
||||
telemetry_link=0;
|
||||
return;
|
||||
}
|
||||
#if defined HUB_TELEMETRY
|
||||
if(!telemetry_link && protocol == MODE_FRSKYD)
|
||||
{ // FrSky
|
||||
@ -521,7 +535,7 @@ void TelemetryUpdate()
|
||||
tx_head = nextHead ;
|
||||
tx_resume();
|
||||
}
|
||||
|
||||
|
||||
void initTXSerial( uint8_t speed)
|
||||
{
|
||||
#ifdef ENABLE_PPM
|
||||
@ -535,12 +549,12 @@ void TelemetryUpdate()
|
||||
USARTC0.CTRLC = 0x03 ;
|
||||
#else
|
||||
#ifdef STM32_BOARD
|
||||
Serial2.begin(9600); //USART3
|
||||
usart3_begin(9600,SERIAL_8N1); //USART3
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE; //disable RX leave TX enabled
|
||||
#else
|
||||
UBRR0H = 0x00;
|
||||
UBRR0L = 0x67;
|
||||
UCSR0A = 0 ; // Clear X2 bit
|
||||
UCSR0A = 0 ; // Clear X2 bit
|
||||
//Set frame format to 8 data bits, none, 1 stop bit
|
||||
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
|
||||
#endif
|
||||
@ -555,17 +569,17 @@ void TelemetryUpdate()
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
|
||||
USARTC0.CTRLC = 0x03 ;*/
|
||||
#else
|
||||
#ifdef STM32_BOARD
|
||||
Serial2.begin(57600); //USART3
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE; //disable RX leave TX enabled
|
||||
#else
|
||||
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
|
||||
#ifdef STM32_BOARD
|
||||
usart3_begin(57600,SERIAL_8N1); //USART3
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE; //disable RX leave TX enabled
|
||||
#else
|
||||
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
|
||||
#endif
|
||||
}
|
||||
else if(speed==SPEED_125K)
|
||||
{ // 125000
|
||||
@ -576,17 +590,17 @@ void TelemetryUpdate()
|
||||
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
|
||||
USARTC0.CTRLC = 0x03 ;*/
|
||||
#else
|
||||
#ifdef STM32_BOARD
|
||||
Serial2.begin(125000); //USART3
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE; //disable RX leave TX enabled
|
||||
#else
|
||||
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
|
||||
#ifdef STM32_BOARD
|
||||
usart3_begin(125000,SERIAL_8N1); //USART3
|
||||
USART3_BASE->CR1 &= ~ USART_CR1_RE; //disable RX leave TX enabled
|
||||
#else
|
||||
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
|
||||
}
|
||||
#endif
|
||||
#ifndef ORANGE_TX
|
||||
@ -601,9 +615,6 @@ void TelemetryUpdate()
|
||||
ISR(USARTC0_DRE_vect)
|
||||
#else
|
||||
#ifdef STM32_BOARD
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
void __irq_usart3()
|
||||
#else
|
||||
ISR(USART_UDRE_vect)
|
||||
@ -625,247 +636,256 @@ void TelemetryUpdate()
|
||||
#endif
|
||||
}
|
||||
if (tx_tail == tx_head)
|
||||
#ifdef STM32_BOARD
|
||||
USART3_BASE->CR1 &= ~USART_CR1_TXEIE;//disable interrupt
|
||||
tx_pause(); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
|
||||
#ifdef STM32_BOARD
|
||||
}
|
||||
#else
|
||||
tx_pause(); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#if defined STM32_BOARD
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif //STM32_BOARD
|
||||
|
||||
#ifdef STM32_BOARD
|
||||
void usart2_begin(uint32_t baud,uint32_t config )
|
||||
{
|
||||
usart_init(USART2);
|
||||
usart_config_gpios_async(USART2,GPIOA,PIN_MAP[PA3].gpio_bit,GPIOA,PIN_MAP[PA2].gpio_bit,config);
|
||||
usart_set_baud_rate(USART2, STM32_PCLK1, baud);//
|
||||
usart_enable(USART2);
|
||||
}
|
||||
void usart3_begin(uint32_t baud,uint32_t config )
|
||||
{
|
||||
usart_init(USART3);
|
||||
usart_config_gpios_async(USART3,GPIOB,PIN_MAP[PB11].gpio_bit,GPIOB,PIN_MAP[PB10].gpio_bit,config);
|
||||
usart_set_baud_rate(USART3, STM32_PCLK1, baud);
|
||||
usart_enable(USART3);
|
||||
}
|
||||
#endif
|
||||
#else //BASH_SERIAL
|
||||
// Routines for bit-bashed serial output
|
||||
// Routines for bit-bashed serial output
|
||||
|
||||
// Speed is 0 for 100K and 1 for 9600
|
||||
void initTXSerial( uint8_t speed)
|
||||
// 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 )
|
||||
{
|
||||
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)
|
||||
}
|
||||
OCR0A = 207 ; // 104uS period
|
||||
TCCR0A = 3 ;
|
||||
TCCR0B = 0x0A ; // Fast PMM, 2MHz
|
||||
}
|
||||
|
||||
void Serial_write( uint8_t byte )
|
||||
else // 100K
|
||||
{
|
||||
uint8_t temp ;
|
||||
uint8_t temp1 ;
|
||||
uint8_t byteLo ;
|
||||
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
|
||||
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 ;
|
||||
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()
|
||||
uint8_t next = (SerialControl.head + 2) & 0x3f ;
|
||||
if ( next != SerialControl.tail )
|
||||
{
|
||||
cli() ;
|
||||
if ( SerialControl.busy == 0 )
|
||||
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 )
|
||||
{
|
||||
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 ;
|
||||
}
|
||||
GPIOR1 = 1 ;
|
||||
OCR0B = TCNT0 + 40 ;
|
||||
OCR0A = OCR0B + 210 ;
|
||||
TIFR0 = (1<<OCF0A) | (1<<OCF0B) ;
|
||||
TIMSK0 |= (1<<OCIE0B) ;
|
||||
SerialControl.busy = 1 ;
|
||||
}
|
||||
else
|
||||
{
|
||||
sei() ;
|
||||
GPIOR1 = 1 ;
|
||||
TIFR0 = (1<<TOV0) ;
|
||||
TIMSK0 |= (1<<TOIE0) ;
|
||||
SerialControl.busy = 1 ;
|
||||
}
|
||||
}
|
||||
|
||||
// Assume timer0 at 0.5uS clock
|
||||
|
||||
ISR(TIMER0_COMPA_vect)
|
||||
else
|
||||
{
|
||||
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 ;
|
||||
}
|
||||
sei() ;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(TIMER0_COMPB_vect)
|
||||
// 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 )
|
||||
{
|
||||
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 ;
|
||||
}
|
||||
TIMSK0 &= ~(1<<OCIE0A) ;
|
||||
GPIOR1 = 3 ;
|
||||
}
|
||||
|
||||
ISR(TIMER0_OVF_vect)
|
||||
else
|
||||
{
|
||||
uint8_t byte ;
|
||||
if ( GPIOR1 > 2 )
|
||||
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 )
|
||||
{
|
||||
byte = GPIOR0 ;
|
||||
SerialControl.busy = 0 ;
|
||||
TIMSK0 &= ~(1<<OCIE0B) ;
|
||||
}
|
||||
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
|
||||
// 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 = 10 ;
|
||||
GPIOR1 = 8 ;
|
||||
OCR0A = OCR0B + 40 ;
|
||||
OCR0B = OCR0A + 8 * 20 ;
|
||||
TIMSK0 |= (1<<OCIE0A) ;
|
||||
}
|
||||
else
|
||||
{
|
||||
SerialControl.busy = 0 ;
|
||||
TIMSK0 &= ~(1<<TOIE0) ;
|
||||
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
|
||||
|
||||
|
@ -33,6 +33,7 @@
|
||||
#ifndef A7105_INSTALLED
|
||||
#undef FLYSKY_A7105_INO
|
||||
#undef HUBSAN_A7105_INO
|
||||
#undef AFHDS2A_A7105_INO
|
||||
#endif
|
||||
#ifndef CYRF6936_INSTALLED
|
||||
#undef DEVO_CYRF6936_INO
|
||||
@ -71,17 +72,21 @@
|
||||
#undef DSM_TELEMETRY
|
||||
#undef SPORT_TELEMETRY
|
||||
#undef HUB_TELEMETRY
|
||||
#undef AFHDS2A_TELEMETRY
|
||||
#else
|
||||
#if not defined(CYRF6936_INSTALLED) || not defined(DSM_CYRF6936_INO)
|
||||
#if not defined(DSM_CYRF6936_INO)
|
||||
#undef DSM_TELEMETRY
|
||||
#endif
|
||||
#if (not defined(CC2500_INSTALLED) || not defined(FRSKYD_CC2500_INO)) && (not defined(A7105_INSTALLED) || not defined(HUBSAN_A7105_INO))
|
||||
#if not defined(FRSKYD_CC2500_INO) && not defined(HUBSAN_A7105_INO) && not defined(AFHDS2A_A7105_INO)
|
||||
#undef HUB_TELEMETRY
|
||||
#endif
|
||||
#if not defined(CC2500_INSTALLED) || not defined(FRSKYX_CC2500_INO)
|
||||
#if not defined(FRSKYX_CC2500_INO)
|
||||
#undef SPORT_TELEMETRY
|
||||
#endif
|
||||
#if not defined(DSM_TELEMETRY) && not defined(HUB_TELEMETRY) && not defined(SPORT_TELEMETRY)
|
||||
#if not defined(AFHDS2A_A7105_INO)
|
||||
#undef AFHDS2A_TELEMETRY
|
||||
#endif
|
||||
#if not defined(DSM_TELEMETRY) && not defined(HUB_TELEMETRY) && not defined(SPORT_TELEMETRY) && not defined(AFHDS2A_TELEMETRY)
|
||||
#undef TELEMETRY
|
||||
#undef INVERT_TELEMETRY
|
||||
#endif
|
||||
|
@ -22,8 +22,9 @@
|
||||
/********************/
|
||||
//Uncomment one of the line below if you have a different module not based on the original Multi Atmega328p design which includes the 4-in-1.
|
||||
//If you don't know then leave them commented.
|
||||
//#define STM32_BOARD
|
||||
|
||||
#ifdef __arm__
|
||||
#define STM32_BOARD // Let's automatically select this board if arm is selected since this is the only one for now...
|
||||
#endif
|
||||
|
||||
/*******************/
|
||||
/*** TX SETTINGS ***/
|
||||
@ -34,6 +35,10 @@
|
||||
#define EATR
|
||||
|
||||
|
||||
//Modify the channel for a software reset modul: AUX...(channel number - 4)
|
||||
//Default is AUX10 (channel 14).
|
||||
#define SWITCH_RESET 14
|
||||
|
||||
/**************************/
|
||||
/*** RF CHIPS INSTALLED ***/
|
||||
/**************************/
|
||||
@ -55,11 +60,11 @@
|
||||
//Comment the protocols you are not using with "//" to save Flash space.
|
||||
|
||||
//The protocols below need an A7105 to be installed
|
||||
#define AFHDS2A_A7105_INO
|
||||
// #define JOYSWAY_A7105_INO
|
||||
|
||||
#define FLYSKY_A7105_INO
|
||||
#define HUBSAN_A7105_INO
|
||||
#define AFHDS2A_A7105_INO
|
||||
//The protocols below need a CYRF6936 to be installed
|
||||
// #define WK2x01_CYRF6936_INO //!\\ //pb voie
|
||||
|
||||
@ -85,7 +90,8 @@
|
||||
// #define NE260_NRF24L01_INO
|
||||
// #define BlueFly_NRF24L01_INO //probleme gene id
|
||||
// #define FBL100_NRF24L01_INO // finir id //!\\ //pb voie ???
|
||||
#define INAV_NRF24L01_INO
|
||||
// #define INAV_NRF24L01_INO // a faire
|
||||
#define Q303_NRF24L01_INO
|
||||
|
||||
#define BAYANG_NRF24L01_INO
|
||||
#define CG023_NRF24L01_INO
|
||||
@ -121,7 +127,7 @@
|
||||
#define DSM_TELEMETRY
|
||||
#define SPORT_TELEMETRY
|
||||
#define HUB_TELEMETRY
|
||||
|
||||
#define AFHDS2A_TELEMETRY
|
||||
|
||||
/****************************/
|
||||
/*** SERIAL MODE SETTINGS ***/
|
||||
@ -274,6 +280,8 @@ const PPM_Parameters PPM_prot[15]= {
|
||||
FORMAT_JJRCX1
|
||||
FORMAT_X5C1
|
||||
FQ777-951
|
||||
MODE_AFHDS2A
|
||||
NONE
|
||||
*/
|
||||
|
||||
// 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...
|
||||
|
@ -87,11 +87,4 @@ enum A7105_MASK {
|
||||
A7105_MASK_VBCF = 1 << 3,
|
||||
};
|
||||
|
||||
enum {
|
||||
INIT_FLYSKY,
|
||||
INIT_FLYSKY_AFHDS2A,
|
||||
INIT_JOYSWAY,
|
||||
INIT_HUBSAN
|
||||
};
|
||||
|
||||
#endif
|
@ -32,8 +32,8 @@ enum PROTOCOLS
|
||||
MODE_BlueFly = 54, // =>NRF24L01
|
||||
MODE_NE260 = 55, // =>NRF24L01
|
||||
|
||||
MODE_AFHDS2A = 31, // =>A7105
|
||||
MODE_INAV = 57, // =>NRF24L01
|
||||
MODE_Q303 = 58, // =>NRF24L01
|
||||
|
||||
MODE_SERIAL = 0, // Serial commands
|
||||
MODE_FLYSKY = 1, // =>A7105
|
||||
@ -63,6 +63,7 @@ enum PROTOCOLS
|
||||
MODE_FRSKYV = 25, // =>CC2500
|
||||
MODE_HONTAI = 26, // =>NRF24L01
|
||||
MODE_OPENLRS = 27, // =>OpenLRS hardware
|
||||
MODE_AFHDS2A = 28, // =>A7105
|
||||
};
|
||||
enum Flysky
|
||||
{
|
||||
@ -71,6 +72,13 @@ enum Flysky
|
||||
V6X6=2,
|
||||
V912=3
|
||||
};
|
||||
enum AFHDS2A
|
||||
{
|
||||
PWM_IBUS = 0,
|
||||
PPM_IBUS = 1,
|
||||
PWM_SBUS = 2,
|
||||
PPM_SBUS = 3,
|
||||
};
|
||||
enum Hisky
|
||||
{
|
||||
Hisky=0,
|
||||
@ -132,7 +140,8 @@ enum MJXQ
|
||||
X600 = 1,
|
||||
X800 = 2,
|
||||
H26D = 3,
|
||||
E010 = 4
|
||||
E010 = 4,
|
||||
H26WH = 5
|
||||
};
|
||||
enum FRSKYX
|
||||
{
|
||||
@ -432,6 +441,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
FrskyV 25
|
||||
HONTAI 26
|
||||
OpenLRS 27
|
||||
AFHDS2A 28
|
||||
BindBit=> 0x80 1=Bind/0=No
|
||||
AutoBindBit=> 0x40 1=Yes /0=No
|
||||
RangeCheck=> 0x20 1=Yes /0=No
|
||||
@ -497,7 +507,12 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
|
||||
FORMAT_HONTAI 0
|
||||
FORMAT_JJRCX1 1
|
||||
FORMAT_X5C1 2
|
||||
FQ777-521 3
|
||||
FQ777-521 3
|
||||
sub_protocol==AFHDS2A
|
||||
PWM_IBUS 0
|
||||
PPM_IBUS 1
|
||||
PWM_SBUS 2
|
||||
PPM_SBUS 3
|
||||
Power value => 0x80 0=High/1=Low
|
||||
Stream[3] = option_protocol;
|
||||
option_protocol value is -127..127
|
||||
|
Binary file not shown.
Loading…
x
Reference in New Issue
Block a user