Browse Source

move to real cpp not ardunio

master
Schoenberger, Philipp 6 years ago
parent
commit
87a7f65481
  1. 12
      Multiprotocol/FrSkyD_cc2500.cpp
  2. 25
      Multiprotocol/FrSkyD_cc2500.h
  3. 26
      Multiprotocol/FrSkyV_cc2500.cpp
  4. 39
      Multiprotocol/FrSkyV_cc2500.h
  5. 42
      Multiprotocol/FrSkyX_cc2500.cpp
  6. 37
      Multiprotocol/FrSkyX_cc2500.h
  7. 283
      Multiprotocol/Multiprotocol.h
  8. 205
      Multiprotocol/Multiprotocol.ino
  9. 211
      Multiprotocol/TX_Def.h
  10. 7
      Multiprotocol/Validate.h
  11. 64
      Multiprotocol/cc2500_spi.cpp
  12. 33
      Multiprotocol/cc2500_spi.h
  13. 51
      Multiprotocol/common.cpp
  14. 77
      Multiprotocol/common.h
  15. 235
      Multiprotocol/config.cpp
  16. 311
      Multiprotocol/config.h
  17. 6
      Multiprotocol/debug.h
  18. 77
      Multiprotocol/input.cpp
  19. 44
      Multiprotocol/input.h
  20. 38
      Multiprotocol/inputs.ino
  21. 15
      Multiprotocol/pins.h
  22. 57
      Multiprotocol/spi.cpp
  23. 38
      Multiprotocol/spi.h
  24. 90
      Multiprotocol/state.cpp
  25. 27
      Multiprotocol/state.h
  26. 217
      Multiprotocol/tx_def.h
  27. 57
      config

12
Multiprotocol/FrSkyD_cc2500.ino → Multiprotocol/FrSkyD_cc2500.cpp

@ -13,10 +13,11 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(FRSKYD_CC2500_INO)
#include "iface_cc2500.h"
#include "common.h"
#include "cc2500_spi.h"
#include "Multiprotocol.h"
static void __attribute__((unused)) frsky2way_init(uint8_t bind)
void frsky2way_init(uint8_t bind)
{
//debugln("frsky2way_init");
FRSKY_init_cc2500(FRSKYD_cc2500_conf);
@ -31,7 +32,7 @@ static void __attribute__((unused)) frsky2way_init(uint8_t bind)
//#######END INIT########
}
static void __attribute__((unused)) frsky2way_build_bind_packet()
void frsky2way_build_bind_packet()
{
//debugln("build bind");
//11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01
@ -57,7 +58,7 @@ static void __attribute__((unused)) frsky2way_build_bind_packet()
packet[17] = 0x01;
}
static void __attribute__((unused)) frsky2way_data_frame()
void frsky2way_data_frame()
{
//pachet[4] is telemetry user frame counter(hub)
//11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88
@ -212,4 +213,3 @@ uint16_t ReadFrSky_2way()
}
return state == FRSKY_DATA4 ? 7500 : 9000;
}
#endif

25
Multiprotocol/FrSkyD_cc2500.h

@ -0,0 +1,25 @@
/*
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/>.
*/
#ifndef _FRSKYD_CC2500_H_
#define _FRSKYD_CC2500_H_
#include <stdint.h>
void frsky2way_init(uint8_t bind);
void frsky2way_build_bind_packet();
void frsky2way_data_frame(void);
uint16_t initFrSky_2way(void);
uint16_t ReadFrSky_2way(void);
#endif

26
Multiprotocol/FrSkyV_cc2500.ino → Multiprotocol/FrSkyV_cc2500.cpp

@ -13,21 +13,12 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(FRSKYV_CC2500_INO)
#define FRSKYV_BIND_COUNT 200
#include "FrSkyV_cc2500.h"
#include "cc2500_spi.h"
#include "common.h"
enum {
FRSKYV_DATA1=0,
FRSKYV_DATA2,
FRSKYV_DATA3,
FRSKYV_DATA4,
FRSKYV_DATA5
};
#include "iface_cc2500.h"
static uint8_t __attribute__((unused)) FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len)
uint8_t FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len)
{
for(uint8_t i = 0; i < len; i++)
{
@ -41,7 +32,7 @@ static uint8_t __attribute__((unused)) FRSKYV_crc8(uint8_t result, uint8_t *data
return result;
}
static uint8_t __attribute__((unused)) FRSKYV_crc8_le(uint8_t *data, uint8_t len)
uint8_t FRSKYV_crc8_le(uint8_t *data, uint8_t len)
{
uint8_t result = 0xD6;
@ -57,7 +48,7 @@ static uint8_t __attribute__((unused)) FRSKYV_crc8_le(uint8_t *data, uint8_t len
return result;
}
static void __attribute__((unused)) FRSKYV_build_bind_packet()
void FRSKYV_build_bind_packet()
{
//0e 03 01 57 12 00 06 0b 10 15 1a 00 00 00 61
packet[0] = 0x0e; //Length
@ -77,7 +68,7 @@ static void __attribute__((unused)) FRSKYV_build_bind_packet()
packet[14] = FRSKYV_crc8(0x93, packet, 14);
}
static uint8_t __attribute__((unused)) FRSKYV_calc_channel()
uint8_t FRSKYV_calc_channel()
{
uint32_t temp=seed;
temp = (temp * 0xaa) % 0x7673;
@ -85,7 +76,7 @@ static uint8_t __attribute__((unused)) FRSKYV_calc_channel()
return (seed & 0xff) % 0x32;
}
static void __attribute__((unused)) FRSKYV_build_data_packet()
void FRSKYV_build_data_packet()
{
uint8_t idx = 0; // transmit lower channels
@ -162,4 +153,3 @@ uint16_t initFRSKYV()
return 10000;
}
#endif

39
Multiprotocol/FrSkyV_cc2500.h

@ -0,0 +1,39 @@
/*
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/>.
*/
#ifndef _FRSKYV_CC2500_H_
#define _FRSKYV_CC2500_H_
#define FRSKYV_BIND_COUNT 200
#include <stdint.h>
#include "Multiprotocol.h"
enum frskyv_data_e {
FRSKYV_DATA1=0,
FRSKYV_DATA2,
FRSKYV_DATA3,
FRSKYV_DATA4,
FRSKYV_DATA5
};
uint8_t FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len);
uint8_t FRSKYV_crc8_le(uint8_t *data, uint8_t len);
void FRSKYV_build_bind_packet(void);
uint8_t FRSKYV_calc_channel(void);
void FRSKYV_build_data_packet(void);
uint16_t ReadFRSKYV(void);
uint16_t initFRSKYV(void);
#endif

42
Multiprotocol/FrSkyX_cc2500.ino → Multiprotocol/FrSkyX_cc2500.cpp

@ -15,24 +15,27 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(FRSKYX_CC2500_INO)
#include "iface_cc2500.h"
#include "Arduino.h"
#include "Multiprotocol.h"
#include "FrSkyX_cc2500.h"
#include <stdint.h>
#include "common.h"
#include "cc2500_spi.h"
uint8_t FrX_chanskip;
uint8_t FrX_send_seq ;
uint8_t FrX_receive_seq ;
#define FRX_FAILSAFE_TIMEOUT 1032
static void __attribute__((unused)) frskyX_set_start(uint8_t ch )
void frskyX_set_start(uint8_t ch)
{
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_25_FSCAL1, calData[ch]);
CC2500_WriteReg(CC2500_0A_CHANNR, hopping_frequency[ch]);
}
static void __attribute__((unused)) frskyX_init()
void frskyX_init(void)
{
FRSKY_init_cc2500((sub_protocol&2)?FRSKYXEU_cc2500_conf:FRSKYX_cc2500_conf); // LBT or FCC
//
@ -47,7 +50,7 @@ static void __attribute__((unused)) frskyX_init()
//#######END INIT########
}
static void __attribute__((unused)) frskyX_initialize_data(uint8_t adr)
void frskyX_initialize_data(uint8_t adr)
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
CC2500_WriteReg(CC2500_18_MCSM0, 0x8);
@ -56,17 +59,19 @@ static void __attribute__((unused)) frskyX_initialize_data(uint8_t adr)
}
//**CRC**
const uint16_t PROGMEM frskyX_CRC_Short[]={
const uint16_t frskyX_CRC_Short[]={
0x0000, 0x1189, 0x2312, 0x329B, 0x4624, 0x57AD, 0x6536, 0x74BF,
0x8C48, 0x9DC1, 0xAF5A, 0xBED3, 0xCA6C, 0xDBE5, 0xE97E, 0xF8F7 };
static uint16_t __attribute__((unused)) frskyX_CRCTable(uint8_t val)
uint16_t frskyX_CRCTable(uint8_t val)
{
uint16_t word ;
word = pgm_read_word(&frskyX_CRC_Short[val&0x0F]) ;
val /= 16 ;
return word ^ (0x1081 * val) ;
}
static uint16_t __attribute__((unused)) frskyX_crc_x(uint8_t *data, uint8_t len)
uint16_t frskyX_crc_x(uint8_t *data, uint8_t len)
{
uint16_t crc = 0;
for(uint8_t i=0; i < len; i++)
@ -74,7 +79,7 @@ static uint16_t __attribute__((unused)) frskyX_crc_x(uint8_t *data, uint8_t len)
return crc;
}
static void __attribute__((unused)) frskyX_build_bind_packet()
void frskyX_build_bind_packet(void)
{
// debugln("%s:%d build bind", __func__, __LINE__);
packet[0] = (sub_protocol & 2 ) ? 0x20 : 0x1D ; // LBT or FCC
@ -104,14 +109,14 @@ static void __attribute__((unused)) frskyX_build_bind_packet()
// 0-2047, 0 = 817, 1024 = 1500, 2047 = 2182
//64=860,1024=1500,1984=2140//Taranis 125%
static uint16_t __attribute__((unused)) frskyX_scaleForPXX( uint8_t i )
uint16_t frskyX_scaleForPXX(uint8_t i)
{ //mapped 860,2140(125%) range to 64,1984(PXX values);
uint16_t chan_val=convert_channel_frsky(i)-1226;
if(i>7) chan_val|=2048; // upper channels offset
return chan_val;
}
#ifdef FAILSAFE_ENABLE
static uint16_t __attribute__((unused)) frskyX_scaleForPXX_FS( uint8_t i )
uint16_t frskyX_scaleForPXX_FS(uint8_t i)
{ //mapped 1,2046(125%) range to 64,1984(PXX values);
uint16_t chan_val=((Failsafe_data[i]*15)>>4)+64;
if(Failsafe_data[i]==FAILSAFE_CHANNEL_NOPULSES)
@ -121,10 +126,8 @@ static uint16_t __attribute__((unused)) frskyX_scaleForPXX_FS( uint8_t i )
if(i>7) chan_val|=2048; // upper channels offset
return chan_val;
}
#endif
#define FRX_FAILSAFE_TIME 1032
static void __attribute__((unused)) frskyX_data_frame()
void frskyX_data_frame(void)
{
//0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12
//
@ -232,7 +235,7 @@ static void __attribute__((unused)) frskyX_data_frame()
packet[limit]=lcrc;//low byte
}
uint16_t ReadFrSkyX()
uint16_t ReadFrSkyX(void)
{
switch(state)
{
@ -323,7 +326,7 @@ uint16_t ReadFrSkyX()
return 1;
}
uint16_t initFrSkyX()
uint16_t initFrSkyX(void)
{
set_rx_tx_addr(MProtocol_id_master);
Frsky_init_hop();
@ -358,4 +361,3 @@ uint16_t initFrSkyX()
FrX_receive_seq = 0 ;
return 10000;
}
#endif

37
Multiprotocol/FrSkyX_cc2500.h

@ -0,0 +1,37 @@
/* **************************
* By Midelic on RCGroups *
**************************
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/>.
*/
#ifndef _FRSKYX_CC2500_H_
#define _FRSKYX_CC2500_H_
#include <stdint.h>
#define FRX_FAILSAFE_TIMEOUT 1032
#define FRX_FAILSAFE_TIME 1032
void frskyX_set_start(uint8_t ch);
void frskyX_init(void);
void frskyX_initialize_data(uint8_t adr);
uint16_t frskyX_CRCTable(uint8_t val);
uint16_t frskyX_crc_x(uint8_t *data, uint8_t len);
void frskyX_build_bind_packet(void);
uint16_t frskyX_scaleForPXX(uint8_t i);
uint16_t frskyX_scaleForPXX_FS(uint8_t i);
void frskyX_data_frame(void);
uint16_t ReadFrSkyX(void);
uint16_t initFrSkyX(void);
#endif

283
Multiprotocol/Multiprotocol.h

@ -13,252 +13,42 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _MULTIPROTOCOL_H_
#define _MULTIPROTOCOL_H_
//******************
// Version
//******************
#define VERSION_MAJOR 1
#define VERSION_MINOR 2
#define VERSION_REVISION 1
#define VERSION_PATCH_LEVEL 1
//******************
// Protocols
//******************
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
PROTO_FLYSKY = 1, // =>A7105
PROTO_HUBSAN = 2, // =>A7105
PROTO_FRSKYD = 3, // =>CC2500
PROTO_HISKY = 4, // =>NRF24L01
PROTO_V2X2 = 5, // =>NRF24L01
PROTO_DSM = 6, // =>CYRF6936
PROTO_DEVO = 7, // =>CYRF6936
PROTO_YD717 = 8, // =>NRF24L01
PROTO_KN = 9, // =>NRF24L01
PROTO_SYMAX = 10, // =>NRF24L01
PROTO_SLT = 11, // =>NRF24L01
PROTO_CX10 = 12, // =>NRF24L01
PROTO_CG023 = 13, // =>NRF24L01
PROTO_BAYANG = 14, // =>NRF24L01
PROTO_FRSKYX = 15, // =>CC2500
PROTO_ESKY = 16, // =>NRF24L01
PROTO_MT99XX = 17, // =>NRF24L01
PROTO_MJXQ = 18, // =>NRF24L01
PROTO_SHENQI = 19, // =>NRF24L01
PROTO_FY326 = 20, // =>NRF24L01
PROTO_SFHSS = 21, // =>CC2500
PROTO_J6PRO = 22, // =>CYRF6936
PROTO_FQ777 = 23, // =>NRF24L01
PROTO_ASSAN = 24, // =>NRF24L01
PROTO_FRSKYV = 25, // =>CC2500
PROTO_HONTAI = 26, // =>NRF24L01
PROTO_OPENLRS = 27, // =>OpenLRS hardware
PROTO_AFHDS2A = 28, // =>A7105
PROTO_Q2X2 = 29, // =>NRF24L01, extension of CX-10 protocol
PROTO_WK2x01 = 30, // =>CYRF6936
PROTO_Q303 = 31, // =>NRF24L01
PROTO_GW008 = 32, // =>NRF24L01
PROTO_DM002 = 33, // =>NRF24L01
PROTO_CABELL = 34, // =>NRF24L01
PROTO_ESKY150 = 35, // =>NRF24L01
PROTO_H8_3D = 36, // =>NRF24L01
PROTO_CORONA = 37, // =>CC2500
PROTO_CFLIE = 38, // =>NRF24L01
PROTO_HITEC = 39, // =>CC2500
PROTO_WFLY = 40, // =>CYRF6936
PROTO_BUGS = 41, // =>A7105
};
enum Flysky
{
Flysky = 0,
V9X9 = 1,
V6X6 = 2,
V912 = 3,
CX20 = 4,
};
enum Hubsan
{
H107 = 0,
H301 = 1,
H501 = 2,
};
enum AFHDS2A
{
PWM_IBUS = 0,
PPM_IBUS = 1,
PWM_SBUS = 2,
PPM_SBUS = 3,
};
enum Hisky
{
Hisky = 0,
HK310 = 1,
};
enum DSM
{
DSM2_22 = 0,
DSM2_11 = 1,
DSMX_22 = 2,
DSMX_11 = 3,
DSM_AUTO = 4,
};
enum YD717
{
YD717 = 0,
SKYWLKR = 1,
SYMAX4 = 2,
XINXUN = 3,
NIHUI = 4,
};
enum KN
{
WLTOYS = 0,
FEILUN = 1,
};
enum SYMAX
{
SYMAX = 0,
SYMAX5C = 1,
};
enum SLT
{
SLT_V1 = 0,
SLT_V2 = 1,
Q100 = 2,
Q200 = 3,
MR100 = 4,
};
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE = 1, // also compatible with CX10-A, CX12
DM007 = 2,
JC3015_1 = 4,
JC3015_2 = 5,
MK33041 = 6,
};
enum Q2X2
{
Q222 = 0,
Q242 = 1,
Q282 = 2,
F_Q222 = 8,
F_Q242 = 9,
F_Q282 = 10,
};
enum CG023
{
CG023 = 0,
YD829 = 1,
};
enum BAYANG
{
BAYANG = 0,
H8S3D = 1,
X16_AH = 2,
IRDRONE = 3,
};
enum MT99XX
{
MT99 = 0,
H7 = 1,
YZ = 2,
LS = 3,
FY805 = 4,
};
enum MJXQ
{
WLH08 = 0,
X600 = 1,
X800 = 2,
H26D = 3,
E010 = 4,
H26WH = 5,
};
enum FRSKYX
{
CH_16 = 0,
CH_8 = 1,
EU_16 = 2,
EU_8 = 3,
};
enum HONTAI
{
HONTAI = 0,
JJRCX1 = 1,
X5C1 = 2,
FQ777_951 =3,
};
enum V2X2
{
V2X2 = 0,
JXD506 = 1,
};
enum FY326
{
FY326 = 0,
FY319 = 1,
};
enum WK2x01
{
WK2801 = 0,
WK2401 = 1,
W6_5_1 = 2,
W6_6_1 = 3,
W6_HEL = 4,
W6_HEL_I= 5,
};
enum Q303
{
Q303 = 0,
CX35 = 1,
CX10D = 2,
CX10WD = 3,
};
enum CABELL
{
CABELL_V3 = 0,
CABELL_V3_TELEMETRY = 1,
CABELL_SET_FAIL_SAFE= 6,
CABELL_UNBIND = 7,
};
enum H8_3D
{
H8_3D = 0,
H20H = 1,
H20MINI = 2,
H30MINI = 3,
};
enum CORONA
{
COR_V1 = 0,
COR_V2 = 1,
FD_V3 = 2,
};
enum HITEC
{
OPT_FW = 0,
OPT_HUB = 1,
MINIMA = 2,
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
#define AUTOBIND 1
#define NO_AUTOBIND 0
struct PPM_Parameters
{
uint8_t protocol : 6;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
uint8_t power : 1;
uint8_t autobind : 1;
uint8_t option;
};
#include "tx_def.h"
#include "stdint.h"
void set_rx_tx_addr(uint32_t id);
#define MAX_PKT 29
extern volatile uint16_t PPM_data[NUM_CHN];
extern uint8_t hopping_frequency_no;
extern uint8_t sub_protocol;
extern uint8_t calData[48];
extern uint32_t MProtocol_id_master;
extern uint8_t protocol_flags;
extern uint8_t protocol_flags2;
extern uint8_t pkt[MAX_PKT];//telemetry receiving packets
extern uint8_t prev_option;
extern uint8_t prev_power; // unused power value
extern uint16_t counter;
extern uint8_t hopping_frequency[50];
extern uint8_t crc8;
extern uint16_t Channel_data[NUM_CHN];
extern uint8_t packet_count;
extern uint8_t RX_num;
extern uint8_t binding_idx;
extern uint8_t packet[40];
extern uint8_t rx_tx_addr[5];
extern uint8_t option;
extern uint16_t state;
extern uint16_t seed;
extern uint8_t phase;
extern uint8_t len;
// Telemetry
@ -277,7 +67,7 @@ enum MultiPacketTypes
};
// Macros
#define NOP() __asm__ __volatile__("nop")
#define _BV(i) (1<<i)
//***************
//*** Flags ***
@ -334,11 +124,6 @@ enum MultiPacketTypes
#define TX_RX_PAUSE_on protocol_flags2 |= _BV(4)
#define IS_TX_RX_PAUSE_on ( ( protocol_flags2 & _BV(4) ) !=0 )
#define IS_TX_PAUSE_on ( ( protocol_flags2 & (_BV(4)|_BV(3)) ) !=0 )
//Signal OK
#define INPUT_SIGNAL_off protocol_flags2 &= ~_BV(5)
#define INPUT_SIGNAL_on protocol_flags2 |= _BV(5)
#define IS_INPUT_SIGNAL_on ( ( protocol_flags2 & _BV(5) ) !=0 )
#define IS_INPUT_SIGNAL_off ( ( protocol_flags2 & _BV(5) ) ==0 )
//Bind from channel
#define BIND_CH_PREV_off protocol_flags2 &= ~_BV(6)
#define BIND_CH_PREV_on protocol_flags2 |= _BV(6)
@ -801,3 +586,5 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Full description at the bottom of Hitec_cc2500.ino
*/
#endif

205
Multiprotocol/Multiprotocol.ino

@ -32,32 +32,36 @@
#include "MultiOrange.h"
#endif
#include "config.h"
#include "tx_def.h"
#include "Multiprotocol.h"
//Multiprotocol module configuration file
#include "_Config.h"
#include "Pins.h"
#include "TX_Def.h"
#include "pins.h"
#include "Validate.h"
#include "common.h"
#include "state.h"
#include "input.h"
#include "cc2500_spi.h"
#include "FrSkyX_cc2500.h"
#include "FrSkyV_cc2500.h"
#include "FrSkyD_cc2500.h"
//Global constants/variables
uint32_t MProtocol_id;//tx id,
uint32_t MProtocol_id_master;
uint32_t blink=0,last_signal=0;
uint8_t protocol_flags=0,protocol_flags2=0;
//
uint16_t counter;
uint8_t channel;
uint8_t packet[40];
#define NUM_CHN 16
// Servo data
uint16_t Channel_data[NUM_CHN];
uint8_t Channel_AUX;
#ifdef FAILSAFE_ENABLE
uint16_t Failsafe_data[NUM_CHN];
#endif
// Protocol variables
uint8_t cyrfmfg_id[6];//for dsm2 and devo
@ -96,7 +100,6 @@ const uint8_t CH_EATR[]={ELEVATOR, AILERON, THROTTLE, RUDDER, CH5, CH6, CH7, CH8
// Mode_select variables
uint8_t mode_select;
uint8_t protocol_flags=0,protocol_flags2=0;
#ifdef ENABLE_PPM
// PPM variable
@ -126,7 +129,6 @@ volatile uint8_t rx_ok_buff[RXBUFFER_SIZE];
volatile uint8_t discard_frame = 0;
// Telemetry
#define MAX_PKT 29
uint8_t pkt[MAX_PKT];//telemetry receiving packets
float TIMER_PRESCALE = 5.82;
// Callback
@ -140,7 +142,7 @@ void setup()
#ifdef DEBUG_SERIAL
Serial.begin(115200,SERIAL_8N1);
while (!Serial); // Wait for ever for the serial port to connect...
debugln("Multiprotocol version: %d.%d.%d.%d", VERSION_MAJOR, VERSION_MINOR, VERSION_REVISION, VERSION_PATCH_LEVEL);
debugln("Multiprotocol startup");
debugln("time %s ", __TIME__);
#endif
@ -307,7 +309,7 @@ void setup()
else
#endif //ENABLE_PPM
debugln("Init complete");
update_inputs();
input.update();
init_state();
}
@ -316,111 +318,45 @@ void setup()
void loop()
{
uint32_t next_callback;
uint16_t diff=0xFFFF;
uint32_t end__ = micros();
uint32_t start = micros();
if(remote_callback==0 || IS_WAIT_BIND_on || diff>2*200)
{
do
{
if(remote_callback==0 || IS_WAIT_BIND_on ) {
do {
Update_All();
} while(remote_callback==0 || IS_WAIT_BIND_on);
}
while(remote_callback==0 || IS_WAIT_BIND_on);
}
while(1)
{
#if 0
if( (TIFR1 & OCF1A_bm) != 0)
{
cli(); // Disable global int due to RW of 16 bits registers
OCR1A=TCNT1; // Callback should already have been called... Use "now" as new sync point.
sei(); // Enable global int
}
else
while((TIFR1 & OCF1A_bm) == 0); // Wait before callback
#endif
uint32_t end__ = micros();
uint32_t start = micros();
end__ = micros();
do
{
//TX_MAIN_PAUSE_on;
//tx_pause();
while(1) {
start = end__;
next_callback = remote_callback();
#if 0
TX_MAIN_PAUSE_off;
tx_resume();
while(next_callback>4000)
{ // start to wait here as much as we can...
next_callback-=2000; // We will wait below for 2ms
cli(); // Disable global int due to RW of 16 bits registers
OCR1A += 2000 * TIMER_PRESCALE; // set compare A for callback
TIFR1=OCF1A_bm; // clear compare A=callback flag
sei(); // enable global int
if(Update_All()) // Protocol changed?
{
next_callback=0; // Launch new protocol ASAP
break;
}
while((TIFR1 & OCF1A_bm) == 0); // wait 2ms...
}
// at this point we have a maximum of 4ms in next_callback
cli(); // Disable global int due to RW of 16 bits registers
OCR1A+= next_callback*TIMER_PRESCALE ; // set compare A for callback
TIFR1=OCF1A_bm; // clear compare A=callback flag
diff=OCR1A-TCNT1; // compare timer and comparator
sei(); // enable global int
#else
if (next_callback > 4000) {
update_inputs();
input.update();
update_state();
}
uint32_t wait_until = start + next_callback;
end__ = micros();
if (end__-start < next_callback) {
uint32_t wait = next_callback;
wait -= ((end__-start));
//wait -= 1000;
delayMicroseconds(wait);
//debugln("%lu vs %lu",wait,next_callback);
/*
debugln("took %lu (%lu - %lu) vs %lu wait %lu wait until %lu",
end__-start, start, end__,
next_callback,
wait, wait_until);
*/
end__ += wait;
}
#endif
end__ = micros();
//debugln("%lu vs %lu",end__-start,next_callback);
//debugln("next %d diff %lu (%lu to %lu) diff %x ",org_next_call, end__ - start_, end__, start_, diff);
}
while(diff&0x8000); // Callback did not took more than requested time for next callback
// so we can launch Update_All before next callback
}
}
uint8_t Update_All()
{
#ifdef ENABLE_SERIAL
#ifdef CHECK_FOR_BOOTLOADER
if ( (mode_select==MODE_SERIAL) && (NotBootChecking == 0) )
pollBoot() ;
else
#endif
if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received
{
update_serial_data(); // Update protocol and data
update_channels_aux();
INPUT_SIGNAL_on; //valid signal received
last_signal=millis();
}
#endif //ENABLE_SERIAL
@ -428,8 +364,8 @@ uint8_t Update_All()
if(mode_select!=MODE_SERIAL && IS_PPM_FLAG_on) // PPM mode and a full frame has been received
{
debugln("%s:%d",__func__, __LINE__);
for(uint8_t i=0;i<PPM_chan_max;i++)
{ // update servo data without interrupts to prevent bad read
for(uint8_t i=0;i<PPM_chan_max;i++) {
// update servo data without interrupts to prevent bad read
uint16_t val;
cli(); // disable global int
val = PPM_data[i];
@ -441,7 +377,6 @@ uint8_t Update_All()
}
PPM_FLAG_off; // wait for next frame before update
update_channels_aux();
INPUT_SIGNAL_on; // valid signal received
last_signal=millis();
}
#endif //ENABLE_PPM
@ -470,9 +405,7 @@ uint8_t Update_All()
}
#endif //ENABLE_BIND_CH
update_inputs();
input.update();
if(IS_CHANGE_PROTOCOL_FLAG_on)
{
@ -641,26 +574,18 @@ static void protocol_init()
switch(protocol) // Init the requested protocol
{
#ifdef CC2500_INSTALLED
#if defined(FRSKYD_CC2500_INO)
case PROTO_FRSKYD:
next_callback = initFrSky_2way();
remote_callback = ReadFrSky_2way;
break;
#endif
#if defined(FRSKYV_CC2500_INO)
case PROTO_FRSKYV:
next_callback = initFRSKYV();
remote_callback = ReadFRSKYV;
break;
#endif
#if defined(FRSKYX_CC2500_INO)
case PROTO_FRSKYX:
next_callback = initFrSkyX();
remote_callback = ReadFrSkyX;
break;
#endif
#endif
}
}
@ -889,84 +814,10 @@ void modules_reset()
}
#endif
#ifdef CHECK_FOR_BOOTLOADER
void pollBoot()
{
uint8_t rxchar ;
uint8_t lState = BootState ;
uint8_t millisTime = millis(); // Call this once only
#ifdef ORANGE_TX
if ( USARTC0.STATUS & USART_RXCIF_bm )
#elif defined STM32_BOARD
if ( USART2_BASE->SR & USART_SR_RXNE )
#else
if ( UCSR0A & ( 1 << RXC0 ) )
#endif
{
rxchar = UDR0 ;
BootCount += 1 ;
if ( ( lState == BOOT_WAIT_30_IDLE ) || ( lState == BOOT_WAIT_30_DATA ) )
{
if ( lState == BOOT_WAIT_30_IDLE ) // Waiting for 0x30
BootTimer = millisTime ; // Start timeout
if ( rxchar == 0x30 )
lState = BOOT_WAIT_20 ;
else
lState = BOOT_WAIT_30_DATA ;
}
else
if ( lState == BOOT_WAIT_20 && rxchar == 0x20 ) // Waiting for 0x20
lState = BOOT_READY ;
}
else // No byte received
{
if ( lState != BOOT_WAIT_30_IDLE ) // Something received
{
uint8_t time = millisTime - BootTimer ;
if ( time > 5 )
{
#ifdef STM32_BOARD
if ( BootCount > 4 )
#else
if ( BootCount > 2 )
#endif
{ // Run normally
NotBootChecking = 0xFF ;
Mprotocol_serial_init( 0 ) ;
}
else if ( lState == BOOT_READY )
{
#ifdef STM32_BOARD
nvic_sys_reset();
while(1); /* wait until reset */
#else
cli(); // Disable global int due to RW of 16 bits registers
void (*p)();
#ifndef ORANGE_TX
p = (void (*)())0x3F00 ; // Word address (0x7E00 byte)
#else
p = (void (*)())0x4000 ; // Word address (0x8000 byte)
#endif
(*p)() ; // go to boot
#endif
}
else
{
lState = BOOT_WAIT_30_IDLE ;
BootCount = 0 ;
}
}
}
}
BootState = lState ;
}
#endif //CHECK_FOR_BOOTLOADER
#if defined(TELEMETRY)
void PPM_Telemetry_serial_init()
{
if( (protocol==PROTO_FRSKYD) || (protocol==PROTO_HUBSAN) || (protocol==PROTO_AFHDS2A) || (protocol==PROTO_BAYANG) || (protocol==PROTO_CABELL) || (protocol==PROTO_HITEC) || (protocol==PROTO_BUGS))
if( (protocol==PROTO_FRSKYD))
initTXSerial( SPEED_9600 ) ;
if(protocol==PROTO_FRSKYX)
initTXSerial( SPEED_57600 ) ;
@ -976,7 +827,7 @@ void PPM_Telemetry_serial_init()
#endif
// Convert 32b id to rx_tx_addr
static void set_rx_tx_addr(uint32_t id)
void set_rx_tx_addr(uint32_t id)
{ // Used by almost all protocols
rx_tx_addr[0] = (id >> 24) & 0xFF;
rx_tx_addr[1] = (id >> 16) & 0xFF;
@ -985,7 +836,7 @@ static void set_rx_tx_addr(uint32_t id)
rx_tx_addr[4] = (rx_tx_addr[2]&0xF0)|(rx_tx_addr[3]&0x0F);
}
static uint32_t random_id(uint16_t address, uint8_t create_new)
uint32_t random_id(uint16_t address, uint8_t create_new)
{
#ifndef FORCE_GLOBAL_ID
uint32_t id=0;

211
Multiprotocol/TX_Def.h

@ -1,211 +0,0 @@
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX_100 2012 // 100%
#define PPM_MIN_100 988 // 100%
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// Multiplex MC2020
#if defined(TX_MPX)
#define PPM_MAX_100 1950 // 100%
#define PPM_MIN_100 1250 // 100%
#endif
// Walkera PL0811-01H
#if defined(TX_WALKERA)
#define PPM_MAX_100 1800 // 100%
#define PPM_MIN_100 1000 // 100%
#endif
//Channel MIN MAX values
#define CHANNEL_MAX_100 1844 // 100%
#define CHANNEL_MIN_100 204 // 100%
#define CHANNEL_MAX_125 2047 // 125%
#define CHANNEL_MIN_125 0 // 125%
#define CHANNEL_MIN_COMMAND 784 // 1350us
#define CHANNEL_SWITCH 1104 // 1550us
#define CHANNEL_MAX_COMMAND 1424 // 1750us
//Channel definitions
#ifdef AETR
#define AILERON 0
#define ELEVATOR 1
#define THROTTLE 2
#define RUDDER 3
#endif
#ifdef AERT
#define AILERON 0
#define ELEVATOR 1
#define THROTTLE 3
#define RUDDER 2
#endif
#ifdef ARET
#define AILERON 0
#define ELEVATOR 2
#define THROTTLE 3
#define RUDDER 1
#endif
#ifdef ARTE
#define AILERON 0
#define ELEVATOR 3
#define THROTTLE 2
#define RUDDER 1
#endif
#ifdef ATRE
#define AILERON 0
#define ELEVATOR 3
#define THROTTLE 1
#define RUDDER 2
#endif
#ifdef ATER
#define AILERON 0
#define ELEVATOR 2
#define THROTTLE 1
#define RUDDER 3
#endif
#ifdef EATR
#define AILERON 1
#define ELEVATOR 0
#define THROTTLE 2
#define RUDDER 3
#endif
#ifdef EART
#define AILERON 1
#define ELEVATOR 0
#define THROTTLE 3
#define RUDDER 2
#endif
#ifdef ERAT
#define AILERON 2
#define ELEVATOR 0
#define THROTTLE 3
#define RUDDER 1
#endif
#ifdef ERTA
#define AILERON 3
#define ELEVATOR 0
#define THROTTLE 2
#define RUDDER 1
#endif
#ifdef ETRA
#define AILERON 3
#define ELEVATOR 0
#define THROTTLE 1
#define RUDDER 2
#endif
#ifdef ETAR
#define AILERON 2
#define ELEVATOR 0
#define THROTTLE 1
#define RUDDER 3
#endif
#ifdef TEAR
#define AILERON 2
#define ELEVATOR 1
#define THROTTLE 0
#define RUDDER 3
#endif
#ifdef TERA
#define AILERON 3
#define ELEVATOR 1
#define THROTTLE 0
#define RUDDER 2
#endif
#ifdef TREA
#define AILERON 3
#define ELEVATOR 2
#define THROTTLE 0
#define RUDDER 1
#endif
#ifdef TRAE
#define AILERON 2
#define ELEVATOR 3
#define THROTTLE 0
#define RUDDER 1
#endif
#ifdef TARE
#define AILERON 1
#define ELEVATOR 3
#define THROTTLE 0
#define RUDDER 2
#endif
#ifdef TAER
#define AILERON 1
#define ELEVATOR 2
#define THROTTLE 0
#define RUDDER 3
#endif
#ifdef RETA
#define AILERON 3
#define ELEVATOR 1
#define THROTTLE 2
#define RUDDER 0
#endif
#ifdef REAT
#define AILERON 2
#define ELEVATOR 1
#define THROTTLE 3
#define RUDDER 0
#endif
#ifdef RAET
#define AILERON 1
#define ELEVATOR 2
#define THROTTLE 3
#define RUDDER 0
#endif
#ifdef RATE
#define AILERON 1
#define ELEVATOR 3
#define THROTTLE 2
#define RUDDER 0
#endif
#ifdef RTAE
#define AILERON 2
#define ELEVATOR 3
#define THROTTLE 1
#define RUDDER 0
#endif
#ifdef RTEA
#define AILERON 3
#define ELEVATOR 2
#define THROTTLE 1
#define RUDDER 0
#endif
#define CH1 0
#define CH2 1
#define CH3 2
#define CH4 3
#define CH5 4
#define CH6 5
#define CH7 6
#define CH8 7
#define CH9 8
#define CH10 9
#define CH11 10
#define CH12 11
#define CH13 12
#define CH14 13
#define CH15 14
#define CH16 15

7
Multiprotocol/Validate.h

@ -1,3 +1,8 @@
#ifndef _VALIDATE_H_
#define _VALIDATE_H_
#include "config.h"
#include "tx_def.h"
// Check selected board type
#if defined (STM32_BOARD) && defined (ORANGE_TX)
#error You must comment the board type STM32_BOARD in _Config.h to compile ORANGE_TX
@ -272,3 +277,5 @@
#if MAX_PPM_CHANNELS>16
#error MAX_PPM_CHANNELS must be below or equal to 16. The default for this value is 16.
#endif
#endif

64
Multiprotocol/CC2500_SPI.ino → Multiprotocol/cc2500_spi.cpp

@ -18,10 +18,11 @@
//CC2500 SPI routines
//-------------------------------
//-------------------------------
#ifdef CC2500_INSTALLED
#include "iface_cc2500.h"
#include <stdint.h>
#include "pins.h"
#include "cc2500_spi.h"
#include "spi.h"
//----------------------------
void CC2500_WriteReg(uint8_t address, uint8_t data)
{
CC25_CSN_off;
@ -31,8 +32,7 @@ void CC2500_WriteReg(uint8_t address, uint8_t data)
CC25_CSN_on;
}
//----------------------
static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
{
CC25_CSN_off;
SPI_Write(CC2500_READ_BURST | address);
@ -41,8 +41,7 @@ static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t le
CC25_CSN_on;
}
//--------------------------------------------
static uint8_t CC2500_ReadReg(uint8_t address)
uint8_t CC2500_ReadReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
@ -52,13 +51,11 @@ static uint8_t CC2500_ReadReg(uint8_t address)
return(result);
}
//------------------------
void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len)
{
CC2500_ReadRegisterMulti(CC2500_3F_RXFIFO, dpbuffer, len);
}
//*********************************************
void CC2500_Strobe(uint8_t state)
{
CC25_CSN_off;
@ -66,7 +63,7 @@ void CC2500_Strobe(uint8_t state)
CC25_CSN_on;
}
static void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
{
CC25_CSN_off;
SPI_Write(CC2500_WRITE_BURST | address);
@ -84,38 +81,20 @@ void CC2500_WriteData(uint8_t *dpbuffer, uint8_t len)
void CC2500_SetTxRxMode(uint8_t mode)
{
if(mode == TX_EN)
{//from deviation firmware
if(mode == TX_EN) {
//from deviation firmware
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F | 0x40);
}
else
if (mode == RX_EN)
{
} else {
if (mode == RX_EN) {
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F | 0x40);
}
else
{
} else {
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
}
}
//------------------------
/*static void cc2500_resetChip(void)
{
// Toggle chip select signal
CC25_CSN_on;
delayMicroseconds(30);
CC25_CSN_off;
delayMicroseconds(30);
CC25_CSN_on;
delayMicroseconds(45);
CC2500_Strobe(CC2500_SRES);
_delay_ms(100);
}
*/
uint8_t CC2500_Reset()
{
CC2500_Strobe(CC2500_SRES);
@ -123,24 +102,6 @@ uint8_t CC2500_Reset()
CC2500_SetTxRxMode(TXRX_OFF);
return CC2500_ReadReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
}
/*
static void CC2500_SetPower_Value(uint8_t power)
{
const unsigned char patable[8]= {
0xC5, // -12dbm
0x97, // -10dbm
0x6E, // -8dbm
0x7F, // -6dbm
0xA9, // -4dbm
0xBB, // -2dbm
0xFE, // 0dbm
0xFF // 1.5dbm
};
if (power > 7)
power = 7;
CC2500_WriteReg(CC2500_3E_PATABLE, patable[power]);
}
*/
void CC2500_SetPower()
{
uint8_t power=CC2500_BIND_POWER;
@ -158,4 +119,3 @@ void CC2500_SetPower()
prev_power=power;
}
}
#endif

33
Multiprotocol/iface_cc2500.h → Multiprotocol/cc2500_spi.h

@ -1,3 +1,4 @@
/*
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
@ -12,9 +13,29 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
//-------------------------------
//-------------------------------
//CC2500 SPI routines
//-------------------------------
//-------------------------------
#ifndef _CC2500_SPI_
#define _CC2500_SPI_
#include <stdint.h>
#include "Multiprotocol.h"
void CC2500_WriteReg(uint8_t address, uint8_t data);
#ifndef _IFACE_CC2500_H_
#define _IFACE_CC2500_H_
void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length);
uint8_t CC2500_ReadReg(uint8_t address);
void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len);
void CC2500_Strobe(uint8_t state);
void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length);
void CC2500_WriteData(uint8_t *dpbuffer, uint8_t len);
void CC2500_SetTxRxMode(uint8_t mode);
uint8_t CC2500_Reset();
void CC2500_SetPower();
#include <stdint.h>
enum {
CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration
@ -139,12 +160,4 @@ enum {
#define CC2500_LQI_CRC_OK_BM 0x80
#define CC2500_LQI_EST_BM 0x7F
//void CC2500_WriteReg(u8 addr, u8 data);
//u8 CC2500_ReadReg(u8 addr);
//void CC2500_Reset();
//void CC2500_Strobe(u8 cmd);
//void CC2500_WriteData(u8 *packet, u8 length);
//void CC2500_ReadData(u8 *dpbuffer, int len);
//void CC2500_SetTxRxMode(enum TXRX_State);
#endif

51
Multiprotocol/Common.ino → Multiprotocol/common.cpp

@ -12,8 +12,18 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#include "config.h"
#include "tx_def.h"
#include "common.h"
#include "Multiprotocol.h"
#include "cc2500_spi.h"
void InitFailsafe()
#ifdef FAILSAFE_ENABLE
uint16_t Failsafe_data[NUM_CHN];
#endif
void InitFailsafe(void)
{
for (uint8_t i = 0; i < NUM_CHN; i++)
Failsafe_data[i] = 1024;
@ -21,14 +31,14 @@ void InitFailsafe()
FAILSAFE_VALUES_on;
}
void InitPPM()
void InitPPM(void)
{
for(uint8_t i=0;i<NUM_CHN;i++)
PPM_data[i]=PPM_MAX_100+PPM_MIN_100;
PPM_data[THROTTLE]=PPM_MIN_100*2;
}
void InitChannel()
void InitChannel(void)
{
for (uint8_t i = 0; i < NUM_CHN; i++)
Channel_data[i] = 1024;
@ -56,8 +66,10 @@ uint16_t convert_channel_10b(uint8_t num)
{
uint16_t val = Channel_data[num];
val = ((val << 2) + val) >> 3;
if (val <= 128) return 0;
if (val >= 1152) return 1023;
if (val <= 128)
return 0;
if (val >= 1152)
return 1023;
return val - 128;
}
// Channel value 100% is converted to 8bit values 0<->255
@ -133,15 +145,6 @@ uint16_t convert_channel_frsky(uint8_t num)
/** FrSky D and X routines **/
/******************************/
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
FRSKY_DATA1,
FRSKY_DATA2,
FRSKY_DATA3,
FRSKY_DATA4,
FRSKY_DATA5
};
void Frsky_init_hop(void)
{
@ -168,7 +171,7 @@ void Frsky_init_hop(void)
/** FrSky V, D and X routines **/
/******************************/
#if defined(FRSKYV_CC2500_INO) || defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
const PROGMEM uint8_t FRSKY_common_startreg_cc2500_conf[] = {
uint8_t FRSKY_common_startreg_cc2500_conf[] = {
CC2500_02_IOCFG0 ,
CC2500_00_IOCFG2 ,
CC2500_17_MCSM1 ,
@ -191,7 +194,7 @@ const PROGMEM uint8_t FRSKY_common_startreg_cc2500_conf[] = {
};
#if defined(FRSKYV_CC2500_INO)
const PROGMEM uint8_t FRSKYV_cc2500_conf[] = {
uint8_t FRSKYV_cc2500_conf[] = {
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
/*17_MCSM1*/ 0x0c ,
@ -215,7 +218,7 @@ const PROGMEM uint8_t FRSKYV_cc2500_conf[] = {
#endif
#if defined(FRSKYD_CC2500_INO)
const PROGMEM uint8_t FRSKYD_cc2500_conf[] = {
uint8_t FRSKYD_cc2500_conf[] = {
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
/*17_MCSM1*/ 0x0c ,
@ -239,7 +242,7 @@ const PROGMEM uint8_t FRSKYD_cc2500_conf[] = {
#endif
#if defined(FRSKYX_CC2500_INO)
const PROGMEM uint8_t FRSKYX_cc2500_conf[] = {
uint8_t FRSKYX_cc2500_conf[] = {
//FRSKYX
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
@ -261,7 +264,7 @@ const PROGMEM uint8_t FRSKYX_cc2500_conf[] = {
/*14_MDMCFG0*/ 0x7a ,
/*15_DEVIATN*/ 0x51
};
const PROGMEM uint8_t FRSKYXEU_cc2500_conf[] = {
uint8_t FRSKYXEU_cc2500_conf[] = {
/*02_IOCFG0*/ 0x06 ,
/*00_IOCFG2*/ 0x06 ,
/*17_MCSM1*/ 0x0E ,
@ -284,7 +287,7 @@ const PROGMEM uint8_t FRSKYXEU_cc2500_conf[] = {
};
#endif
const PROGMEM uint8_t FRSKY_common_end_cc2500_conf[][2] = {
uint8_t FRSKY_common_end_cc2500_conf[][2] = {
{ CC2500_19_FOCCFG, 0x16 },
{ CC2500_1A_BSCFG, 0x6c },
{ CC2500_1B_AGCCTRL2, 0x43 },
@ -308,8 +311,8 @@ void FRSKY_init_cc2500(const uint8_t *ptr)
{
for (uint8_t i = 0; i < 19; i++)
{
uint8_t reg = pgm_read_byte_near(&FRSKY_common_startreg_cc2500_conf[i]);
uint8_t val = pgm_read_byte_near(&ptr[i]);
uint8_t reg = FRSKY_common_startreg_cc2500_conf[i];
uint8_t val = ptr[i];
if (reg == CC2500_0C_FSCTRL0)
val = option;
CC2500_WriteReg(reg, val);
@ -317,8 +320,8 @@ void FRSKY_init_cc2500(const uint8_t *ptr)
prev_option = option ; // Save option to monitor FSCTRL0 change
for (uint8_t i = 0; i < 17; i++)
{
uint8_t reg = pgm_read_byte_near(&FRSKY_common_end_cc2500_conf[i][0]);
uint8_t val = pgm_read_byte_near(&FRSKY_common_end_cc2500_conf[i][1]);
uint8_t reg = FRSKY_common_end_cc2500_conf[i][0];
uint8_t val = FRSKY_common_end_cc2500_conf[i][1];
CC2500_WriteReg(reg, val);
}
CC2500_SetTxRxMode(TX_EN);

77
Multiprotocol/common.h

@ -0,0 +1,77 @@
/*
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/>.
*/
#ifndef _COMMON_H_
#define _COMMON_H_
#include <stdint.h>
#include "config.h"
#include "tx_def.h"
void InitFailsafe(void);
void InitPPM(void);
void InitChannel(void);
void reverse_channel(uint8_t num);
uint16_t convert_channel_ppm(uint8_t num);
uint16_t convert_channel_10b(uint8_t num);
uint8_t convert_channel_8b(uint8_t num);
int16_t convert_channel_16b_limit(uint8_t num, int16_t min, int16_t max);
int16_t convert_channel_16b_nolimit(uint8_t num, int16_t min, int16_t max);
uint8_t convert_channel_s8b(uint8_t num);
uint16_t limit_channel_100(uint8_t num);
void convert_channel_HK310(uint8_t num, uint8_t *low, uint8_t *high);
void convert_failsafe_HK310(uint8_t num, uint8_t *low, uint8_t *high);
uint16_t convert_channel_frsky(uint8_t num);
/******************************/
/** FrSky D and X routines **/
/******************************/
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
FRSKY_DATA1,
FRSKY_DATA2,
FRSKY_DATA3,
FRSKY_DATA4,
FRSKY_DATA5
};
void Frsky_init_hop(void);
/******************************/
/** FrSky V, D and X routines **/
/******************************/
#if defined(FRSKYV_CC2500_INO) || defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO)
extern uint8_t FRSKY_common_startreg_cc2500_conf[];
#if defined(FRSKYV_CC2500_INO)
extern uint8_t FRSKYV_cc2500_conf[];
#endif
#if defined(FRSKYD_CC2500_INO)
extern uint8_t FRSKYD_cc2500_conf[];
#endif
#if defined(FRSKYX_CC2500_INO)
extern uint8_t FRSKYX_cc2500_conf[];
extern uint8_t FRSKYXEU_cc2500_conf[];
#endif
extern uint8_t FRSKY_common_end_cc2500_conf[][2];
void FRSKY_init_cc2500(const uint8_t *ptr);
#ifdef FAILSAFE_ENABLE
extern uint16_t Failsafe_data[NUM_CHN];
#endif
#endif
#endif

235
Multiprotocol/config.cpp

@ -0,0 +1,235 @@
/*
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/>.
*/
#include "config.h"
uint8_t curr_bank = 0;
const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
//****************************** BANK 1 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 0 },
/* 2 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 20 },
/* 3 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 40 },
/* 4 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 60 },
/* 5 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 80 },
/* 6 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 100 },
/* 7 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 120 },
/* 8 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 140 },
/* 9 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 160 },
/* 10 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 180 },
/* 11 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 200 },
/* 12 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 220 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 240 },
/* 14 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 255 },
//****************************** BANK 2 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -120 },
/* 2 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -100 },
/* 3 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -80 },
/* 4 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -60 },
/* 5 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -40 },
/* 6 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -20 },
/* 7 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 0 },
/* 8 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 10 },
/* 9 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 20 },
/* 10 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 40 },
/* 11 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 60 },
/* 12 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 80 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 100 },
/* 14 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 120 },
//****************************** BANK 3 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -120 },
/* 2 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -100 },
/* 3 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -80 },
/* 4 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -60 },
/* 5 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -40 },
/* 6 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -20 },
/* 7 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 0 },
/* 8 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 10 },
/* 9 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 20 },
/* 10 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 40 },
/* 11 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 60 },
/* 12 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 80 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 100 },
/* 14 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 120 },
};
/* Available protocols and associated sub protocols to pick and choose from
PROTO_FLYSKY
Flysky
V9X9
V6X6
V912
CX20
PROTO_HUBSAN
H107
H301
H501
PROTO_FRSKYV
NONE
PROTO_FRSKYD
NONE
PROTO_FRSKYX
CH_16
CH_8
EU_16
EU_8
PROTO_HISKY
Hisky
HK310
PROTO_V2X2
V2X2
JXD506
PROTO_DSM
DSM2_22
DSM2_11
DSMX_22
DSMX_11
PROTO_DEVO
NONE
PROTO_YD717
YD717
SKYWLKRP_LOW
SYMAX4
XINXUN
NIHUI
PROTO_KN
WLTOYS
FEILUN
PROTO_SYMAX
SYMAX
SYMAX5C
PROTO_SLT
NONE
PROTO_CX10
CX10_GREEN
CX10_BLUE
DM007
JC3015_1
JC3015_2
MK33041
PROTO_Q2X2
Q222
Q242
Q282
PROTO_SLT
SLT
VISTA
PROTO_CG023
CG023
YD829
PROTO_BAYANG
BAYANG
H8S3D
X16_AH
IRDRONE
PROTO_ESKY
NONE
PROTO_MT99XX
MT99
H7
YZ
LS
FY805
PROTO_MJXQ
WLH08
X600
X800
H26D
E010
H26WH
PROTO_SHENQI
NONE
PROTO_FY326
FY326
FY319
PROTO_SFHSS
NONE
PROTO_J6PRO
NONE
PROTO_FQ777
NONE
PROTO_ASSAN
NONE
PROTO_HONTAI
HONTAI
JJRCX1
X5C1
FQ777_951
PROTO_AFHDS2A
PWM_IBUS
PPM_IBUS
PWM_SBUS
PPM_SBUS
PROTO_WK2x01
WK2801
WK2401
W6_5_1
W6_6_1
W6_HEL
W6_HEL_I
PROTO_Q303
Q303
CX35
CX10D
CX10WD
PROTO_GW008
NONE
PROTO_DM002
NONE
PROTO_CABELL
CABELL_V3
CABELL_V3_TELEMETRY
CABELL_SET_FAIL_SAFE
CABELL_UNBIND
PROTO_ESKY150
PROTO_H8_3D
H8_3D
H20H
H20MINI
H30MINI
PROTO_CORONA
COR_V1
COR_V2
FD_V3
PROTO_CFLIE
NONE
PROTO_HITEC
OPT_FW
OPT_HUB
MINIMA
PROTO_WFLY
NONE
PROTO_BUGS
NONE
PROTO_SLT
SLT_V1
SLT_V2
Q100
Q200
MR100
*/
// RX_Num is used for TX & RX match. Using different RX_Num values for each receiver will prevent starting a model with the false config loaded...
// RX_Num value is between 0 and 15.
// Power P_HIGH or P_LOW: High or low power setting for the transmission.
// For indoor P_LOW is more than enough.
// Auto Bind AUTOBIND or NO_AUTOBIND
// For protocols which does not require binding at each power up (like Flysky, FrSky...), you might still want a bind to be initiated each time you power up the TX.
// As an example, it's usefull for the WLTOYS F929/F939/F949/F959 (all using the Flysky protocol) which requires a bind at each power up.
// It also enables the Bind from channel feature, allowing to execute a bind by toggling a designated channel.
// Option: the value is between -128 and +127.
// The option value is only valid for some protocols, read this page for more information: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md

311
Multiprotocol/_Config.h → Multiprotocol/config.h

@ -12,7 +12,10 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _CONFIG_H_
#define _CONFIG_H_
#include <stdint.h>
/**********************************************/
/** Multiprotocol module configuration file ***/
/**********************************************/
@ -202,10 +205,6 @@
// - If you put too low values you won't be able to use your full stick range, it will be maxed out before reaching the ends
// - Centered stick value is usually 1500. It should match the middle between MIN and MAX, ie Center=(MAX+MIN)/2. If your TX is not centered you can adjust the value MIN or MAX.
// - 100% is referred as the value when the TX is set to default with no trims
#if defined(TX_CUSTOM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#endif
/** Number of PPM Channels **/
// The line below is used to set the minimum number of channels which the module should receive to consider a PPM frame valid.
@ -215,240 +214,82 @@
// The default value is 16 to receive all possible channels but you might want to filter some "bad" channels from the PPM frame like the ones above 6 on the Walkera PL0811.
#define MAX_PPM_CHANNELS 16
/** Rotary Switch Protocol Selector Settings **/
//The table below indicates which protocol to run when a specific position on the rotary switch has been selected.
//All fields and values are explained below. Everything is configurable from here like in the Serial mode.
//Tip: You can associate multiple times the same protocol to different rotary switch positions to take advantage of the model match based on RX_Num
#define NBR_BANKS 3
extern uint8_t curr_bank;
//A system of banks enable the access to more protocols than positions on the rotary switch. Banks can be selected by placing the rotary switch on position 15, power up the module and
// short press the bind button multiple times until you reach the desired one. The bank number currently selected is indicated by the number of LED flash.
// Full procedure is located here: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md#protocol-selection-in-ppm-mode
struct PPM_Parameters
{
uint8_t protocol : 6;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
//The parameter below indicates the number of desired banks between 1 and 5. Default is 5.
#define NBR_BANKS 3
uint8_t curr_bank = 0;
const PPM_Parameters PPM_prot[14*NBR_BANKS]= {
#if NBR_BANKS > 0
//****************************** BANK 1 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 0 },
/* 2 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 20 },
/* 3 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 40 },
/* 4 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 60 },
/* 5 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 80 },
/* 6 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 100 },
/* 7 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 120 },
/* 8 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 140 },
/* 9 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 160 },
/* 10 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 180 },
/* 11 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 200 },
/* 12 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 220 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 240 },
/* 14 */ {PROTO_FRSKYD, 0 , 0 , P_LOW , AUTOBIND , 255 },
#endif
#if NBR_BANKS > 1
//****************************** BANK 2 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -120 },
/* 2 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -100 },
/* 3 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -80 },
/* 4 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -60 },
/* 5 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -40 },
/* 6 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , -20 },
/* 7 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 0 },
/* 8 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 10 },
/* 9 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 20 },
/* 10 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 40 },
/* 11 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 60 },
/* 12 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 80 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 100 },
/* 14 */ {PROTO_FRSKYX, EU_16 , 0 , P_LOW , AUTOBIND , 120 },
#endif
#if NBR_BANKS > 2
//****************************** BANK 3 ******************************
// Switch Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -120 },
/* 2 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -100 },
/* 3 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -80 },
/* 4 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -60 },
/* 5 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -40 },
/* 6 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , -20 },
/* 7 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 0 },
/* 8 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 10 },
/* 9 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 20 },
/* 10 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 40 },
/* 11 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 60 },
/* 12 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 80 }, // option=fine freq tuning
/* 13 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 100 },
/* 14 */ {PROTO_FRSKYX, CH_16 , 0 , P_LOW , AUTOBIND , 120 },
#endif
};
/* Available protocols and associated sub protocols to pick and choose from
PROTO_FLYSKY
Flysky
V9X9
V6X6
V912
CX20
PROTO_HUBSAN
H107
H301
H501
PROTO_FRSKYV
NONE
PROTO_FRSKYD
NONE
PROTO_FRSKYX
CH_16
CH_8
EU_16
EU_8
PROTO_HISKY
Hisky
HK310
PROTO_V2X2
V2X2
JXD506
PROTO_DSM
DSM2_22
DSM2_11
DSMX_22
DSMX_11
PROTO_DEVO
NONE
PROTO_YD717
YD717
SKYWLKRP_LOW
SYMAX4
XINXUN
NIHUI
PROTO_KN
WLTOYS
FEILUN
PROTO_SYMAX
SYMAX
SYMAX5C
PROTO_SLT
NONE
PROTO_CX10
CX10_GREEN
CX10_BLUE
DM007
JC3015_1
JC3015_2
MK33041
PROTO_Q2X2
Q222
Q242
Q282
PROTO_SLT
SLT
VISTA
PROTO_CG023
CG023
YD829
PROTO_BAYANG
BAYANG
H8S3D
X16_AH
IRDRONE
PROTO_ESKY
NONE
PROTO_MT99XX
MT99
H7
YZ
LS
FY805
PROTO_MJXQ
WLH08
X600
X800
H26D
E010
H26WH
PROTO_SHENQI
NONE
PROTO_FY326
FY326
FY319
PROTO_SFHSS
NONE
PROTO_J6PRO
NONE
PROTO_FQ777
NONE
PROTO_ASSAN
NONE
PROTO_HONTAI
HONTAI
JJRCX1
X5C1
FQ777_951
PROTO_AFHDS2A
PWM_IBUS
PPM_IBUS
PWM_SBUS
PPM_SBUS
PROTO_WK2x01
WK2801
WK2401
W6_5_1
W6_6_1
W6_HEL
W6_HEL_I
PROTO_Q303
Q303
CX35
CX10D
CX10WD
PROTO_GW008
NONE
PROTO_DM002
NONE
PROTO_CABELL
CABELL_V3
CABELL_V3_TELEMETRY
CABELL_SET_FAIL_SAFE
CABELL_UNBIND
PROTO_ESKY150
PROTO_H8_3D
H8_3D
H20H
H20MINI
H30MINI
PROTO_CORONA
COR_V1
COR_V2
FD_V3
PROTO_CFLIE
NONE
PROTO_HITEC
OPT_FW
OPT_HUB
MINIMA
PROTO_WFLY
NONE
PROTO_BUGS
NONE
PROTO_SLT
SLT_V1
SLT_V2
Q100
Q200
MR100
*/
#define P_HIGH 1
#define P_LOW 0
uint8_t power : 1;
#define AUTOBIND 1
#define NO_AUTOBIND 0
uint8_t autobind : 1;
// RX_Num is used for TX & RX match. Using different RX_Num values for each receiver will prevent starting a model with the false config loaded...
// RX_Num value is between 0 and 15.
uint8_t option;
};
// Power P_HIGH or P_LOW: High or low power setting for the transmission.
// For indoor P_LOW is more than enough.
//******************
// Protocols
//******************
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
PROTO_FLYSKY = 1, // =>A7105
PROTO_HUBSAN = 2, // =>A7105
PROTO_FRSKYD = 3, // =>CC2500
PROTO_HISKY = 4, // =>NRF24L01
PROTO_V2X2 = 5, // =>NRF24L01
PROTO_DSM = 6, // =>CYRF6936
PROTO_DEVO = 7, // =>CYRF6936
PROTO_YD717 = 8, // =>NRF24L01
PROTO_KN = 9, // =>NRF24L01
PROTO_SYMAX = 10, // =>NRF24L01
PROTO_SLT = 11, // =>NRF24L01
PROTO_CX10 = 12, // =>NRF24L01
PROTO_CG023 = 13, // =>NRF24L01
PROTO_BAYANG = 14, // =>NRF24L01
PROTO_FRSKYX = 15, // =>CC2500
PROTO_ESKY = 16, // =>NRF24L01
PROTO_MT99XX = 17, // =>NRF24L01
PROTO_MJXQ = 18, // =>NRF24L01
PROTO_SHENQI = 19, // =>NRF24L01
PROTO_FY326 = 20, // =>NRF24L01
PROTO_SFHSS = 21, // =>CC2500
PROTO_J6PRO = 22, // =>CYRF6936
PROTO_FQ777 = 23, // =>NRF24L01
PROTO_ASSAN = 24, // =>NRF24L01
PROTO_FRSKYV = 25, // =>CC2500
PROTO_HONTAI = 26, // =>NRF24L01
PROTO_OPENLRS = 27, // =>OpenLRS hardware
PROTO_AFHDS2A = 28, // =>A7105
PROTO_Q2X2 = 29, // =>NRF24L01, extension of CX-10 protocol
PROTO_WK2x01 = 30, // =>CYRF6936
PROTO_Q303 = 31, // =>NRF24L01
PROTO_GW008 = 32, // =>NRF24L01
PROTO_DM002 = 33, // =>NRF24L01
PROTO_CABELL = 34, // =>NRF24L01
PROTO_ESKY150 = 35, // =>NRF24L01
PROTO_H8_3D = 36, // =>NRF24L01
PROTO_CORONA = 37, // =>CC2500
PROTO_CFLIE = 38, // =>NRF24L01
PROTO_HITEC = 39, // =>CC2500
PROTO_WFLY = 40, // =>CYRF6936
PROTO_BUGS = 41, // =>A7105
};
// Auto Bind AUTOBIND or NO_AUTOBIND
// For protocols which does not require binding at each power up (like Flysky, FrSky...), you might still want a bind to be initiated each time you power up the TX.
// As an example, it's usefull for the WLTOYS F929/F939/F949/F959 (all using the Flysky protocol) which requires a bind at each power up.
// It also enables the Bind from channel feature, allowing to execute a bind by toggling a designated channel.
enum FRSKYX_SUP_PROTOCOL
{
CH_16 = 0,
CH_8 = 1,
EU_16 = 2,
EU_8 = 3,
};
// Option: the value is between -128 and +127.
// The option value is only valid for some protocols, read this page for more information: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md
extern const PPM_Parameters PPM_prot[14*NBR_BANKS];
#endif

6
Multiprotocol/debug.h

@ -1,5 +1,7 @@
#ifndef DEBUG_H
#define DEBUG_H
#ifndef _DEBUG_H_
#define _DEBUG_H_
#include "Arduino.h"
#include <stdio.h>
//********************
//** Debug messages **

77
Multiprotocol/input.cpp

@ -0,0 +1,77 @@
#include "Arduino.h"
#include <string.h>
#include "config.h"
#include "tx_def.h"
#include "Multiprotocol.h"
#include "input.h"
#include "pins.h"
#include "state.h"
Input input;
Input::Input(void) {
this->curr = &(this->input[0]);
this->old = &(this->input[1]);
memset(this->input,0, sizeof(this->input));
}
void Input::mark_processed(void) {
struct data* temp = this->old;
this->old = this->curr;
this->curr = temp;
}
struct Input::data* Input::get_curr_input(void) {
return this->curr;
}
struct Input::data* Input::get_old_input(void) {
return this->old;
}
void Input::update(void) {
this->curr->throttle = analogRead(Throttle_pin);
this->curr->yaw = analogRead(Yaw_pin);
this->curr->roll = analogRead(Roll_pin);
this->curr->pitch = analogRead(Pitch_pin);
this->curr->aux[0] = digitalRead(Aux1_pin);
this->curr->aux[1] = digitalRead(Aux2_pin);
this->curr->aux[2] = digitalRead(Aux3_pin);
this->curr->aux[3] = digitalRead(Aux4_pin);
this->curr->aux[4] = digitalRead(Aux5_pin);
this->curr->aux[5] = digitalRead(Aux6_pin);
this->curr->menu = digitalRead(Menu_pin);
// only do channeloutpu if needed
if (curr_state != s_fly)
return;
Channel_data[THROTTLE] = map(this->curr->throttle, 0, 3500, CHANNEL_MIN_100, CHANNEL_MAX_100);
Channel_data[RUDDER] = map(this->curr->yaw, 0, 3500, CHANNEL_MIN_100, CHANNEL_MAX_100);
Channel_data[AILERON] = map(this->curr->roll, 0, 3500, CHANNEL_MIN_100, CHANNEL_MAX_100);
Channel_data[ELEVATOR] = map(this->curr->pitch, 0, 3500, CHANNEL_MIN_100, CHANNEL_MAX_100);
for (uint8_t i = 0; i<6; ++i) {
if(this->curr->aux[i])
Channel_data[CH5+i] = CHANNEL_MAX_100;
else
Channel_data[CH5+i] = CHANNEL_MIN_100;
}
}
bool Input::menu_triggered(void) {
return false;
}
bool Input::left_triggered(void) {
return false;
}
bool Input::right_triggered(void) {
return false;
}
bool Input::down_triggered(void) {
return false;
}
bool Input::up_triggered(void) {
return false;
}

44
Multiprotocol/input.h

@ -0,0 +1,44 @@
#ifndef _INPUT_H_
#define _INPUT_H_
#include <stdint.h>
#include "tx_def.h"
class Input {
private:
struct data {
uint16_t throttle;
uint16_t yaw;
uint16_t roll;
uint16_t pitch;
bool aux[6];
bool menu;
};
int curr_input;
public:
struct data input[2];
struct data* curr;
struct data* old;
Input(void);
void update(void);
struct data* get_curr_input(void);
struct data* get_old_input(void);
void update_inputs(void);
void mark_processed(void);
// menu inputs
bool menu_triggered(void);
bool left_triggered(void);
bool right_triggered(void);
bool down_triggered(void);
bool up_triggered(void);
};
extern uint16_t Channel_data[NUM_CHN];
extern Input input;
#endif

38
Multiprotocol/inputs.ino

@ -1,38 +0,0 @@
void update_inputs(void) {
INPUT_SIGNAL_on;
if (state < FRSKY_BIND_DONE)
return;
uint16_t throttle = analogRead(Throttle_pin);
uint16_t yaw = analogRead(Yaw_pin);
uint16_t roll = analogRead(Roll_pin);
uint16_t pitch = analogRead(Pitch_pin);
uint16_t aux1 = 0;//analogRead(Aux1_pin);
uint16_t aux2 = analogRead(Aux2_pin);
uint16_t ch_min=CHANNEL_MIN_100;
uint16_t ch_max=CHANNEL_MAX_100;
Channel_data[THROTTLE] += map(throttle, 0, 3500, ch_min, ch_max);
Channel_data[RUDDER] += map(yaw, 0, 3500, ch_min, ch_max);
Channel_data[AILERON] += map(roll, 0, 3500, ch_min, ch_max);
Channel_data[ELEVATOR] += map(pitch, 0, 3500, ch_min, ch_max);
//Channel_data[CH5] += map(aux1, 0, 3500, ch_min, ch_max);
Channel_data[CH6] += map(aux2, 0, 3500, ch_min, ch_max);
Channel_data[THROTTLE] /= 2;
Channel_data[RUDDER] /= 2;
Channel_data[AILERON] /= 2;
Channel_data[ELEVATOR] /= 2;
Channel_data[CH5] /= 2;
Channel_data[CH6] /= 2;
//debugln("T %d y %d r %d p %d a1 %d a2 %d",throttle,yaw,roll,pitch,aux1,aux2);
//debugln("T %d y %d r %d p %d a1 %d a2 %d",Channel_data[THROTTLE],Channel_data[RUDDER],Channel_data[AILERON],Channel_data[ELEVATOR],Channel_data[CH5],Channel_data[CH6]);
}

15
Multiprotocol/Pins.h → Multiprotocol/pins.h

@ -13,6 +13,11 @@
//*******************
//*** Pinouts ***
//*******************
#ifndef _PINS_H_
#define _PINS_H_
#include "Arduino.h"
#define LED_off
#define LED_on
#define LED_output
@ -29,10 +34,18 @@
#define Yaw_pin PA5
#define Roll_pin PA6
#define Pitch_pin PA7
#define Aux1_pin PB0
#define Aux2_pin PB0
#define Aux3_pin PB0
#define Aux4_pin PB0
#define Aux5_pin PB0
#define Aux6_pin PB0
#define Menu_pin PB0
#define cli()
#define sei()
#define NOP() __asm__ __volatile__("nop")
#define SDI_on digitalWrite(SDI_pin, HIGH)
#define SDI_off digitalWrite(SDI_pin, LOW)
@ -66,3 +79,5 @@
//*** EEPROM ***
//*******************
#define EE_ADDR uint8_t*
#endif

57
Multiprotocol/spi.cpp

@ -0,0 +1,57 @@
/*
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/>.
*/
#include <stdint.h>
#include "pins.h"
#include "spi.h"
/********************/
/** SPI routines **/
/********************/
void SPI_Write(uint8_t command)
{
uint8_t n=8;
SCLK_off;//SCK start low
SDI_off;
do
{
if(command&0x80)
SDI_on;
else
SDI_off;
SCLK_on;
//delay(1);
command = command << 1;
SCLK_off;
}
while(--n) ;
SDI_on;
}
uint8_t SPI_Read(void)
{
uint8_t result=0,i;
for(i=0;i<8;i++)
{
result=result<<1;
if(SDO_1)
result |= 0x01;
SCLK_on;
NOP();
SCLK_off;
}
return result;
}

38
Multiprotocol/SPI.ino → Multiprotocol/spi.h

@ -15,39 +15,11 @@
/********************/
/** SPI routines **/
/********************/
void SPI_Write(uint8_t command)
{
uint8_t n=8;
#ifndef _SPI_H_
#define _SPI_H_
SCLK_off;//SCK start low
SDI_off;
do
{
if(command&0x80)
SDI_on;
else
SDI_off;
SCLK_on;
//delay(1);
command = command << 1;
SCLK_off;
}
while(--n) ;
SDI_on;
}
void SPI_Write(uint8_t command);
uint8_t SPI_Read(void);
uint8_t SPI_Read(void)
{
uint8_t result=0,i;
for(i=0;i<8;i++)
{
result=result<<1;
if(SDO_1)
result |= 0x01;
SCLK_on;
NOP();
SCLK_off;
}
return result;
}
#endif

90
Multiprotocol/state.cpp

@ -1,7 +1,9 @@
#include <LiquidCrystal_I2C.h>
#include "state.h"
#include <stdio.h>
#include "Arduino.h"
#include "state.h"
#include "debug.h"
#include "tx_def.h"
LiquidCrystal_I2C lcd(0x27,16,2);
@ -10,6 +12,8 @@ State *new_state = NULL;
State *s_init = new LCD_state_init();
State *s_bind = new LCD_state_bind();
State *s_fly = new LCD_state_fly();
State *s_menu = new LCD_state_menu();
enum lcd_special_chars {
@ -54,7 +58,6 @@ void install_special_caracters(void)
}
void init_state(void) {
Wire.setSDA(PB9);
Wire.setSCL(PB8);
Wire.begin();
@ -86,54 +89,103 @@ void update_state(void) {
//LCD_state_init
LCD_state_init::LCD_state_init(void) {
snprintf(this->line1,sizeof(this->line2)," wellcome ");
snprintf(this->line2,sizeof(this->line2)," phschoen ");
snprintf(this->line[0],sizeof(this->line[0])," wellcome ");
snprintf(this->line[1],sizeof(this->line[1])," phschoen ");
}
void LCD_state_init::enter(void) {
lcd.setCursor(0,0);
lcd.print(this->line1);
lcd.print(this->line[0]);
lcd.setCursor(0,1);
lcd.print(this->line2);
time_enter = millis();
lcd.print(this->line[1]);
this->time_enter = millis();
}
void LCD_state_init::update(void)
{
uint32_t diff;
diff = millis()-time_enter;
diff = millis() - this->time_enter;
if (diff > 5 * 1000) {
new_state = s_bind;
}
}
void LCD_state_init::leave(void)
{
lcd.clear();
}
//LCD_state_bind
LCD_state_bind::LCD_state_bind(void) {
snprintf(this->line1,sizeof(this->line2),"bind mode ");
snprintf(this->line2,sizeof(this->line2)," ");
snprintf(this->line[0],sizeof(this->line[0]),"bind mode ");
snprintf(this->line[1],sizeof(this->line[1])," ");
this->bind_time = 20;
}
void LCD_state_bind::enter(void) {
lcd.setCursor(0,0);
lcd.print(this->line1);
lcd.print(this->line[0]);
lcd.setCursor(0,1);
lcd.print(this->line2);
lcd.print(this->line[1]);
this->time_enter = millis();
}
void LCD_state_bind::update(void)
{
debugln("blubber\n");
unsigned long remain = millis() - this->time_enter;
remain = remain/1000; // to sec
remain = this->bind_time - remain;
snprintf(this->line2,sizeof(this->line2),"remaining sec %02d",remain);
unsigned long time_in_ms = millis() - this->time_enter;
unsigned long time_in_s = time_in_ms/1000; // to sec
unsigned long remain_s = this->bind_time - time_in_s;
snprintf(this->line[0],sizeof(this->line[1]),"remaining sec %02d",remain_s);
lcd.setCursor(0,1);
lcd.print(this->line2);
time_enter = millis();
lcd.print(this->line[0]);
if (time_in_s >= this->bind_time)
new_state = s_menu;
}
void LCD_state_bind::leave(void)
{
lcd.clear();
}
// LCD_state_menu
LCD_state_menu::LCD_state_menu(void) {
snprintf(this->line[0],sizeof(this->line[0]),"Menubind mode ");
snprintf(this->line[1],sizeof(this->line[1])," ");
this->curr_selected = 0;
}
void LCD_state_menu::enter(void) {
lcd.setCursor(0,0);
lcd.print(this->line[0]);
lcd.setCursor(0,1);
lcd.print(this->line[1]);
this->time_enter = millis();
}
void LCD_state_menu::update(void)
{
}
void LCD_state_menu::leave(void)
{
lcd.clear();
}
// LCD_state_fly
LCD_state_fly::LCD_state_fly(void) {
snprintf(this->line[0],sizeof(this->line[0]),"fly mode ");
snprintf(this->line[1],sizeof(this->line[1])," ");
}
void LCD_state_fly::enter(void) {
lcd.setCursor(0,0);
lcd.print(this->line[0]);
lcd.setCursor(0,1);
lcd.print(this->line[1]);
this->time_enter = millis();
}
void LCD_state_fly::update(void)
{
}
void LCD_state_fly::leave(void)
{
lcd.clear();
}

27
Multiprotocol/state.h

@ -3,6 +3,7 @@
#define _STATE_H_
#include <LiquidCrystal_I2C.h>
#include <stdint.h>
void init_state(void);
@ -11,8 +12,7 @@ void update_state(void);
class State {
protected:
char line1[17];
char line2[17];
char line[2][17];
public:
virtual void enter(void) {
@ -50,13 +50,34 @@ public:
void leave(void);
};
class LCD_state_flight: public State {
class LCD_state_fly: public State {
private:
unsigned long time_enter;
public:
LCD_state_fly(void);
void enter(void);
void update(void);
void leave(void);
};
class LCD_state_menu: public State {
private:
unsigned long time_enter;
uint8_t curr_selected;
public:
LCD_state_menu(void);
void enter(void);
void update(void);
void leave(void);
};
extern State *curr_state;
extern State *new_state;
extern State *s_init;
extern State *s_bind;
extern State *s_fly;
extern State *s_menu;
#endif /*_STATE_H_*/

217
Multiprotocol/tx_def.h

@ -0,0 +1,217 @@
#ifndef _TX_DEV_H_
#define _TX_DEV_H_
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX_100 2012 // 100%
#define PPM_MIN_100 988 // 100%
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// Multiplex MC2020
#if defined(TX_MPX)
#define PPM_MAX_100 1950 // 100%
#define PPM_MIN_100 1250 // 100%
#endif
// Walkera PL0811-01H
#if defined(TX_WALKERA)
#define PPM_MAX_100 1800 // 100%
#define PPM_MIN_100 1000 // 100%
#endif
//Channel MIN MAX values
#define CHANNEL_MAX_100 1844 // 100%
#define CHANNEL_MIN_100 204 // 100%
#define CHANNEL_MAX_125 2047 // 125%
#define CHANNEL_MIN_125 0 // 125%
#define CHANNEL_MIN_COMMAND 784 // 1350us
#define CHANNEL_SWITCH 1104 // 1550us
#define CHANNEL_MAX_COMMAND 1424 // 1750us
//Channel definitions
#ifdef AETR
#define AILERON 0
#define ELEVATOR 1
#define THROTTLE 2
#define RUDDER 3
#endif
#ifdef AERT
#define AILERON 0
#define ELEVATOR 1
#define THROTTLE 3
#define RUDDER 2
#endif
#ifdef ARET
#define AILERON 0
#define ELEVATOR 2
#define THROTTLE 3
#define RUDDER 1
#endif
#ifdef ARTE
#define AILERON 0
#define ELEVATOR 3
#define THROTTLE 2
#define RUDDER 1
#endif
#ifdef ATRE
#define AILERON 0
#define ELEVATOR 3
#define THROTTLE 1
#define RUDDER 2
#endif
#ifdef ATER
#define AILERON 0
#define ELEVATOR 2
#define THROTTLE 1
#define RUDDER 3
#endif
#ifdef EATR
#define AILERON 1
#define ELEVATOR 0
#define THROTTLE 2
#define RUDDER 3
#endif
#ifdef EART
#define AILERON 1
#define ELEVATOR 0
#define THROTTLE 3
#define RUDDER 2
#endif
#ifdef ERAT
#define AILERON 2
#define ELEVATOR 0
#define THROTTLE 3
#define RUDDER 1
#endif
#ifdef ERTA
#define AILERON 3
#define ELEVATOR 0
#define THROTTLE 2
#define RUDDER 1
#endif
#ifdef ETRA
#define AILERON 3
#define ELEVATOR 0
#define THROTTLE 1
#define RUDDER 2
#endif
#ifdef ETAR
#define AILERON 2
#define ELEVATOR 0
#define THROTTLE 1
#define RUDDER 3
#endif
#ifdef TEAR
#define AILERON 2
#define ELEVATOR 1
#define THROTTLE 0
#define RUDDER 3
#endif
#ifdef TERA
#define AILERON 3
#define ELEVATOR 1
#define THROTTLE 0
#define RUDDER 2
#endif
#ifdef TREA
#define AILERON 3
#define ELEVATOR 2
#define THROTTLE 0
#define RUDDER 1
#endif
#ifdef TRAE
#define AILERON 2
#define ELEVATOR 3
#define THROTTLE 0
#define RUDDER 1
#endif
#ifdef TARE
#define AILERON 1
#define ELEVATOR 3
#define THROTTLE 0
#define RUDDER 2
#endif
#ifdef TAER
#define AILERON 1
#define ELEVATOR 2
#define THROTTLE 0
#define RUDDER 3
#endif
#ifdef RETA
#define AILERON 3
#define ELEVATOR 1
#define THROTTLE 2
#define RUDDER 0
#endif
#ifdef REAT
#define AILERON 2
#define ELEVATOR 1
#define THROTTLE 3
#define RUDDER 0
#endif
#ifdef RAET
#define AILERON 1
#define ELEVATOR 2
#define THROTTLE 3
#define RUDDER 0
#endif
#ifdef RATE
#define AILERON 1
#define ELEVATOR 3
#define THROTTLE 2
#define RUDDER 0
#endif
#ifdef RTAE
#define AILERON 2
#define ELEVATOR 3
#define THROTTLE 1
#define RUDDER 0
#endif
#ifdef RTEA
#define AILERON 3
#define ELEVATOR 2
#define THROTTLE 1
#define RUDDER 0
#endif
#define CH1 0
#define CH2 1
#define CH3 2
#define CH4 3
#define CH5 4
#define CH6 5
#define CH7 6
#define CH8 7
#define CH9 8
#define CH10 9
#define CH11 10
#define CH12 11
#define CH13 12
#define CH14 13
#define CH15 14
#define CH16 15
#define NUM_CHN 16
#endif /* _TX_DEV_H_ */

57
config

@ -0,0 +1,57 @@
resource MOTOR 1 A03
resource MOTOR 2 B08
resource MOTOR 3 A02
resource MOTOR 4 B09
resource PWM 1 D07
resource PWM 2 C08
resource PWM 3 K05
resource PWM 4 D04
resource PWM 5 B02
resource PWM 7 B01
resource PWM 8 A02
feature -RX_PPM
feature -OSD
feature RX_SERIAL
feature LED_STRIP
beeper -GPS_STATUS
beeper -ON_USB
beeper -CAM_CONNECTION_OPEN
beeper -CAM_CONNECTION_CLOSED
serial 2 64 115200 57600 0 115200
led 0 1,0::CW:0
led 1 0,0::CW:0
aux 0 0 0 1650 2100 0
aux 1 1 1 1600 2100 0
aux 2 2 1 925 1400 0
aux 3 27 0 1475 2100 0
set acc_calibration = 46,25,-115
set baro_hardware = NONE
set mid_rc = 1518
set min_check = 1003
set max_check = 1995
set serialrx_provider = SBUS
set blackbox_device = NONE
set align_board_yaw = 270
set bat_capacity = 750
profile 0
profile 1
profile 2
profile 2
rateprofile 0
rateprofile 1
rateprofile 2
rateprofile 3
rateprofile 4
rateprofile 5
rateprofile 0
save
Loading…
Cancel
Save