mirror of
https://github.com/opentx/opentx.git
synced 2025-07-24 00:35:18 +03:00
Another lot of refactoring
This commit is contained in:
parent
9f2c7ded51
commit
ab77595c6c
26 changed files with 357 additions and 347 deletions
|
@ -232,7 +232,7 @@ void evalFunctions(const CustomFunctionData * functions, CustomFunctionsContext
|
|||
{
|
||||
unsigned int moduleIndex = CFN_PARAM(cfn);
|
||||
if (moduleIndex < NUM_MODULES) {
|
||||
moduleFlag[moduleIndex] = 1 + CFN_FUNC(cfn) - FUNC_RANGECHECK;
|
||||
moduleSettings[moduleIndex].mode = 1 + CFN_FUNC(cfn) - FUNC_RANGECHECK;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -403,7 +403,7 @@ void evalFunctions(const CustomFunctionData * functions, CustomFunctionsContext
|
|||
{
|
||||
unsigned int moduleIndex = CFN_PARAM(cfn);
|
||||
if (moduleIndex < NUM_MODULES) {
|
||||
moduleFlag[moduleIndex] = 0;
|
||||
moduleSettings[moduleIndex].mode = 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -247,7 +247,7 @@ void onBindMenu(const char * result)
|
|||
return;
|
||||
}
|
||||
|
||||
moduleFlag[moduleIdx] = MODULE_BIND;
|
||||
moduleSettings[moduleIdx].mode = MODULE_MODE_BIND;
|
||||
}
|
||||
|
||||
|
||||
|
@ -331,9 +331,9 @@ void menuModelSetup(event_t event)
|
|||
|
||||
#if (defined(DSM2) || defined(PXX))
|
||||
if (menuEvent) {
|
||||
moduleFlag[0] = 0;
|
||||
moduleSettings[0].mode = 0;
|
||||
#if NUM_MODULES > 1
|
||||
moduleFlag[1] = 0;
|
||||
moduleSettings[1].mode = 0;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
@ -1027,10 +1027,10 @@ void menuModelSetup(event_t event)
|
|||
lcdDrawTextAlignedLeft(y, STR_RANGE);
|
||||
lcdDrawText(MODEL_SETUP_2ND_COLUMN, y, STR_MODULE_RANGE, attr);
|
||||
if (attr && s_editMode>0) {
|
||||
moduleFlag[INTERNAL_MODULE] = MODULE_RANGECHECK;
|
||||
moduleSettings[INTERNAL_MODULE].mode = MODULE_MODE_RANGECHECK;
|
||||
}
|
||||
if (attr && s_editMode==0) {
|
||||
moduleFlag[INTERNAL_MODULE] = MODULE_NORMAL_MODE;
|
||||
moduleSettings[INTERNAL_MODULE].mode = MODULE_MODE_NORMAL;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -1201,8 +1201,8 @@ void menuModelSetup(event_t event)
|
|||
POPUP_MENU_START(onBindMenu);
|
||||
continue;
|
||||
}
|
||||
if (moduleFlag[moduleIdx] == MODULE_BIND) {
|
||||
newFlag = MODULE_BIND;
|
||||
if (moduleSettings[moduleIdx].mode == MODULE_MODE_BIND) {
|
||||
newFlag = MODULE_MODE_BIND;
|
||||
}
|
||||
else {
|
||||
if (!popupMenuNoItems) {
|
||||
|
@ -1211,26 +1211,26 @@ void menuModelSetup(event_t event)
|
|||
}
|
||||
}
|
||||
else {
|
||||
newFlag = MODULE_BIND;
|
||||
newFlag = MODULE_MODE_BIND;
|
||||
}
|
||||
}
|
||||
else if (l_posHorz == 2) {
|
||||
newFlag = MODULE_RANGECHECK;
|
||||
newFlag = MODULE_MODE_RANGECHECK;
|
||||
}
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (attr && l_posHorz>0 && s_editMode>0) {
|
||||
if (l_posHorz == 1)
|
||||
newFlag = MODULE_BIND;
|
||||
newFlag = MODULE_MODE_BIND;
|
||||
else if (l_posHorz == 2)
|
||||
newFlag = MODULE_RANGECHECK;
|
||||
newFlag = MODULE_MODE_RANGECHECK;
|
||||
}
|
||||
#endif
|
||||
moduleFlag[moduleIdx] = newFlag;
|
||||
moduleSettings[moduleIdx].mode = newFlag;
|
||||
|
||||
#if defined(MULTIMODULE)
|
||||
if (newFlag == MODULE_BIND) {
|
||||
if (newFlag == MODULE_MODE_BIND) {
|
||||
multiBindStatus = MULTI_BIND_INITIATED;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -573,7 +573,7 @@ void menuMainView(event_t event)
|
|||
#endif
|
||||
|
||||
#if defined(DSM2)
|
||||
if (moduleFlag[0] == MODULE_BIND) {
|
||||
if (moduleSettings[0].mode == MODULE_MODE_BIND) {
|
||||
// Issue 98
|
||||
lcdDrawText(15*FW, 0, "BIND", 0);
|
||||
}
|
||||
|
|
|
@ -130,7 +130,7 @@ void onBindMenu(const char * result)
|
|||
return;
|
||||
}
|
||||
|
||||
moduleFlag[moduleIdx] = MODULE_BIND;
|
||||
moduleSettings[moduleIdx].bind = 1;;
|
||||
}
|
||||
|
||||
void copySelection(char * dst, const char * src, uint8_t size)
|
||||
|
@ -309,8 +309,8 @@ void menuModelSetup(event_t event)
|
|||
|
||||
#if (defined(DSM2) || defined(PXX))
|
||||
if (menuEvent) {
|
||||
moduleFlag[0] = 0;
|
||||
moduleFlag[1] = 0;
|
||||
moduleSettings[0].mode = 0;
|
||||
moduleSettings[1].mode = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -1061,7 +1061,7 @@ void menuModelSetup(event_t event)
|
|||
POPUP_MENU_START(onBindMenu);
|
||||
continue;
|
||||
}
|
||||
if (moduleFlag[moduleIdx] == MODULE_BIND) {
|
||||
if (moduleSettings[moduleIdx].mode == MODULE_BIND) {
|
||||
newFlag = MODULE_BIND;
|
||||
}
|
||||
else {
|
||||
|
@ -1079,7 +1079,7 @@ void menuModelSetup(event_t event)
|
|||
}
|
||||
}
|
||||
}
|
||||
moduleFlag[moduleIdx] = newFlag;
|
||||
moduleSettings[moduleIdx].mode = newFlag;
|
||||
#if defined(MULTIMODULE)
|
||||
if (newFlag == MODULE_BIND)
|
||||
multiBindStatus = MULTI_BIND_INITIATED;
|
||||
|
|
|
@ -138,7 +138,7 @@ void onBindMenu(const char * result)
|
|||
return;
|
||||
}
|
||||
|
||||
moduleFlag[moduleIdx] = MODULE_BIND;
|
||||
moduleSettings[moduleIdx].bind = 1;;
|
||||
}
|
||||
|
||||
void onModelSetupBitmapMenu(const char * result)
|
||||
|
@ -298,8 +298,8 @@ bool menuModelSetup(event_t event)
|
|||
}
|
||||
|
||||
if (menuEvent) {
|
||||
moduleFlag[0] = 0;
|
||||
moduleFlag[1] = 0;
|
||||
moduleSettings[0].mode = 0;
|
||||
moduleSettings[1].mode = 0;
|
||||
}
|
||||
|
||||
int sub = menuVerticalPosition;
|
||||
|
@ -945,8 +945,8 @@ bool menuModelSetup(event_t event)
|
|||
}
|
||||
}
|
||||
}
|
||||
drawButton(MODEL_SETUP_2ND_COLUMN+xOffsetBind, y, STR_MODULE_BIND, (moduleFlag[moduleIdx] == MODULE_BIND ? BUTTON_ON : BUTTON_OFF) | (l_posHorz==1 ? attr : 0));
|
||||
drawButton(MODEL_SETUP_2ND_COLUMN+MODEL_SETUP_RANGE_OFS+xOffsetBind, y, STR_MODULE_RANGE, (moduleFlag[moduleIdx] == MODULE_RANGECHECK ? BUTTON_ON : BUTTON_OFF) | (l_posHorz==2 ? attr : 0));
|
||||
drawButton(MODEL_SETUP_2ND_COLUMN+xOffsetBind, y, STR_MODULE_BIND, (moduleSettings[moduleIdx].mode == MODULE_MODE_BIND ? BUTTON_ON : BUTTON_OFF) | (l_posHorz==1 ? attr : 0));
|
||||
drawButton(MODEL_SETUP_2ND_COLUMN+MODEL_SETUP_RANGE_OFS+xOffsetBind, y, STR_MODULE_RANGE, (moduleSettings[moduleIdx].mode == MODULE_MODE_RANGECHECK ? BUTTON_ON : BUTTON_OFF) | (l_posHorz==2 ? attr : 0));
|
||||
uint8_t newFlag = 0;
|
||||
#if defined(MULTIMODULE)
|
||||
if (multiBindStatus == MULTI_BIND_FINISHED) {
|
||||
|
@ -982,8 +982,8 @@ bool menuModelSetup(event_t event)
|
|||
POPUP_MENU_START(onBindMenu);
|
||||
continue;
|
||||
}
|
||||
if (moduleFlag[moduleIdx] == MODULE_BIND) {
|
||||
newFlag = MODULE_BIND;
|
||||
if (moduleSettings[moduleIdx].mode == MODULE_MODE_BIND) {
|
||||
newFlag = MODULE_MODE_BIND;
|
||||
}
|
||||
else {
|
||||
if (!popupMenuNoItems) {
|
||||
|
@ -992,17 +992,17 @@ bool menuModelSetup(event_t event)
|
|||
}
|
||||
}
|
||||
else {
|
||||
newFlag = MODULE_BIND;
|
||||
newFlag = MODULE_MODE_BIND;
|
||||
}
|
||||
}
|
||||
else if (l_posHorz == 2) {
|
||||
newFlag = MODULE_RANGECHECK;
|
||||
newFlag = MODULE_MODE_RANGECHECK;
|
||||
}
|
||||
}
|
||||
}
|
||||
moduleFlag[moduleIdx] = newFlag;
|
||||
moduleSettings[moduleIdx].mode = newFlag;
|
||||
#if defined(MULTIMODULE)
|
||||
if (newFlag == MODULE_BIND)
|
||||
if (newFlag == MODULE_MODE_BIND)
|
||||
multiBindStatus = MULTI_BIND_INITIATED;
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -290,6 +290,8 @@ enum SwashType {
|
|||
#endif
|
||||
|
||||
enum ChannelsProtocols {
|
||||
PROTOCOL_CHANNELS_UNINITIALIZED,
|
||||
PROTOCOL_CHANNELS_NONE,
|
||||
PROTOCOL_CHANNELS_PPM,
|
||||
#if defined(PXX) || defined(DSM2)
|
||||
PROTOCOL_CHANNELS_PXX,
|
||||
|
@ -302,8 +304,7 @@ enum ChannelsProtocols {
|
|||
PROTOCOL_CHANNELS_CROSSFIRE,
|
||||
PROTOCOL_CHANNELS_MULTIMODULE,
|
||||
PROTOCOL_CHANNELS_SBUS,
|
||||
PROTOCOL_CHANNELS_PXX2,
|
||||
PROTOCOL_CHANNELS_NONE
|
||||
PROTOCOL_CHANNELS_PXX2
|
||||
};
|
||||
|
||||
enum XJTRFProtocols {
|
||||
|
|
|
@ -1488,9 +1488,9 @@ void doMixerCalculations()
|
|||
static uint8_t countRangecheck = 0;
|
||||
for (uint8_t i=0; i<NUM_MODULES; ++i) {
|
||||
#if defined(MULTIMODULE)
|
||||
if (moduleFlag[i] != MODULE_NORMAL_MODE || (i == EXTERNAL_MODULE && multiModuleStatus.isBinding())) {
|
||||
if (moduleSettings[i].mode != MODULE_MODE_NORMAL || (i == EXTERNAL_MODULE && multiModuleStatus.isBinding())) {
|
||||
#else
|
||||
if (moduleFlag[i] != MODULE_NORMAL_MODE) {
|
||||
if (moduleSettings[i].mode != MODULE_MODE_NORMAL) {
|
||||
#endif
|
||||
if (++countRangecheck >= 250) {
|
||||
countRangecheck = 0;
|
||||
|
|
|
@ -110,7 +110,7 @@ void putDsm2Flush()
|
|||
// This is the data stream to send, prepare after 19.5 mS
|
||||
// Send after 22.5 mS
|
||||
|
||||
void setupPulsesDSM2(uint8_t port)
|
||||
void setupPulsesDSM2(uint8_t module)
|
||||
{
|
||||
uint8_t dsmDat[14];
|
||||
|
||||
|
@ -124,7 +124,7 @@ void setupPulsesDSM2(uint8_t port)
|
|||
|
||||
modulePulsesData[EXTERNAL_MODULE].dsm2.ptr = modulePulsesData[EXTERNAL_MODULE].dsm2.pulses;
|
||||
|
||||
switch (s_current_protocol[port]) {
|
||||
switch (moduleSettings[module].protocol) {
|
||||
case PROTOCOL_CHANNELS_DSM2_LP45:
|
||||
dsmDat[0] = 0x00;
|
||||
break;
|
||||
|
@ -140,29 +140,29 @@ void setupPulsesDSM2(uint8_t port)
|
|||
if (dsm2BindTimer > 0) {
|
||||
dsm2BindTimer--;
|
||||
if (switchState(SW_DSM2_BIND)) {
|
||||
moduleFlag[port] = MODULE_BIND;
|
||||
moduleSettings[port].mode = MODULE_MODE_BIND;
|
||||
dsmDat[0] |= DSM2_SEND_BIND;
|
||||
}
|
||||
}
|
||||
else if (moduleFlag[port] == MODULE_RANGECHECK) {
|
||||
else if (moduleSettings[port].mode == MODULE_MODE_RANGECHECK) {
|
||||
dsmDat[0] |= DSM2_SEND_RANGECHECK;
|
||||
}
|
||||
else {
|
||||
moduleFlag[port] = 0;
|
||||
moduleSettings[port].mode = 0;
|
||||
}
|
||||
#else
|
||||
if (moduleFlag[port] == MODULE_BIND) {
|
||||
if (moduleSettings[module].mode == MODULE_MODE_BIND) {
|
||||
dsmDat[0] |= DSM2_SEND_BIND;
|
||||
}
|
||||
else if (moduleFlag[port] == MODULE_RANGECHECK) {
|
||||
else if (moduleSettings[module].mode == MODULE_MODE_RANGECHECK) {
|
||||
dsmDat[0] |= DSM2_SEND_RANGECHECK;
|
||||
}
|
||||
#endif
|
||||
|
||||
dsmDat[1] = g_model.header.modelId[port]; // DSM2 Header second byte for model match
|
||||
dsmDat[1] = g_model.header.modelId[module]; // DSM2 Header second byte for model match
|
||||
|
||||
for (int i=0; i<DSM2_CHANS; i++) {
|
||||
int channel = g_model.moduleData[port].channelsStart+i;
|
||||
int channel = g_model.moduleData[module].channelsStart+i;
|
||||
int value = channelOutputs[channel] + 2*PPM_CH_CENTER(channel) - 2*PPM_CENTER;
|
||||
uint16_t pulse = limit(0, ((value*13)>>5)+512, 1023);
|
||||
dsmDat[2+2*i] = (i<<2) | ((pulse>>8)&0x03);
|
|
@ -152,16 +152,16 @@ void sendFrameProtocolHeader(uint8_t port, bool failsafe)
|
|||
int8_t optionValue = g_model.moduleData[port].multi.optionValue;
|
||||
|
||||
uint8_t protoByte = 0;
|
||||
if (moduleFlag[port] == MODULE_BIND)
|
||||
if (moduleSettings[port].mode == MODULE_BIND)
|
||||
protoByte |= MULTI_SEND_BIND;
|
||||
else if (moduleFlag[port] == MODULE_RANGECHECK)
|
||||
else if (moduleSettings[port].mode == MODULE_RANGECHECK)
|
||||
protoByte |= MULTI_SEND_RANGECHECK;
|
||||
|
||||
// rfProtocol
|
||||
if (g_model.moduleData[port].getMultiProtocol(true) == MM_RF_PROTO_DSM2) {
|
||||
|
||||
// Autobinding should always be done in DSMX 11ms
|
||||
if (g_model.moduleData[port].multi.autoBindMode && moduleFlag[port] == MODULE_BIND)
|
||||
if (g_model.moduleData[port].multi.autoBindMode && moduleSettings[port].mode == MODULE_BIND)
|
||||
subtype = MM_RF_DSM2_SUBTYPE_AUTO;
|
||||
|
||||
// Multi module in DSM mode wants the number of channels to be used as option value
|
|
@ -23,10 +23,7 @@
|
|||
#include "pulses/pxx2.h"
|
||||
|
||||
uint8_t s_pulses_paused = 0;
|
||||
uint8_t s_current_protocol[NUM_MODULES] = { MODULES_INIT(255) };
|
||||
uint16_t failsafeCounter[NUM_MODULES] = { MODULES_INIT(100) };
|
||||
uint8_t moduleFlag[NUM_MODULES] = { 0 };
|
||||
|
||||
ModuleSettings moduleSettings[NUM_MODULES];
|
||||
ModulePulsesData modulePulsesData[NUM_MODULES] __DMA;
|
||||
TrainerPulsesData trainerPulsesData __DMA;
|
||||
|
||||
|
@ -86,7 +83,7 @@ uint8_t getRequiredProtocol(uint8_t port)
|
|||
// The module is set to OFF during one second before BIND start
|
||||
{
|
||||
static tmr10ms_t bindStartTime = 0;
|
||||
if (moduleFlag[EXTERNAL_MODULE] == MODULE_BIND) {
|
||||
if (moduleSettings[EXTERNAL_MODULE].mode == MODULE_MODE_BIND) {
|
||||
if (bindStartTime == 0) bindStartTime = get_tmr10ms();
|
||||
if ((tmr10ms_t)(get_tmr10ms() - bindStartTime) < 100) {
|
||||
required_protocol = PROTOCOL_CHANNELS_NONE;
|
||||
|
@ -117,7 +114,7 @@ uint8_t getRequiredProtocol(uint8_t port)
|
|||
|
||||
#if 0
|
||||
// will need an EEPROM conversion
|
||||
if (moduleFlag[port] == MODULE_OFF) {
|
||||
if (moduleSettings[port].mode == MODULE_OFF) {
|
||||
required_protocol = PROTOCOL_CHANNELS_NONE;
|
||||
}
|
||||
#endif
|
||||
|
@ -324,9 +321,9 @@ void setupPulses(uint8_t module)
|
|||
|
||||
heartbeat |= (HEART_TIMER_PULSES << module);
|
||||
|
||||
if (s_current_protocol[module] != required_protocol) {
|
||||
disablePulses(module, s_current_protocol[module]);
|
||||
s_current_protocol[module] = required_protocol;
|
||||
if (moduleSettings[module].protocol != required_protocol) {
|
||||
disablePulses(module, moduleSettings[module].protocol);
|
||||
moduleSettings[module].protocol = required_protocol;
|
||||
enablePulses(module, required_protocol);
|
||||
}
|
||||
else {
|
|
@ -21,20 +21,15 @@
|
|||
#ifndef _PULSES_H_
|
||||
#define _PULSES_H_
|
||||
|
||||
enum ModuleFlag
|
||||
{
|
||||
MODULE_NORMAL_MODE,
|
||||
MODULE_RANGECHECK,
|
||||
MODULE_BIND,
|
||||
// MODULE_OFF, // will need an EEPROM conversion
|
||||
};
|
||||
|
||||
extern uint8_t moduleFlag[NUM_MODULES];
|
||||
#include "definitions.h"
|
||||
#include "dataconstants.h"
|
||||
#include "pulses/pxx2.h"
|
||||
#include "pulses/pxx1.h"
|
||||
|
||||
#if NUM_MODULES > 1
|
||||
#define IS_RANGECHECK_ENABLE() (moduleFlag[0] == MODULE_RANGECHECK || moduleFlag[1] == MODULE_RANGECHECK)
|
||||
#define IS_RANGECHECK_ENABLE() (moduleSettings[0].mode == MODULE_MODE_RANGECHECK || moduleSettings[1].mode == MODULE_MODE_RANGECHECK)
|
||||
#else
|
||||
#define IS_RANGECHECK_ENABLE() (moduleFlag[0] == MODULE_RANGECHECK)
|
||||
#define IS_RANGECHECK_ENABLE() (moduleSettings[0].mode == MODULE_MODE_RANGECHECK)
|
||||
#endif
|
||||
|
||||
#if defined(DSM2) && !defined(PCBTARANIS)
|
||||
|
@ -42,8 +37,6 @@ enum ModuleFlag
|
|||
extern uint8_t dsm2BindTimer;
|
||||
#endif
|
||||
|
||||
#define IS_PPM_PROTOCOL(protocol) (protocol==PROTO_PPM)
|
||||
|
||||
#if defined(PXX)
|
||||
#define IS_PXX_PROTOCOL(protocol) (protocol==PROTO_PXX)
|
||||
#else
|
||||
|
@ -73,7 +66,211 @@ enum ModuleFlag
|
|||
|
||||
#define IS_SBUS_PROTOCOL(protocol) (protocol == PROTOCOL_CHANNELS_SBUS)
|
||||
|
||||
#if NUM_MODULES == 2
|
||||
#define MODULES_INIT(...) __VA_ARGS__, __VA_ARGS__
|
||||
#else
|
||||
#define MODULES_INIT(...) __VA_ARGS__
|
||||
#endif
|
||||
|
||||
extern uint8_t s_pulses_paused;
|
||||
|
||||
enum ModuleSettingsMode
|
||||
{
|
||||
MODULE_MODE_NORMAL,
|
||||
MODULE_MODE_RANGECHECK,
|
||||
MODULE_MODE_BIND,
|
||||
MODULE_MODE_REGISTER
|
||||
};
|
||||
|
||||
PACK(struct ModuleSettings {
|
||||
uint8_t protocol:5;
|
||||
uint8_t paused:1;
|
||||
uint8_t mode:2;
|
||||
uint16_t failsafeCounter;
|
||||
});
|
||||
|
||||
extern ModuleSettings moduleSettings[NUM_MODULES];
|
||||
|
||||
template<class T> struct PpmPulsesData {
|
||||
T pulses[20];
|
||||
T * ptr;
|
||||
};
|
||||
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
PACK(struct Dsm2SerialPulsesData {
|
||||
uint8_t pulses[64];
|
||||
uint8_t * ptr;
|
||||
uint8_t serialByte ;
|
||||
uint8_t serialBitCount;
|
||||
uint16_t _alignment;
|
||||
});
|
||||
#else
|
||||
#define MAX_PULSES_TRANSITIONS 300
|
||||
PACK(struct Dsm2TimerPulsesData {
|
||||
pulse_duration_t pulses[MAX_PULSES_TRANSITIONS];
|
||||
pulse_duration_t * ptr;
|
||||
uint16_t rest;
|
||||
uint8_t index;
|
||||
});
|
||||
#endif
|
||||
|
||||
#define PPM_PERIOD_HALF_US(module) ((g_model.moduleData[module].ppm.frameLength * 5 + 225) * 200) /*half us*/
|
||||
#define PPM_PERIOD(module) (PPM_PERIOD_HALF_US(module) / 2000) /*ms*/
|
||||
#define DSM2_BAUDRATE 125000
|
||||
#define DSM2_PERIOD 22 /*ms*/
|
||||
#define SBUS_BAUDRATE 100000
|
||||
#define SBUS_PERIOD_HALF_US ((g_model.moduleData[EXTERNAL_MODULE].sbus.refreshRate * 5 + 225) * 200) /*half us*/
|
||||
#define SBUS_PERIOD (SBUS_PERIOD_HALF_US / 2000) /*ms*/
|
||||
#define MULTIMODULE_BAUDRATE 100000
|
||||
#define MULTIMODULE_PERIOD 7 /*ms*/
|
||||
|
||||
#define CROSSFIRE_FRAME_MAXLEN 64
|
||||
PACK(struct CrossfirePulsesData {
|
||||
uint8_t pulses[CROSSFIRE_FRAME_MAXLEN];
|
||||
});
|
||||
|
||||
union ModulePulsesData {
|
||||
#if defined(INTMODULE_USART) || defined(EXTMODULE_USART)
|
||||
UartPxxPulses pxx_uart;
|
||||
#endif
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
SerialPxxPulses pxx;
|
||||
#elif !defined(INTMODULE_USART) || !defined(EXTMODULE_USART)
|
||||
PwmPxxPulses pxx;
|
||||
#endif
|
||||
|
||||
Pxx2Pulses pxx2;
|
||||
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
Dsm2SerialPulsesData dsm2;
|
||||
#else
|
||||
Dsm2TimerPulsesData dsm2;
|
||||
#endif
|
||||
|
||||
PpmPulsesData<pulse_duration_t> ppm;
|
||||
CrossfirePulsesData crossfire;
|
||||
} __ALIGNED(4);
|
||||
|
||||
/* The __ALIGNED keyword is required to align the struct inside the modulePulsesData below,
|
||||
* which is also defined to be __DMA (which includes __ALIGNED) aligned.
|
||||
* Arrays in C/C++ are always defined to be *contiguously*. The first byte of the second element is therefore always
|
||||
* sizeof(ModulePulsesData). __ALIGNED is required for sizeof(ModulePulsesData) to be a multiple of the alignment.
|
||||
*/
|
||||
|
||||
/* TODO: internal pulsedata only needs 200 bytes vs 300 bytes for external, both use 300 byte since we have a common struct */
|
||||
extern ModulePulsesData modulePulsesData[NUM_MODULES];
|
||||
|
||||
union TrainerPulsesData {
|
||||
PpmPulsesData<trainer_pulse_duration_t> ppm;
|
||||
};
|
||||
|
||||
extern TrainerPulsesData trainerPulsesData;
|
||||
extern const uint16_t CRCTable[];
|
||||
|
||||
void setupPulses(uint8_t port);
|
||||
void setupPulsesDSM2(uint8_t port);
|
||||
void setupPulsesMultimodule(uint8_t port);
|
||||
void setupPulsesSbus(uint8_t port);
|
||||
void setupPulsesPXX(uint8_t port);
|
||||
void setupPulsesPPMModule(uint8_t port);
|
||||
void setupPulsesPPMTrainer();
|
||||
void sendByteDsm2(uint8_t b);
|
||||
void putDsm2Flush();
|
||||
void putDsm2SerialBit(uint8_t bit);
|
||||
void sendByteSbus(uint8_t byte);
|
||||
|
||||
#if defined(HUBSAN)
|
||||
void Hubsan_Init();
|
||||
#endif
|
||||
|
||||
inline void startPulses()
|
||||
{
|
||||
s_pulses_paused = false;
|
||||
|
||||
#if defined(PCBTARANIS) || defined(PCBHORUS)
|
||||
setupPulses(INTERNAL_MODULE);
|
||||
setupPulses(EXTERNAL_MODULE);
|
||||
#else
|
||||
setupPulses(EXTERNAL_MODULE);
|
||||
#endif
|
||||
|
||||
#if defined(HUBSAN)
|
||||
Hubsan_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
inline bool pulsesStarted() { return moduleSettings[0].protocol != PROTOCOL_CHANNELS_UNINITIALIZED; }
|
||||
inline void pausePulses() { s_pulses_paused = true; }
|
||||
inline void resumePulses() { s_pulses_paused = false; }
|
||||
|
||||
#define SEND_FAILSAFE_NOW(idx) moduleSettings[idx].failsafeCounter = 1
|
||||
|
||||
inline void SEND_FAILSAFE_1S()
|
||||
{
|
||||
for (int i=0; i<NUM_MODULES; i++) {
|
||||
moduleSettings[i].failsafeCounter = 100;
|
||||
}
|
||||
}
|
||||
|
||||
// Assign failsafe values using the current channel outputs
|
||||
// for channels not set previously to HOLD or NOPULSE
|
||||
void setCustomFailsafe(uint8_t moduleIndex);
|
||||
|
||||
#if defined(PCBXLITE) && !defined(MODULE_R9M_FULLSIZE)
|
||||
#define LEN_R9M_REGION "\006"
|
||||
#define TR_R9M_REGION "FCC\0 ""EU\0 ""868MHz""915MHz"
|
||||
#define LEN_R9M_FCC_POWER_VALUES "\010"
|
||||
#define LEN_R9M_LBT_POWER_VALUES "\015"
|
||||
#define TR_R9M_FCC_POWER_VALUES "(100 mW)"
|
||||
#define TR_R9M_LBT_POWER_VALUES "25 mW 8ch\0 ""25 mW 16ch\0 ""100mW no tele"
|
||||
#define LEN_R9MFLEX_FREQ "\006"
|
||||
#define TR_R9MFLEX_FREQ "868Mhz""915Mhz"
|
||||
|
||||
enum R9MFCCPowerValues {
|
||||
R9M_FCC_POWER_100 = 0,
|
||||
R9M_FCC_POWER_MAX = R9M_FCC_POWER_100
|
||||
};
|
||||
|
||||
enum R9MLBTPowerValues {
|
||||
R9M_LBT_POWER_25 = 0,
|
||||
R9M_LBT_POWER_25_16,
|
||||
R9M_LBT_POWER_100,
|
||||
R9M_LBT_POWER_MAX = R9M_LBT_POWER_100
|
||||
};
|
||||
|
||||
#define BIND_TELEM_ALLOWED(idx) (!(IS_TELEMETRY_INTERNAL_MODULE() && moduleIdx == EXTERNAL_MODULE) && (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power < R9M_LBT_POWER_100))
|
||||
#define BIND_CH9TO16_ALLOWED(idx) (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power != R9M_LBT_POWER_25)
|
||||
|
||||
#else
|
||||
|
||||
#define LEN_R9M_REGION "\004"
|
||||
#define TR_R9M_REGION "FCC\0""EU\0 ""FLEX"
|
||||
#define LEN_R9MFLEX_FREQ "\006"
|
||||
#define TR_R9MFLEX_FREQ "868Mhz""915Mhz"
|
||||
#define LEN_R9M_FCC_POWER_VALUES "\006"
|
||||
#define LEN_R9M_LBT_POWER_VALUES "\013"
|
||||
#define TR_R9M_FCC_POWER_VALUES "10 mW\0" "100 mW" "500 mW" "1 W\0"
|
||||
#define TR_R9M_LBT_POWER_VALUES "25 mW 8ch\0 ""25 mW 16ch\0" "200 mW 16ch" "500 mW 16ch"
|
||||
|
||||
enum R9MFCCPowerValues {
|
||||
R9M_FCC_POWER_10 = 0,
|
||||
R9M_FCC_POWER_100,
|
||||
R9M_FCC_POWER_500,
|
||||
R9M_FCC_POWER_1000,
|
||||
R9M_FCC_POWER_MAX = R9M_FCC_POWER_1000
|
||||
};
|
||||
|
||||
enum R9MLBTPowerValues {
|
||||
R9M_LBT_POWER_25 = 0,
|
||||
R9M_LBT_POWER_25_16,
|
||||
R9M_LBT_POWER_200,
|
||||
R9M_LBT_POWER_500,
|
||||
R9M_LBT_POWER_MAX = R9M_LBT_POWER_500
|
||||
};
|
||||
|
||||
#define BIND_TELEM_ALLOWED(idx) (!(IS_TELEMETRY_INTERNAL_MODULE() && moduleIdx == EXTERNAL_MODULE) && (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power < R9M_LBT_POWER_200))
|
||||
#define BIND_CH9TO16_ALLOWED(idx) (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power != R9M_LBT_POWER_25)
|
||||
#endif
|
||||
|
||||
#include "pulses_arm.h"
|
||||
|
||||
#endif // _PULSES_H_
|
||||
|
|
|
@ -1,217 +0,0 @@
|
|||
/*
|
||||
* Copyright (C) OpenTX
|
||||
*
|
||||
* Based on code named
|
||||
* th9x - http://code.google.com/p/th9x
|
||||
* er9x - http://code.google.com/p/er9x
|
||||
* gruvin9x - http://code.google.com/p/gruvin9x
|
||||
*
|
||||
* License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
|
||||
*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License version 2 as
|
||||
* published by the Free Software Foundation.
|
||||
*
|
||||
* This program 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.
|
||||
*/
|
||||
|
||||
#ifndef _PULSES_ARM_H_
|
||||
#define _PULSES_ARM_H_
|
||||
|
||||
#include "pulses/pxx2.h"
|
||||
#include "pulses/pxx1.h"
|
||||
|
||||
#if NUM_MODULES == 2
|
||||
#define MODULES_INIT(...) __VA_ARGS__, __VA_ARGS__
|
||||
#else
|
||||
#define MODULES_INIT(...) __VA_ARGS__
|
||||
#endif
|
||||
|
||||
extern uint8_t s_current_protocol[NUM_MODULES];
|
||||
extern uint8_t s_pulses_paused;
|
||||
extern uint16_t failsafeCounter[NUM_MODULES];
|
||||
|
||||
template<class T> struct PpmPulsesData {
|
||||
T pulses[20];
|
||||
T * ptr;
|
||||
};
|
||||
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
PACK(struct Dsm2SerialPulsesData {
|
||||
uint8_t pulses[64];
|
||||
uint8_t * ptr;
|
||||
uint8_t serialByte ;
|
||||
uint8_t serialBitCount;
|
||||
uint16_t _alignment;
|
||||
});
|
||||
#else
|
||||
#define MAX_PULSES_TRANSITIONS 300
|
||||
PACK(struct Dsm2TimerPulsesData {
|
||||
pulse_duration_t pulses[MAX_PULSES_TRANSITIONS];
|
||||
pulse_duration_t * ptr;
|
||||
uint16_t rest;
|
||||
uint8_t index;
|
||||
});
|
||||
#endif
|
||||
|
||||
#define PPM_PERIOD_HALF_US(module) ((g_model.moduleData[module].ppm.frameLength * 5 + 225) * 200) /*half us*/
|
||||
#define PPM_PERIOD(module) (PPM_PERIOD_HALF_US(module) / 2000) /*ms*/
|
||||
#define DSM2_BAUDRATE 125000
|
||||
#define DSM2_PERIOD 22 /*ms*/
|
||||
#define SBUS_BAUDRATE 100000
|
||||
#define SBUS_PERIOD_HALF_US ((g_model.moduleData[EXTERNAL_MODULE].sbus.refreshRate * 5 + 225) * 200) /*half us*/
|
||||
#define SBUS_PERIOD (SBUS_PERIOD_HALF_US / 2000) /*ms*/
|
||||
#define MULTIMODULE_BAUDRATE 100000
|
||||
#define MULTIMODULE_PERIOD 7 /*ms*/
|
||||
|
||||
#define CROSSFIRE_FRAME_MAXLEN 64
|
||||
PACK(struct CrossfirePulsesData {
|
||||
uint8_t pulses[CROSSFIRE_FRAME_MAXLEN];
|
||||
});
|
||||
|
||||
union ModulePulsesData {
|
||||
#if defined(INTMODULE_USART) || defined(EXTMODULE_USART)
|
||||
UartPxxPulses pxx_uart;
|
||||
#endif
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
SerialPxxPulses pxx;
|
||||
#elif !defined(INTMODULE_USART) || !defined(EXTMODULE_USART)
|
||||
PwmPxxPulses pxx;
|
||||
#endif
|
||||
|
||||
Pxx2Pulses pxx2;
|
||||
|
||||
#if defined(PPM_PIN_SERIAL)
|
||||
Dsm2SerialPulsesData dsm2;
|
||||
#else
|
||||
Dsm2TimerPulsesData dsm2;
|
||||
#endif
|
||||
|
||||
PpmPulsesData<pulse_duration_t> ppm;
|
||||
CrossfirePulsesData crossfire;
|
||||
} __ALIGNED(4);
|
||||
|
||||
/* The __ALIGNED keyword is required to align the struct inside the modulePulsesData below,
|
||||
* which is also defined to be __DMA (which includes __ALIGNED) aligned.
|
||||
* Arrays in C/C++ are always defined to be *contiguously*. The first byte of the second element is therefore always
|
||||
* sizeof(ModulePulsesData). __ALIGNED is required for sizeof(ModulePulsesData) to be a multiple of the alignment.
|
||||
*/
|
||||
|
||||
/* TODO: internal pulsedata only needs 200 bytes vs 300 bytes for external, both use 300 byte since we have a common struct */
|
||||
extern ModulePulsesData modulePulsesData[NUM_MODULES];
|
||||
|
||||
union TrainerPulsesData {
|
||||
PpmPulsesData<trainer_pulse_duration_t> ppm;
|
||||
};
|
||||
|
||||
extern TrainerPulsesData trainerPulsesData;
|
||||
extern const uint16_t CRCTable[];
|
||||
|
||||
void setupPulses(uint8_t port);
|
||||
void setupPulsesDSM2(uint8_t port);
|
||||
void setupPulsesMultimodule(uint8_t port);
|
||||
void setupPulsesSbus(uint8_t port);
|
||||
void setupPulsesPXX(uint8_t port);
|
||||
void setupPulsesPPMModule(uint8_t port);
|
||||
void setupPulsesPPMTrainer();
|
||||
void sendByteDsm2(uint8_t b);
|
||||
void putDsm2Flush();
|
||||
void putDsm2SerialBit(uint8_t bit);
|
||||
void sendByteSbus(uint8_t byte);
|
||||
|
||||
#if defined(HUBSAN)
|
||||
void Hubsan_Init();
|
||||
#endif
|
||||
|
||||
inline void startPulses()
|
||||
{
|
||||
s_pulses_paused = false;
|
||||
|
||||
#if defined(PCBTARANIS) || defined(PCBHORUS)
|
||||
setupPulses(INTERNAL_MODULE);
|
||||
setupPulses(EXTERNAL_MODULE);
|
||||
#else
|
||||
setupPulses(EXTERNAL_MODULE);
|
||||
#endif
|
||||
|
||||
#if defined(HUBSAN)
|
||||
Hubsan_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
inline bool pulsesStarted() { return s_current_protocol[0] != 255; }
|
||||
inline void pausePulses() { s_pulses_paused = true; }
|
||||
inline void resumePulses() { s_pulses_paused = false; }
|
||||
|
||||
#define SEND_FAILSAFE_NOW(idx) failsafeCounter[idx] = 1
|
||||
|
||||
inline void SEND_FAILSAFE_1S()
|
||||
{
|
||||
for (int i=0; i<NUM_MODULES; i++) {
|
||||
failsafeCounter[i] = 100;
|
||||
}
|
||||
}
|
||||
|
||||
// Assign failsafe values using the current channel outputs
|
||||
// for channels not set previously to HOLD or NOPULSE
|
||||
void setCustomFailsafe(uint8_t moduleIndex);
|
||||
|
||||
#if defined(PCBXLITE) && !defined(MODULE_R9M_FULLSIZE)
|
||||
#define LEN_R9M_REGION "\006"
|
||||
#define TR_R9M_REGION "FCC\0 ""EU\0 ""868MHz""915MHz"
|
||||
#define LEN_R9M_FCC_POWER_VALUES "\010"
|
||||
#define LEN_R9M_LBT_POWER_VALUES "\015"
|
||||
#define TR_R9M_FCC_POWER_VALUES "(100 mW)"
|
||||
#define TR_R9M_LBT_POWER_VALUES "25 mW 8ch\0 ""25 mW 16ch\0 ""100mW no tele"
|
||||
#define LEN_R9MFLEX_FREQ "\006"
|
||||
#define TR_R9MFLEX_FREQ "868Mhz""915Mhz"
|
||||
|
||||
enum R9MFCCPowerValues {
|
||||
R9M_FCC_POWER_100 = 0,
|
||||
R9M_FCC_POWER_MAX = R9M_FCC_POWER_100
|
||||
};
|
||||
|
||||
enum R9MLBTPowerValues {
|
||||
R9M_LBT_POWER_25 = 0,
|
||||
R9M_LBT_POWER_25_16,
|
||||
R9M_LBT_POWER_100,
|
||||
R9M_LBT_POWER_MAX = R9M_LBT_POWER_100
|
||||
};
|
||||
|
||||
#define BIND_TELEM_ALLOWED(idx) (!(IS_TELEMETRY_INTERNAL_MODULE() && moduleIdx == EXTERNAL_MODULE) && (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power < R9M_LBT_POWER_100))
|
||||
#define BIND_CH9TO16_ALLOWED(idx) (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power != R9M_LBT_POWER_25)
|
||||
|
||||
#else
|
||||
|
||||
#define LEN_R9M_REGION "\004"
|
||||
#define TR_R9M_REGION "FCC\0""EU\0 ""FLEX"
|
||||
#define LEN_R9MFLEX_FREQ "\006"
|
||||
#define TR_R9MFLEX_FREQ "868Mhz""915Mhz"
|
||||
#define LEN_R9M_FCC_POWER_VALUES "\006"
|
||||
#define LEN_R9M_LBT_POWER_VALUES "\013"
|
||||
#define TR_R9M_FCC_POWER_VALUES "10 mW\0" "100 mW" "500 mW" "1 W\0"
|
||||
#define TR_R9M_LBT_POWER_VALUES "25 mW 8ch\0 ""25 mW 16ch\0" "200 mW 16ch" "500 mW 16ch"
|
||||
|
||||
enum R9MFCCPowerValues {
|
||||
R9M_FCC_POWER_10 = 0,
|
||||
R9M_FCC_POWER_100,
|
||||
R9M_FCC_POWER_500,
|
||||
R9M_FCC_POWER_1000,
|
||||
R9M_FCC_POWER_MAX = R9M_FCC_POWER_1000
|
||||
};
|
||||
|
||||
enum R9MLBTPowerValues {
|
||||
R9M_LBT_POWER_25 = 0,
|
||||
R9M_LBT_POWER_25_16,
|
||||
R9M_LBT_POWER_200,
|
||||
R9M_LBT_POWER_500,
|
||||
R9M_LBT_POWER_MAX = R9M_LBT_POWER_500
|
||||
};
|
||||
|
||||
#define BIND_TELEM_ALLOWED(idx) (!(IS_TELEMETRY_INTERNAL_MODULE() && moduleIdx == EXTERNAL_MODULE) && (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power < R9M_LBT_POWER_200))
|
||||
#define BIND_CH9TO16_ALLOWED(idx) (!isModuleR9M_LBT(idx) || g_model.moduleData[idx].pxx.power != R9M_LBT_POWER_25)
|
||||
#endif
|
||||
#endif // _PULSES_ARM_H_
|
|
@ -22,21 +22,25 @@
|
|||
#include "pulses/pxx1.h"
|
||||
|
||||
template <class PxxTransport>
|
||||
uint8_t Pxx1Pulses<PxxTransport>::addFlag1(uint8_t port)
|
||||
uint8_t Pxx1Pulses<PxxTransport>::addFlag1(uint8_t module)
|
||||
{
|
||||
uint8_t flag1 = (g_model.moduleData[port].rfProtocol << 6);
|
||||
if (moduleFlag[port] == MODULE_BIND) {
|
||||
uint8_t flag1 = (g_model.moduleData[module].rfProtocol << 6);
|
||||
if (moduleSettings[module].mode == MODULE_MODE_BIND) {
|
||||
flag1 |= (g_eeGeneral.countryCode << 1) | PXX_SEND_BIND;
|
||||
}
|
||||
else if (moduleFlag[port] == MODULE_RANGECHECK) {
|
||||
else if (moduleSettings[module].mode == MODULE_MODE_RANGECHECK) {
|
||||
flag1 |= PXX_SEND_RANGECHECK;
|
||||
}
|
||||
else if (g_model.moduleData[port].failsafeMode != FAILSAFE_NOT_SET && g_model.moduleData[port].failsafeMode != FAILSAFE_RECEIVER) {
|
||||
if (failsafeCounter[port]-- == 0) {
|
||||
failsafeCounter[port] = 1000;
|
||||
else {
|
||||
bool failsafeNeeded = g_model.moduleData[module].failsafeMode != FAILSAFE_NOT_SET && g_model.moduleData[module].failsafeMode != FAILSAFE_RECEIVER;
|
||||
if (moduleSettings[module].failsafeCounter-- == 0) {
|
||||
// failsafeCounter is also used for knowing if the frame is odd / even
|
||||
moduleSettings[module].failsafeCounter = 1000;
|
||||
if (failsafeNeeded) {
|
||||
flag1 |= PXX_SEND_FAILSAFE;
|
||||
}
|
||||
if (failsafeCounter[port] == 0 && g_model.moduleData[port].channelsCount > 0) {
|
||||
}
|
||||
if (failsafeNeeded && moduleSettings[module].failsafeCounter == 0 && g_model.moduleData[module].channelsCount > 0) {
|
||||
flag1 |= PXX_SEND_FAILSAFE;
|
||||
}
|
||||
}
|
||||
|
@ -45,22 +49,22 @@ uint8_t Pxx1Pulses<PxxTransport>::addFlag1(uint8_t port)
|
|||
}
|
||||
|
||||
template <class PxxTransport>
|
||||
void Pxx1Pulses<PxxTransport>::addExtraFlags(uint8_t port)
|
||||
void Pxx1Pulses<PxxTransport>::addExtraFlags(uint8_t module)
|
||||
{
|
||||
// Ext. flag (holds antenna selection on Horus internal module, 0x00 otherwise)
|
||||
uint8_t extra_flags = 0;
|
||||
|
||||
#if defined(PCBHORUS) || defined(PCBXLITE)
|
||||
if (port == INTERNAL_MODULE) {
|
||||
extra_flags |= (g_model.moduleData[port].pxx.external_antenna << 0);
|
||||
if (module == INTERNAL_MODULE) {
|
||||
extra_flags |= (g_model.moduleData[module].pxx.external_antenna << 0);
|
||||
}
|
||||
#endif
|
||||
|
||||
extra_flags |= (g_model.moduleData[port].pxx.receiver_telem_off << 1);
|
||||
extra_flags |= (g_model.moduleData[port].pxx.receiver_channel_9_16 << 2);
|
||||
if (isModuleR9M(port)) {
|
||||
extra_flags |= (min<uint8_t>(g_model.moduleData[port].pxx.power, isModuleR9M_FCC_VARIANT(port) ? (uint8_t)R9M_FCC_POWER_MAX : (uint8_t)R9M_LBT_POWER_MAX) << 3);
|
||||
if (isModuleR9M_EUPLUS(port))
|
||||
extra_flags |= (g_model.moduleData[module].pxx.receiver_telem_off << 1);
|
||||
extra_flags |= (g_model.moduleData[module].pxx.receiver_channel_9_16 << 2);
|
||||
if (isModuleR9M(module)) {
|
||||
extra_flags |= (min<uint8_t>(g_model.moduleData[module].pxx.power, isModuleR9M_FCC_VARIANT(module) ? (uint8_t)R9M_FCC_POWER_MAX : (uint8_t)R9M_LBT_POWER_MAX) << 3);
|
||||
if (isModuleR9M_EUPLUS(module))
|
||||
extra_flags |= (1 << 6);
|
||||
}
|
||||
|
||||
|
@ -72,7 +76,7 @@ void Pxx1Pulses<PxxTransport>::addExtraFlags(uint8_t port)
|
|||
}
|
||||
|
||||
template <class PxxTransport>
|
||||
void Pxx1Pulses<PxxTransport>::add8ChannelsFrame(uint8_t port, uint8_t sendUpperChannels)
|
||||
void Pxx1Pulses<PxxTransport>::add8ChannelsFrame(uint8_t module, uint8_t sendUpperChannels)
|
||||
{
|
||||
PxxTransport::initCrc();
|
||||
|
||||
|
@ -80,19 +84,19 @@ void Pxx1Pulses<PxxTransport>::add8ChannelsFrame(uint8_t port, uint8_t sendUpper
|
|||
addHead();
|
||||
|
||||
// RX Number
|
||||
PxxTransport::addByte(g_model.header.modelId[port]);
|
||||
PxxTransport::addByte(g_model.header.modelId[module]);
|
||||
|
||||
// Flag1
|
||||
uint8_t flag1 = addFlag1(port);
|
||||
uint8_t flag1 = addFlag1(module);
|
||||
|
||||
// Flag2
|
||||
PxxTransport::addByte(0);
|
||||
|
||||
// Channels
|
||||
PxxPulses<PxxTransport>::addChannels(port, flag1 & PXX_SEND_FAILSAFE, sendUpperChannels);
|
||||
PxxPulses<PxxTransport>::addChannels(module, flag1 & PXX_SEND_FAILSAFE, sendUpperChannels);
|
||||
|
||||
// Extra flags
|
||||
addExtraFlags(port);
|
||||
addExtraFlags(module);
|
||||
|
||||
// CRC
|
||||
addCrc();
|
||||
|
@ -105,22 +109,21 @@ void Pxx1Pulses<PxxTransport>::add8ChannelsFrame(uint8_t port, uint8_t sendUpper
|
|||
}
|
||||
|
||||
template <class PxxTransport>
|
||||
void Pxx1Pulses<PxxTransport>::setupFrame(uint8_t port)
|
||||
void Pxx1Pulses<PxxTransport>::setupFrame(uint8_t module)
|
||||
{
|
||||
PxxTransport::initFrame();
|
||||
|
||||
#if defined(PXX_FREQUENCY_HIGH)
|
||||
add8ChannelsFrame(port, 0);
|
||||
if (sentModuleChannels(port) > 8) {
|
||||
add8ChannelsFrame(port, 8);
|
||||
add8ChannelsFrame(module, 0);
|
||||
if (sentModuleChannels(module) > 8) {
|
||||
add8ChannelsFrame(module, 8);
|
||||
}
|
||||
#else
|
||||
static uint8_t pass[NUM_MODULES] = { MODULES_INIT(0) };
|
||||
uint8_t sendUpperChannels = 0;
|
||||
if (pass[port]++ & 0x01) {
|
||||
sendUpperChannels = g_model.moduleData[port].channelsCount;
|
||||
if (moduleSettings[module].failsafeCounter & 0x01) {
|
||||
sendUpperChannels = g_model.moduleData[module].channelsCount;
|
||||
}
|
||||
add8ChannelsFrame(port, sendUpperChannels);
|
||||
add8ChannelsFrame(module, sendUpperChannels);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -25,8 +25,8 @@ uint8_t Pxx2Pulses::addFlag0(uint8_t module)
|
|||
{
|
||||
uint8_t flag0 = g_model.header.modelId[module] & 0x3F;
|
||||
if (g_model.moduleData[module].failsafeMode != FAILSAFE_NOT_SET && g_model.moduleData[module].failsafeMode != FAILSAFE_RECEIVER) {
|
||||
if (failsafeCounter[module]-- == 0) {
|
||||
failsafeCounter[module] = 1000;
|
||||
if (moduleSettings[module].failsafeCounter-- == 0) {
|
||||
moduleSettings[module].failsafeCounter = 1000;
|
||||
flag0 |= PXX2_FLAG0_FAILSAFE;
|
||||
}
|
||||
}
|
||||
|
@ -40,10 +40,8 @@ void Pxx2Pulses::addFlag1(uint8_t module)
|
|||
Pxx2Transport::addByte(flag1);
|
||||
}
|
||||
|
||||
void Pxx2Pulses::setupFrame(uint8_t module)
|
||||
void Pxx2Pulses::setupChannelsFrame(uint8_t module)
|
||||
{
|
||||
initFrame();
|
||||
|
||||
addFrameType(PXX2_TYPE_C_MODULE, PXX2_TYPE_ID_CHANNELS);
|
||||
|
||||
// FLAG0
|
||||
|
@ -55,6 +53,31 @@ void Pxx2Pulses::setupFrame(uint8_t module)
|
|||
// Channels
|
||||
addChannels(module, flag0 & PXX2_FLAG0_FAILSAFE, 0);
|
||||
addChannels(module, flag0 & PXX2_FLAG0_FAILSAFE, 1);
|
||||
}
|
||||
|
||||
void Pxx2Pulses::setupRegisterFrame(uint8_t module)
|
||||
{
|
||||
addFrameType(PXX2_TYPE_C_MODULE, PXX2_TYPE_ID_REGISTER);
|
||||
Pxx2Transport::addByte(0);
|
||||
}
|
||||
|
||||
void Pxx2Pulses::setupBindFrame(uint8_t module)
|
||||
{
|
||||
addFrameType(PXX2_TYPE_C_MODULE, PXX2_TYPE_ID_BIND);
|
||||
}
|
||||
|
||||
void Pxx2Pulses::setupFrame(uint8_t module)
|
||||
{
|
||||
initFrame();
|
||||
|
||||
uint8_t mode = moduleSettings[module].mode;
|
||||
|
||||
if (mode == MODULE_MODE_REGISTER)
|
||||
setupRegisterFrame(module);
|
||||
else if (mode == MODULE_MODE_BIND)
|
||||
setupBindFrame(module);
|
||||
else
|
||||
setupChannelsFrame(module);
|
||||
|
||||
#if 0
|
||||
// TODO PXX15
|
||||
|
|
|
@ -71,7 +71,14 @@ class Pxx2Transport: public DataBuffer<uint8_t, 64>, public PxxCrcMixin {
|
|||
|
||||
class Pxx2Pulses: public PxxPulses<Pxx2Transport> {
|
||||
public:
|
||||
void setupFrame(uint8_t port);
|
||||
void setupFrame(uint8_t module);
|
||||
|
||||
protected:
|
||||
void setupRegisterFrame(uint8_t module);
|
||||
|
||||
void setupBindFrame(uint8_t module);
|
||||
|
||||
void setupChannelsFrame(uint8_t module);
|
||||
|
||||
void addHead()
|
||||
{
|
||||
|
|
|
@ -128,11 +128,11 @@ set(FIRMWARE_SRC
|
|||
|
||||
set(PULSES_SRC
|
||||
${PULSES_SRC}
|
||||
pulses_arm.cpp
|
||||
ppm_arm.cpp
|
||||
pulses.cpp
|
||||
ppm.cpp
|
||||
pxx.cpp
|
||||
pxx1.cpp
|
||||
pxx2.cpp
|
||||
dsm2_arm.cpp
|
||||
sbus_arm.cpp
|
||||
dsm2.cpp
|
||||
sbus.cpp
|
||||
)
|
||||
|
|
|
@ -87,7 +87,7 @@ extern "C" void INTMODULE_DMA_STREAM_IRQHandler(void)
|
|||
|
||||
void intmoduleSendNextFrame()
|
||||
{
|
||||
if (s_current_protocol[INTERNAL_MODULE] == PROTOCOL_CHANNELS_PXX2) {
|
||||
if (moduleSettings[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX2) {
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
DMA_DeInit(INTMODULE_DMA_STREAM);
|
||||
DMA_InitStructure.DMA_Channel = INTMODULE_DMA_CHANNEL;
|
||||
|
|
|
@ -219,7 +219,7 @@ void extmoduleSerialStart(uint32_t /*baudrate*/, uint32_t period_half_us)
|
|||
|
||||
void extmoduleSendNextFrame()
|
||||
{
|
||||
if (s_current_protocol[EXTERNAL_MODULE] == PROTOCOL_CHANNELS_PPM) {
|
||||
if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PPM) {
|
||||
#if defined(PCBX10) || PCBREV >= 13
|
||||
EXTMODULE_TIMER->CCR3 = GET_MODULE_PPM_DELAY(EXTERNAL_MODULE)*2;
|
||||
EXTMODULE_TIMER->CCER = TIM_CCER_CC3E | (GET_MODULE_PPM_POLARITY(EXTERNAL_MODULE) ? TIM_CCER_CC3P : 0);
|
||||
|
@ -238,7 +238,7 @@ void extmoduleSendNextFrame()
|
|||
EXTMODULE_DMA_STREAM->NDTR = modulePulsesData[EXTERNAL_MODULE].ppm.ptr - modulePulsesData[EXTERNAL_MODULE].ppm.pulses;
|
||||
EXTMODULE_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||
}
|
||||
else if (s_current_protocol[EXTERNAL_MODULE] == PROTOCOL_CHANNELS_PXX) {
|
||||
else if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX) {
|
||||
EXTMODULE_TIMER->CCR2 = modulePulsesData[EXTERNAL_MODULE].pxx.getLast() - 4000; // 2mS in advance
|
||||
EXTMODULE_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||
#if defined(PCBX10) || PCBREV >= 13
|
||||
|
@ -251,16 +251,16 @@ void extmoduleSendNextFrame()
|
|||
EXTMODULE_DMA_STREAM->NDTR = modulePulsesData[EXTERNAL_MODULE].pxx.getSize();
|
||||
EXTMODULE_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||
}
|
||||
else if (IS_DSM2_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]) || IS_MULTIMODULE_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]) || IS_SBUS_PROTOCOL(s_current_protocol[EXTERNAL_MODULE])) {
|
||||
else if (IS_DSM2_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_MULTIMODULE_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol)) {
|
||||
EXTMODULE_TIMER->CCR2 = *(modulePulsesData[EXTERNAL_MODULE].dsm2.ptr - 1) - 4000; // 2mS in advance
|
||||
EXTMODULE_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||
#if defined(PCBX10) || PCBREV >= 13
|
||||
EXTMODULE_DMA_STREAM->CR |= EXTMODULE_DMA_CHANNEL | DMA_SxCR_DIR_0 | DMA_SxCR_MINC | DMA_SxCR_PSIZE_0 | DMA_SxCR_MSIZE_0 | DMA_SxCR_PL_0 | DMA_SxCR_PL_1;
|
||||
if (IS_SBUS_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]))
|
||||
if (IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol))
|
||||
EXTMODULE_TIMER->CCER = TIM_CCER_CC3E | (GET_SBUS_POLARITY(EXTERNAL_MODULE) ? TIM_CCER_CC3P : 0); // reverse polarity for Sbus if needed
|
||||
#else
|
||||
EXTMODULE_DMA_STREAM->CR |= EXTMODULE_DMA_CHANNEL | DMA_SxCR_DIR_0 | DMA_SxCR_MINC | DMA_SxCR_PSIZE_1 | DMA_SxCR_MSIZE_1 | DMA_SxCR_PL_0 | DMA_SxCR_PL_1;
|
||||
if (IS_SBUS_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]))
|
||||
if (IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol))
|
||||
EXTMODULE_TIMER->CCER = TIM_CCER_CC1E | (GET_SBUS_POLARITY(EXTERNAL_MODULE) ? TIM_CCER_CC1P : 0); // reverse polarity for Sbus if needed
|
||||
#endif
|
||||
EXTMODULE_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
||||
|
|
|
@ -330,7 +330,7 @@ void StartSimu(bool tests, const char * sdPath, const char * settingsPath)
|
|||
if (simu_running)
|
||||
return;
|
||||
|
||||
s_current_protocol[0] = 255;
|
||||
moduleSettings[0].protocol = PROTOCOL_CHANNELS_UNINITIALIZED;
|
||||
menuLevel = 0;
|
||||
|
||||
simu_start_mode = (tests ? 0 : 0x02 /* OPENTX_START_NO_CHECKS */);
|
||||
|
|
|
@ -276,7 +276,7 @@ extern "C" void PWM_IRQHandler(void)
|
|||
|
||||
if (reason & PWM_ISR1_CHID3) {
|
||||
// Use the current protocol, don't switch until set_up_pulses
|
||||
switch (s_current_protocol[EXTERNAL_MODULE]) {
|
||||
switch (moduleSettings[EXTERNAL_MODULE].protocol) {
|
||||
case PROTOCOL_CHANNELS_PXX:
|
||||
// Alternate periods of 6.5mS and 2.5 mS
|
||||
period = pwmptr->PWM_CH_NUM[3].PWM_CPDR;
|
||||
|
|
|
@ -240,7 +240,7 @@ void extmodulePxx2Start()
|
|||
|
||||
void extmoduleSendNextFrame()
|
||||
{
|
||||
if (s_current_protocol[EXTERNAL_MODULE] == PROTOCOL_CHANNELS_PPM) {
|
||||
if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PPM) {
|
||||
EXTMODULE_TIMER->CCR1 = GET_MODULE_PPM_DELAY(EXTERNAL_MODULE) * 2;
|
||||
EXTMODULE_TIMER->CCER = EXTMODULE_TIMER_OUTPUT_ENABLE | (GET_MODULE_PPM_POLARITY(EXTERNAL_MODULE) ? EXTMODULE_TIMER_OUTPUT_POLARITY : 0); // // we are using complementary output so logic has to be reversed here
|
||||
EXTMODULE_TIMER->CCR2 = *(modulePulsesData[EXTERNAL_MODULE].ppm.ptr - 1) - 4000; // 2mS in advance
|
||||
|
@ -251,7 +251,7 @@ void extmoduleSendNextFrame()
|
|||
EXTMODULE_TIMER_DMA_STREAM->NDTR = modulePulsesData[EXTERNAL_MODULE].ppm.ptr - modulePulsesData[EXTERNAL_MODULE].ppm.pulses;
|
||||
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||
}
|
||||
else if (s_current_protocol[EXTERNAL_MODULE] == PROTOCOL_CHANNELS_PXX) {
|
||||
else if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX) {
|
||||
#if defined(EXTMODULE_USART)
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
DMA_DeInit(EXTMODULE_USART_DMA_STREAM);
|
||||
|
@ -284,8 +284,8 @@ void extmoduleSendNextFrame()
|
|||
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||
#endif
|
||||
}
|
||||
else if (IS_DSM2_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]) || IS_MULTIMODULE_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]) || IS_SBUS_PROTOCOL(s_current_protocol[EXTERNAL_MODULE])) {
|
||||
if (IS_SBUS_PROTOCOL(s_current_protocol[EXTERNAL_MODULE]))
|
||||
else if (IS_DSM2_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_MULTIMODULE_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol)) {
|
||||
if (IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol))
|
||||
EXTMODULE_TIMER->CCER = EXTMODULE_TIMER_OUTPUT_ENABLE | (GET_SBUS_POLARITY(EXTERNAL_MODULE) ? EXTMODULE_TIMER_OUTPUT_POLARITY : 0); // reverse polarity for Sbus if needed
|
||||
EXTMODULE_TIMER->CCR2 = *(modulePulsesData[EXTERNAL_MODULE].dsm2.ptr - 1) - 4000; // 2mS in advance
|
||||
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||
|
|
|
@ -65,7 +65,7 @@ void intmoduleTimerStart(uint32_t period, uint8_t state)
|
|||
|
||||
void intmoduleSendNextFrame()
|
||||
{
|
||||
if (s_current_protocol[INTERNAL_MODULE] == PROTOCOL_CHANNELS_PXX) {
|
||||
if (moduleSettings[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX) {
|
||||
INTMODULE_TIMER->CCR2 = modulePulsesData[INTERNAL_MODULE].pxx.getLast() - 4000; // 2mS in advance
|
||||
INTMODULE_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||
INTMODULE_DMA_STREAM->CR |= INTMODULE_DMA_CHANNEL | DMA_SxCR_DIR_0 | DMA_SxCR_MINC | DMA_SxCR_PSIZE_0 | DMA_SxCR_MSIZE_0 | DMA_SxCR_PL_0 | DMA_SxCR_PL_1;
|
||||
|
@ -75,7 +75,7 @@ void intmoduleSendNextFrame()
|
|||
INTMODULE_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||
}
|
||||
#if defined(TARANIS_INTERNAL_PPM)
|
||||
else if (s_current_protocol[INTERNAL_MODULE] == PROTOCOL_CHANNELS_PPM) {
|
||||
else if (moduleSettings[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PPM) {
|
||||
INTMODULE_TIMER->CCR3 = GET_MODULE_PPM_DELAY(INTERNAL_MODULE) * 2;
|
||||
INTMODULE_TIMER->CCER = TIM_CCER_CC3E | (GET_MODULE_PPM_POLARITY(INTERNAL_MODULE) ? 0 : TIM_CCER_CC3P);
|
||||
INTMODULE_TIMER->CCR2 = *(modulePulsesData[INTERNAL_MODULE].ppm.ptr - 1) - 4000; // 2mS in advance
|
||||
|
|
|
@ -81,7 +81,7 @@ bool isProtocolSynchronous(uint8_t protocol)
|
|||
void sendSynchronousPulses()
|
||||
{
|
||||
for (uint8_t module = 0; module < NUM_MODULES; module++) {
|
||||
uint8_t protocol = s_current_protocol[module];
|
||||
uint8_t protocol = moduleSettings[module].protocol;
|
||||
if (isProtocolSynchronous(protocol)) {
|
||||
setupPulses(module);
|
||||
}
|
||||
|
@ -180,7 +180,7 @@ void scheduleNextMixerCalculation(uint8_t module, uint16_t period_ms)
|
|||
{
|
||||
// Schedule next mixer calculation time,
|
||||
|
||||
if (isProtocolSynchronous(s_current_protocol[module])) {
|
||||
if (isProtocolSynchronous(moduleSettings[module].protocol)) {
|
||||
nextMixerTime[module] += period_ms / RTOS_MS_PER_TICK;
|
||||
if (nextMixerTime[module] < RTOS_GET_TIME()) {
|
||||
// we are late ... let's add some small delay
|
||||
|
|
|
@ -400,8 +400,7 @@ void processDSMBindPacket(const uint8_t *packet)
|
|||
setTelemetryValue(TELEM_PROTO_SPEKTRUM, (I2C_PSEUDO_TX << 8) + 4, 0, 0, debugval, UNIT_RAW, 0);
|
||||
|
||||
/* Finally stop binding as the rx just told us that it is bound */
|
||||
if (g_model.moduleData[EXTERNAL_MODULE].type == MODULE_TYPE_MULTIMODULE && g_model.moduleData[EXTERNAL_MODULE].getMultiProtocol(true) == MM_RF_PROTO_DSM2
|
||||
&& moduleFlag[EXTERNAL_MODULE] == MODULE_BIND) {
|
||||
if (g_model.moduleData[EXTERNAL_MODULE].type == MODULE_TYPE_MULTIMODULE && g_model.moduleData[EXTERNAL_MODULE].getMultiProtocol(true) == MM_RF_PROTO_DSM2 && moduleSettings[EXTERNAL_MODULE].mode == MODULE_BIND) {
|
||||
multiBindStatus=MULTI_BIND_FINISHED;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue