mirror of
https://github.com/opentx/opentx.git
synced 2025-07-26 01:35:21 +03:00
parent
1c977c5821
commit
c8160f5f9b
10 changed files with 102 additions and 26 deletions
3
.gitmodules
vendored
3
.gitmodules
vendored
|
@ -1,3 +1,6 @@
|
||||||
[submodule "radio/src/thirdparty/GCS_MAVLink/include_v1.0"]
|
[submodule "radio/src/thirdparty/GCS_MAVLink/include_v1.0"]
|
||||||
path = radio/src/thirdparty/GCS_MAVLink/include_v1.0
|
path = radio/src/thirdparty/GCS_MAVLink/include_v1.0
|
||||||
url = https://github.com/mavlink/c_library_v1.git
|
url = https://github.com/mavlink/c_library_v1.git
|
||||||
|
[submodule "radio/src/thirdparty/libACCESS"]
|
||||||
|
path = radio/src/thirdparty/libACCESS
|
||||||
|
url = https://github.com/FrSky-OS/libACCESS.git
|
||||||
|
|
|
@ -452,6 +452,10 @@ if(NOT MSVC)
|
||||||
# these are in addition to CMAKE_CXX_FLAGS
|
# these are in addition to CMAKE_CXX_FLAGS
|
||||||
set(CMAKE_EXE_LINKER_FLAGS "-lm -T${RADIO_SRC_DIRECTORY}/${LINKER_SCRIPT} -Wl,-Map=firmware.map,--cref,--no-warn-mismatch,--gc-sections")
|
set(CMAKE_EXE_LINKER_FLAGS "-lm -T${RADIO_SRC_DIRECTORY}/${LINKER_SCRIPT} -Wl,-Map=firmware.map,--cref,--no-warn-mismatch,--gc-sections")
|
||||||
|
|
||||||
|
if(ACCESS_LIB)
|
||||||
|
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--whole-archive ${RADIO_SRC_DIRECTORY}/${THIRDPARTY_DIR}/libACCESS/libAccess.a -Wl,--no-whole-archive")
|
||||||
|
endif()
|
||||||
|
|
||||||
if(SEMIHOSTING)
|
if(SEMIHOSTING)
|
||||||
add_definitions(-DSEMIHOSTING)
|
add_definitions(-DSEMIHOSTING)
|
||||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} --specs=rdimon.specs")
|
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} --specs=rdimon.specs")
|
||||||
|
|
|
@ -1397,4 +1397,8 @@ inline bool isAsteriskDisplayed()
|
||||||
return globalData.unexpectedShutdown;
|
return globalData.unexpectedShutdown;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(ACCESS_LIB)
|
||||||
|
#include "thirdparty/libACCESS/libAccess.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // _OPENTX_H_
|
#endif // _OPENTX_H_
|
||||||
|
|
|
@ -322,14 +322,14 @@ static void enablePulsesInternalModule(uint8_t protocol)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void setupPulsesInternalModule(uint8_t protocol)
|
bool setupPulsesInternalModule(uint8_t protocol)
|
||||||
{
|
{
|
||||||
switch (protocol) {
|
switch (protocol) {
|
||||||
#if defined(HARDWARE_INTERNAL_MODULE) && defined(PXX1) && !defined(INTMODULE_USART)
|
#if defined(HARDWARE_INTERNAL_MODULE) && defined(PXX1) && !defined(INTMODULE_USART)
|
||||||
case PROTOCOL_CHANNELS_PXX1_PULSES:
|
case PROTOCOL_CHANNELS_PXX1_PULSES:
|
||||||
intmodulePulsesData.pxx.setupFrame(INTERNAL_MODULE);
|
intmodulePulsesData.pxx.setupFrame(INTERNAL_MODULE);
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PXX1) && defined(INTMODULE_USART)
|
#if defined(PXX1) && defined(INTMODULE_USART)
|
||||||
|
@ -338,12 +338,13 @@ void setupPulsesInternalModule(uint8_t protocol)
|
||||||
#if !defined(INTMODULE_HEARTBEAT)
|
#if !defined(INTMODULE_HEARTBEAT)
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
||||||
#endif
|
#endif
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PXX2)
|
#if defined(PXX2)
|
||||||
case PROTOCOL_CHANNELS_PXX2_HIGHSPEED:
|
case PROTOCOL_CHANNELS_PXX2_HIGHSPEED:
|
||||||
intmodulePulsesData.pxx2.setupFrame(INTERNAL_MODULE);
|
{
|
||||||
|
bool result = intmodulePulsesData.pxx2.setupFrame(INTERNAL_MODULE);
|
||||||
if (moduleState[INTERNAL_MODULE].mode == MODULE_MODE_SPECTRUM_ANALYSER || moduleState[INTERNAL_MODULE].mode == MODULE_MODE_POWER_METER) {
|
if (moduleState[INTERNAL_MODULE].mode == MODULE_MODE_SPECTRUM_ANALYSER || moduleState[INTERNAL_MODULE].mode == MODULE_MODE_POWER_METER) {
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_TOOLS_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_TOOLS_PERIOD);
|
||||||
}
|
}
|
||||||
|
@ -352,25 +353,26 @@ void setupPulsesInternalModule(uint8_t protocol)
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_PERIOD);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
return result;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PCBTARANIS) && defined(INTERNAL_MODULE_PPM)
|
#if defined(PCBTARANIS) && defined(INTERNAL_MODULE_PPM)
|
||||||
case PROTOCOL_CHANNELS_PPM:
|
case PROTOCOL_CHANNELS_PPM:
|
||||||
setupPulsesPPMInternalModule();
|
setupPulsesPPMInternalModule();
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, PPM_PERIOD(INTERNAL_MODULE));
|
scheduleNextMixerCalculation(INTERNAL_MODULE, PPM_PERIOD(INTERNAL_MODULE));
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(INTERNAL_MODULE_MULTI)
|
#if defined(INTERNAL_MODULE_MULTI)
|
||||||
case PROTOCOL_CHANNELS_MULTIMODULE:
|
case PROTOCOL_CHANNELS_MULTIMODULE:
|
||||||
setupPulsesMultiInternalModule();
|
setupPulsesMultiInternalModule();
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, MULTIMODULE_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, MULTIMODULE_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -387,8 +389,7 @@ bool setupPulsesInternalModule()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
setupPulsesInternalModule(protocol);
|
return setupPulsesInternalModule(protocol);
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -74,6 +74,7 @@ enum ModuleSettingsMode
|
||||||
MODULE_MODE_SHARE,
|
MODULE_MODE_SHARE,
|
||||||
MODULE_MODE_RANGECHECK,
|
MODULE_MODE_RANGECHECK,
|
||||||
MODULE_MODE_RESET,
|
MODULE_MODE_RESET,
|
||||||
|
MODULE_MODE_AUTHENTICATION,
|
||||||
MODULE_MODE_OTA_UPDATE,
|
MODULE_MODE_OTA_UPDATE,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -357,10 +357,31 @@ void Pxx2Pulses::sendOtaUpdate(uint8_t module, const char * rxName, uint32_t add
|
||||||
extmoduleSendNextFrame();
|
extmoduleSendNextFrame();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Pxx2Pulses::setupFrame(uint8_t module)
|
void Pxx2Pulses::setupAuthenticationFrame(uint8_t module, uint8_t mode, const uint8_t * outputMessage)
|
||||||
|
{
|
||||||
|
initFrame();
|
||||||
|
|
||||||
|
addFrameType(PXX2_TYPE_C_MODULE, PXX2_TYPE_ID_AUTHENTICATION);
|
||||||
|
|
||||||
|
Pxx2Transport::addByte(mode);
|
||||||
|
if (outputMessage) {
|
||||||
|
for (uint8_t i = 0; i < 16; i++) {
|
||||||
|
Pxx2Transport::addByte(outputMessage[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
endFrame();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Pxx2Pulses::setupFrame(uint8_t module)
|
||||||
{
|
{
|
||||||
if (moduleState[module].mode == MODULE_MODE_OTA_UPDATE)
|
if (moduleState[module].mode == MODULE_MODE_OTA_UPDATE)
|
||||||
return;
|
return false;
|
||||||
|
|
||||||
|
if (moduleState[module].mode == MODULE_MODE_AUTHENTICATION) {
|
||||||
|
moduleState[module].mode = MODULE_MODE_NORMAL;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
initFrame();
|
initFrame();
|
||||||
|
|
||||||
|
@ -413,6 +434,8 @@ void Pxx2Pulses::setupFrame(uint8_t module)
|
||||||
}
|
}
|
||||||
|
|
||||||
endFrame();
|
endFrame();
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Pxx2OtaUpdate::waitStep(uint8_t step, uint8_t timeout)
|
bool Pxx2OtaUpdate::waitStep(uint8_t step, uint8_t timeout)
|
||||||
|
|
|
@ -25,16 +25,17 @@
|
||||||
#include "io/frsky_pxx2.h"
|
#include "io/frsky_pxx2.h"
|
||||||
#include "./pxx.h"
|
#include "./pxx.h"
|
||||||
|
|
||||||
#define PXX2_TYPE_C_MODULE 0x01
|
#define PXX2_TYPE_C_MODULE 0x01
|
||||||
#define PXX2_TYPE_ID_REGISTER 0x01
|
#define PXX2_TYPE_ID_REGISTER 0x01
|
||||||
#define PXX2_TYPE_ID_BIND 0x02
|
#define PXX2_TYPE_ID_BIND 0x02
|
||||||
#define PXX2_TYPE_ID_CHANNELS 0x03
|
#define PXX2_TYPE_ID_CHANNELS 0x03
|
||||||
#define PXX2_TYPE_ID_TX_SETTINGS 0x04
|
#define PXX2_TYPE_ID_TX_SETTINGS 0x04
|
||||||
#define PXX2_TYPE_ID_RX_SETTINGS 0x05
|
#define PXX2_TYPE_ID_RX_SETTINGS 0x05
|
||||||
#define PXX2_TYPE_ID_HW_INFO 0x06
|
#define PXX2_TYPE_ID_HW_INFO 0x06
|
||||||
#define PXX2_TYPE_ID_SHARE 0x07
|
#define PXX2_TYPE_ID_SHARE 0x07
|
||||||
#define PXX2_TYPE_ID_RESET 0x08
|
#define PXX2_TYPE_ID_RESET 0x08
|
||||||
#define PXX2_TYPE_ID_TELEMETRY 0xFE
|
#define PXX2_TYPE_ID_AUTHENTICATION 0x09
|
||||||
|
#define PXX2_TYPE_ID_TELEMETRY 0xFE
|
||||||
|
|
||||||
#define PXX2_TYPE_C_POWER_METER 0x02
|
#define PXX2_TYPE_C_POWER_METER 0x02
|
||||||
#define PXX2_TYPE_ID_POWER_METER 0x01
|
#define PXX2_TYPE_ID_POWER_METER 0x01
|
||||||
|
@ -75,7 +76,10 @@ enum PXX2ModuleModelID {
|
||||||
PXX2_MODULE_R9M_LITE_PRO,
|
PXX2_MODULE_R9M_LITE_PRO,
|
||||||
PXX2_MODULE_ISRM_N,
|
PXX2_MODULE_ISRM_N,
|
||||||
PXX2_MODULE_ISRM_S_X9,
|
PXX2_MODULE_ISRM_S_X9,
|
||||||
PXX2_MODULE_ISRM_S_X10
|
PXX2_MODULE_ISRM_S_X10E,
|
||||||
|
PXX2_MODULE_XJT_LITE,
|
||||||
|
PXX2_MODULE_ISRM_S_X10S,
|
||||||
|
PXX2_MODULE_ISRM_S_X9LITE,
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char * const PXX2ModulesNames[] = {
|
static const char * const PXX2ModulesNames[] = {
|
||||||
|
@ -89,7 +93,10 @@ static const char * const PXX2ModulesNames[] = {
|
||||||
"R9MLite-PRO",
|
"R9MLite-PRO",
|
||||||
"ISRM-N",
|
"ISRM-N",
|
||||||
"ISRM-S-X9",
|
"ISRM-S-X9",
|
||||||
"ISRM-S-X10",
|
"ISRM-S-X10E",
|
||||||
|
"XJT Lite",
|
||||||
|
"ISRM-S-X10S",
|
||||||
|
"ISRM-S-X9Lite"
|
||||||
};
|
};
|
||||||
|
|
||||||
inline const char * getPXX2ModuleName(uint8_t modelId)
|
inline const char * getPXX2ModuleName(uint8_t modelId)
|
||||||
|
@ -128,7 +135,10 @@ static const uint8_t PXX2ModuleOptions[] = {
|
||||||
0b00000110, // R9MLite-PRO
|
0b00000110, // R9MLite-PRO
|
||||||
0b00000100, // ISRM-N
|
0b00000100, // ISRM-N
|
||||||
0b00000100, // ISRM-S-X9
|
0b00000100, // ISRM-S-X9
|
||||||
0b00000101, // ISRM-S-X10
|
0b00000101, // ISRM-S-X10E
|
||||||
|
0b00000001, // XJT_LITE
|
||||||
|
0b00000101, // ISRM-S-X10S
|
||||||
|
0b00000101, // ISRM-S-X9LITE
|
||||||
};
|
};
|
||||||
|
|
||||||
inline uint8_t getPXX2ModuleOptions(uint8_t modelId)
|
inline uint8_t getPXX2ModuleOptions(uint8_t modelId)
|
||||||
|
@ -332,7 +342,8 @@ class Pxx2Pulses: public Pxx2Transport {
|
||||||
friend class Pxx2OtaUpdate;
|
friend class Pxx2OtaUpdate;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void setupFrame(uint8_t module);
|
bool setupFrame(uint8_t module);
|
||||||
|
void setupAuthenticationFrame(uint8_t module, uint8_t mode, const uint8_t * outputMessage);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void setupHardwareInfoFrame(uint8_t module);
|
void setupHardwareInfoFrame(uint8_t module);
|
||||||
|
|
|
@ -109,6 +109,10 @@ if(INTERNAL_MODULE_PXX2)
|
||||||
set(PXX2 ON)
|
set(PXX2 ON)
|
||||||
add_definitions(-DHARDWARE_INTERNAL_MODULE)
|
add_definitions(-DHARDWARE_INTERNAL_MODULE)
|
||||||
add_definitions(-DINTERNAL_MODULE_PXX2)
|
add_definitions(-DINTERNAL_MODULE_PXX2)
|
||||||
|
if (NOT PCBREV STREQUAL EXPRESS)
|
||||||
|
set(ACCESS_LIB ON)
|
||||||
|
add_definitions(-DACCESS_LIB)
|
||||||
|
endif()
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(INTERNAL_MODULE_MULTI)
|
if(INTERNAL_MODULE_MULTI)
|
||||||
|
|
|
@ -39,6 +39,8 @@ class Pxx2Telemetry
|
||||||
|
|
||||||
static void processPowerMeterFrame(uint8_t module, uint8_t * frame);
|
static void processPowerMeterFrame(uint8_t module, uint8_t * frame);
|
||||||
|
|
||||||
|
static void processAuthenticationFrame(uint8_t module, uint8_t * frame);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -219,6 +221,24 @@ void processTelemetryFrame(uint8_t module, uint8_t * frame)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(ACCESS_LIB)
|
||||||
|
void processAuthenticationFrame(uint8_t module, uint8_t * frame)
|
||||||
|
{
|
||||||
|
uint8_t cryptoType = frame[3];
|
||||||
|
uint8_t messageDigest[16] = {0};
|
||||||
|
|
||||||
|
if (INTERNAL_MODULE == module && accessCRL(cryptoType, frame+4, messageDigest)) {
|
||||||
|
moduleState[module].mode = MODULE_MODE_AUTHENTICATION;
|
||||||
|
Pxx2Pulses & pxx2 = intmodulePulsesData.pxx2;
|
||||||
|
pxx2.setupAuthenticationFrame(module, cryptoType, (const uint8_t *)messageDigest);
|
||||||
|
intmoduleSendBuffer(pxx2.getData(), pxx2.getSize());
|
||||||
|
// we remain in AUTHENTICATION mode to avoid a CHANNELS frame is sent at the end of the mixing process
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define processAuthenticationFrame(module, frame)
|
||||||
|
#endif
|
||||||
|
|
||||||
void processSpectrumAnalyserFrame(uint8_t module, uint8_t * frame)
|
void processSpectrumAnalyserFrame(uint8_t module, uint8_t * frame)
|
||||||
{
|
{
|
||||||
if (moduleState[module].mode != MODULE_MODE_SPECTRUM_ANALYSER) {
|
if (moduleState[module].mode != MODULE_MODE_SPECTRUM_ANALYSER) {
|
||||||
|
@ -311,6 +331,10 @@ void processModuleFrame(uint8_t module, uint8_t *frame)
|
||||||
processTelemetryFrame(module, frame);
|
processTelemetryFrame(module, frame);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case PXX2_TYPE_ID_AUTHENTICATION:
|
||||||
|
processAuthenticationFrame(module, frame);
|
||||||
|
break;
|
||||||
|
|
||||||
case PXX2_TYPE_ID_RESET:
|
case PXX2_TYPE_ID_RESET:
|
||||||
processResetFrame(module, frame);
|
processResetFrame(module, frame);
|
||||||
break;
|
break;
|
||||||
|
|
1
radio/src/thirdparty/libACCESS
vendored
Submodule
1
radio/src/thirdparty/libACCESS
vendored
Submodule
|
@ -0,0 +1 @@
|
||||||
|
Subproject commit 1bae467262bbe8232111a6baee7195850cef2531
|
Loading…
Add table
Add a link
Reference in a new issue