mirror of
https://github.com/opentx/opentx.git
synced 2025-07-26 17:55:19 +03:00
parent
013cf6e968
commit
8c3f226a6e
11 changed files with 68 additions and 63 deletions
|
@ -192,7 +192,7 @@ extern const MenuHandlerFunc menuTabModel[MENU_MODEL_PAGES_COUNT];
|
||||||
enum EnumTabRadio {
|
enum EnumTabRadio {
|
||||||
MENU_RADIO_SETUP,
|
MENU_RADIO_SETUP,
|
||||||
MENU_RADIO_SD_MANAGER,
|
MENU_RADIO_SD_MANAGER,
|
||||||
#if defined(LUA) || defined(PXX2)
|
#if defined(LUA) || defined(PXX2) || defined(MULTIMODULE)
|
||||||
MENU_RADIO_TOOLS,
|
MENU_RADIO_TOOLS,
|
||||||
#endif
|
#endif
|
||||||
MENU_RADIO_SPECIAL_FUNCTIONS,
|
MENU_RADIO_SPECIAL_FUNCTIONS,
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
|
|
||||||
bool menuStatsGraph(event_t event)
|
bool menuStatsGraph(event_t event)
|
||||||
{
|
{
|
||||||
switch(event) {
|
switch (event) {
|
||||||
case EVT_KEY_LONG(KEY_ENTER):
|
case EVT_KEY_LONG(KEY_ENTER):
|
||||||
g_eeGeneral.globalTimer = 0;
|
g_eeGeneral.globalTimer = 0;
|
||||||
storageDirty(EE_GENERAL);
|
storageDirty(EE_GENERAL);
|
||||||
|
|
|
@ -169,6 +169,7 @@ void checkEeprom()
|
||||||
{
|
{
|
||||||
#if defined(RTC_BACKUP_RAM) && !defined(SIMU)
|
#if defined(RTC_BACKUP_RAM) && !defined(SIMU)
|
||||||
if (TIME_TO_BACKUP_RAM()) {
|
if (TIME_TO_BACKUP_RAM()) {
|
||||||
|
if (!globalData.unexpectedShutdown)
|
||||||
rambackupWrite();
|
rambackupWrite();
|
||||||
rambackupDirtyMsk = 0;
|
rambackupDirtyMsk = 0;
|
||||||
}
|
}
|
||||||
|
@ -486,10 +487,10 @@ void perMain()
|
||||||
periodicTick();
|
periodicTick();
|
||||||
DEBUG_TIMER_STOP(debugTimerPerMain1);
|
DEBUG_TIMER_STOP(debugTimerPerMain1);
|
||||||
|
|
||||||
if (mainRequestFlags & (1 << REQUEST_FLIGHT_RESET)) {
|
if (mainRequestFlags & (1u << REQUEST_FLIGHT_RESET)) {
|
||||||
TRACE("Executing requested Flight Reset");
|
TRACE("Executing requested Flight Reset");
|
||||||
flightReset();
|
flightReset();
|
||||||
mainRequestFlags &= ~(1 << REQUEST_FLIGHT_RESET);
|
mainRequestFlags &= ~(1u << REQUEST_FLIGHT_RESET);
|
||||||
}
|
}
|
||||||
|
|
||||||
checkBacklight();
|
checkBacklight();
|
||||||
|
|
|
@ -488,10 +488,12 @@ extern uint8_t flightModeTransitionLast;
|
||||||
#define availableMemory() ((unsigned int)((unsigned char *)&_heap_end - heap))
|
#define availableMemory() ((unsigned int)((unsigned char *)&_heap_end - heap))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
extern uint32_t nextMixerTime[NUM_MODULES];
|
||||||
|
|
||||||
void evalFlightModeMixes(uint8_t mode, uint8_t tick10ms);
|
void evalFlightModeMixes(uint8_t mode, uint8_t tick10ms);
|
||||||
void evalMixes(uint8_t tick10ms);
|
void evalMixes(uint8_t tick10ms);
|
||||||
void doMixerCalculations();
|
void doMixerCalculations();
|
||||||
void scheduleNextMixerCalculation(uint8_t module, uint16_t period_ms);
|
void scheduleNextMixerCalculation(uint8_t module, uint32_t period_ms);
|
||||||
|
|
||||||
void checkTrims();
|
void checkTrims();
|
||||||
void perMain();
|
void perMain();
|
||||||
|
|
|
@ -345,6 +345,11 @@ inline int8_t defaultModuleChannels_M8(uint8_t idx)
|
||||||
return maxModuleChannels_M8(idx);
|
return maxModuleChannels_M8(idx);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
inline uint8_t sentModulePXXChannels(uint8_t idx)
|
||||||
|
{
|
||||||
|
return 8 + g_model.moduleData[idx].channelsCount;
|
||||||
|
}
|
||||||
|
|
||||||
inline int8_t sentModuleChannels(uint8_t idx)
|
inline int8_t sentModuleChannels(uint8_t idx)
|
||||||
{
|
{
|
||||||
if (isModuleCrossfire(idx))
|
if (isModuleCrossfire(idx))
|
||||||
|
@ -354,7 +359,7 @@ inline int8_t sentModuleChannels(uint8_t idx)
|
||||||
else if (isModuleSBUS(idx))
|
else if (isModuleSBUS(idx))
|
||||||
return 16;
|
return 16;
|
||||||
else
|
else
|
||||||
return 8 + g_model.moduleData[idx].channelsCount;
|
return sentModulePXXChannels(idx);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool isDefaultModelRegistrationID()
|
inline bool isDefaultModelRegistrationID()
|
||||||
|
|
|
@ -219,21 +219,21 @@ void enablePulsesExternalModule(uint8_t protocol)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void setupPulsesExternalModule(uint8_t protocol)
|
bool setupPulsesExternalModule(uint8_t protocol)
|
||||||
{
|
{
|
||||||
switch (protocol) {
|
switch (protocol) {
|
||||||
#if defined(PXX1)
|
#if defined(PXX1)
|
||||||
case PROTOCOL_CHANNELS_PXX1_PULSES:
|
case PROTOCOL_CHANNELS_PXX1_PULSES:
|
||||||
extmodulePulsesData.pxx.setupFrame(EXTERNAL_MODULE);
|
extmodulePulsesData.pxx.setupFrame(EXTERNAL_MODULE);
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, PXX_PULSES_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, PXX_PULSES_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PXX1) && defined(HARDWARE_EXTERNAL_MODULE_SIZE_SML)
|
#if defined(PXX1) && defined(HARDWARE_EXTERNAL_MODULE_SIZE_SML)
|
||||||
case PROTOCOL_CHANNELS_PXX1_SERIAL:
|
case PROTOCOL_CHANNELS_PXX1_SERIAL:
|
||||||
extmodulePulsesData.pxx_uart.setupFrame(EXTERNAL_MODULE);
|
extmodulePulsesData.pxx_uart.setupFrame(EXTERNAL_MODULE);
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, EXTMODULE_PXX1_SERIAL_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, EXTMODULE_PXX1_SERIAL_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PXX2)
|
#if defined(PXX2)
|
||||||
|
@ -241,14 +241,14 @@ void setupPulsesExternalModule(uint8_t protocol)
|
||||||
case PROTOCOL_CHANNELS_PXX2_LOWSPEED:
|
case PROTOCOL_CHANNELS_PXX2_LOWSPEED:
|
||||||
extmodulePulsesData.pxx2.setupFrame(EXTERNAL_MODULE);
|
extmodulePulsesData.pxx2.setupFrame(EXTERNAL_MODULE);
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, PXX2_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, PXX2_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SBUS)
|
#if defined(SBUS)
|
||||||
case PROTOCOL_CHANNELS_SBUS:
|
case PROTOCOL_CHANNELS_SBUS:
|
||||||
setupPulsesSbus();
|
setupPulsesSbus();
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, SBUS_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, SBUS_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(DSM2)
|
#if defined(DSM2)
|
||||||
|
@ -257,32 +257,33 @@ void setupPulsesExternalModule(uint8_t protocol)
|
||||||
case PROTOCOL_CHANNELS_DSM2_DSMX:
|
case PROTOCOL_CHANNELS_DSM2_DSMX:
|
||||||
setupPulsesDSM2();
|
setupPulsesDSM2();
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, DSM2_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, DSM2_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(CROSSFIRE)
|
#if defined(CROSSFIRE)
|
||||||
case PROTOCOL_CHANNELS_CROSSFIRE:
|
case PROTOCOL_CHANNELS_CROSSFIRE:
|
||||||
setupPulsesCrossfire();
|
setupPulsesCrossfire();
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, CROSSFIRE_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, CROSSFIRE_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(MULTIMODULE)
|
#if defined(MULTIMODULE)
|
||||||
case PROTOCOL_CHANNELS_MULTIMODULE:
|
case PROTOCOL_CHANNELS_MULTIMODULE:
|
||||||
setupPulsesMultiExternalModule();
|
setupPulsesMultiExternalModule();
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, MULTIMODULE_PERIOD);
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, MULTIMODULE_PERIOD);
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PPM)
|
#if defined(PPM)
|
||||||
case PROTOCOL_CHANNELS_PPM:
|
case PROTOCOL_CHANNELS_PPM:
|
||||||
setupPulsesPPMExternalModule();
|
setupPulsesPPMExternalModule();
|
||||||
scheduleNextMixerCalculation(EXTERNAL_MODULE, PPM_PERIOD(EXTERNAL_MODULE));
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, PPM_PERIOD(EXTERNAL_MODULE));
|
||||||
break;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
scheduleNextMixerCalculation(EXTERNAL_MODULE, 50/*ms*/);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -338,7 +339,9 @@ bool setupPulsesInternalModule(uint8_t protocol)
|
||||||
#if defined(PXX1) && defined(INTMODULE_USART)
|
#if defined(PXX1) && defined(INTMODULE_USART)
|
||||||
case PROTOCOL_CHANNELS_PXX1_SERIAL:
|
case PROTOCOL_CHANNELS_PXX1_SERIAL:
|
||||||
intmodulePulsesData.pxx_uart.setupFrame(INTERNAL_MODULE);
|
intmodulePulsesData.pxx_uart.setupFrame(INTERNAL_MODULE);
|
||||||
#if !defined(INTMODULE_HEARTBEAT)
|
#if defined(INTMODULE_HEARTBEAT)
|
||||||
|
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD + 1 /* backup */);
|
||||||
|
#else
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, INTMODULE_PXX1_SERIAL_PERIOD);
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
|
@ -351,11 +354,13 @@ bool setupPulsesInternalModule(uint8_t protocol)
|
||||||
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);
|
||||||
}
|
}
|
||||||
#if !defined(INTMODULE_HEARTBEAT)
|
|
||||||
else {
|
else {
|
||||||
|
#if defined(INTMODULE_HEARTBEAT)
|
||||||
|
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_PERIOD + 1 /* backup */);
|
||||||
|
#else
|
||||||
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_PERIOD);
|
scheduleNextMixerCalculation(INTERNAL_MODULE, PXX2_PERIOD);
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -375,7 +380,8 @@ bool setupPulsesInternalModule(uint8_t protocol)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return true;
|
scheduleNextMixerCalculation(INTERNAL_MODULE, 50/*ms*/);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -410,8 +416,7 @@ bool setupPulsesExternalModule()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
setupPulsesExternalModule(protocol);
|
return setupPulsesExternalModule(protocol);
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -69,17 +69,17 @@ void Pxx1Pulses<PxxTransport>::addExtraFlags(uint8_t module)
|
||||||
}
|
}
|
||||||
|
|
||||||
template <class PxxTransport>
|
template <class PxxTransport>
|
||||||
void Pxx1Pulses<PxxTransport>::addChannels(uint8_t port, uint8_t sendFailsafe, uint8_t sendUpperChannels)
|
void Pxx1Pulses<PxxTransport>::addChannels(uint8_t moduleIdx, uint8_t sendFailsafe, uint8_t sendUpperChannels)
|
||||||
{
|
{
|
||||||
uint16_t pulseValue = 0;
|
uint16_t pulseValue = 0;
|
||||||
uint16_t pulseValueLow = 0;
|
uint16_t pulseValueLow = 0;
|
||||||
|
|
||||||
for (int8_t i=0; i<8; i++) {
|
for (uint8_t i = 0; i < 8; i++) {
|
||||||
if (sendFailsafe) {
|
if (sendFailsafe) {
|
||||||
if (g_model.moduleData[port].failsafeMode == FAILSAFE_HOLD) {
|
if (g_model.moduleData[moduleIdx].failsafeMode == FAILSAFE_HOLD) {
|
||||||
pulseValue = (i < sendUpperChannels ? 4095 : 2047);
|
pulseValue = (i < sendUpperChannels ? 4095 : 2047);
|
||||||
}
|
}
|
||||||
else if (g_model.moduleData[port].failsafeMode == FAILSAFE_NOPULSES) {
|
else if (g_model.moduleData[moduleIdx].failsafeMode == FAILSAFE_NOPULSES) {
|
||||||
pulseValue = (i < sendUpperChannels ? 2048 : 0);
|
pulseValue = (i < sendUpperChannels ? 2048 : 0);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -92,7 +92,7 @@ void Pxx1Pulses<PxxTransport>::addChannels(uint8_t port, uint8_t sendFailsafe, u
|
||||||
pulseValue = 2048;
|
pulseValue = 2048;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
failsafeValue += 2*PPM_CH_CENTER(8+g_model.moduleData[port].channelsStart+i) - 2*PPM_CENTER;
|
failsafeValue += 2*PPM_CH_CENTER(8+g_model.moduleData[moduleIdx].channelsStart+i) - 2*PPM_CENTER;
|
||||||
pulseValue = limit(2049, (failsafeValue * 512 / 682) + 3072, 4094);
|
pulseValue = limit(2049, (failsafeValue * 512 / 682) + 3072, 4094);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -105,7 +105,7 @@ void Pxx1Pulses<PxxTransport>::addChannels(uint8_t port, uint8_t sendFailsafe, u
|
||||||
pulseValue = 0;
|
pulseValue = 0;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
failsafeValue += 2*PPM_CH_CENTER(g_model.moduleData[port].channelsStart+i) - 2*PPM_CENTER;
|
failsafeValue += 2*PPM_CH_CENTER(g_model.moduleData[moduleIdx].channelsStart+i) - 2*PPM_CENTER;
|
||||||
pulseValue = limit(1, (failsafeValue * 512 / 682) + 1024, 2046);
|
pulseValue = limit(1, (failsafeValue * 512 / 682) + 1024, 2046);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -113,12 +113,12 @@ void Pxx1Pulses<PxxTransport>::addChannels(uint8_t port, uint8_t sendFailsafe, u
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (i < sendUpperChannels) {
|
if (i < sendUpperChannels) {
|
||||||
int channel = 8 + g_model.moduleData[port].channelsStart + i;
|
int channel = 8 + g_model.moduleData[moduleIdx].channelsStart + i;
|
||||||
int value = channelOutputs[channel] + 2*PPM_CH_CENTER(channel) - 2*PPM_CENTER;
|
int value = channelOutputs[channel] + 2*PPM_CH_CENTER(channel) - 2*PPM_CENTER;
|
||||||
pulseValue = limit(2049, (value * 512 / 682) + 3072, 4094);
|
pulseValue = limit(2049, (value * 512 / 682) + 3072, 4094);
|
||||||
}
|
}
|
||||||
else if (i < sentModuleChannels(port)) {
|
else if (i < sentModulePXXChannels(moduleIdx)) {
|
||||||
int channel = g_model.moduleData[port].channelsStart + i;
|
int channel = g_model.moduleData[moduleIdx].channelsStart + i;
|
||||||
int value = channelOutputs[channel] + 2*PPM_CH_CENTER(channel) - 2*PPM_CENTER;
|
int value = channelOutputs[channel] + 2*PPM_CH_CENTER(channel) - 2*PPM_CENTER;
|
||||||
pulseValue = limit(1, (value * 512 / 682) + 1024, 2046);
|
pulseValue = limit(1, (value * 512 / 682) + 1024, 2046);
|
||||||
}
|
}
|
||||||
|
@ -186,7 +186,7 @@ void Pxx1Pulses<PxxTransport>::setupFrame(uint8_t module)
|
||||||
moduleState[module].counter = 1000;
|
moduleState[module].counter = 1000;
|
||||||
}
|
}
|
||||||
add8ChannelsFrame(module, 0, sendFailsafe);
|
add8ChannelsFrame(module, 0, sendFailsafe);
|
||||||
if (sentModuleChannels(module) > 8) {
|
if (sentModulePXXChannels(module) > 8) {
|
||||||
add8ChannelsFrame(module, 8, sendFailsafe);
|
add8ChannelsFrame(module, 8, sendFailsafe);
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -25,8 +25,12 @@
|
||||||
#include "crc.h"
|
#include "crc.h"
|
||||||
|
|
||||||
struct HeartbeatCapture {
|
struct HeartbeatCapture {
|
||||||
|
#if !defined(INTMODULE_USART)
|
||||||
uint32_t timestamp;
|
uint32_t timestamp;
|
||||||
|
#endif
|
||||||
|
#if defined(DEBUG_LATENCY)
|
||||||
uint32_t count;
|
uint32_t count;
|
||||||
|
#endif
|
||||||
uint8_t valid;
|
uint8_t valid;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,7 @@ uint8_t storageDirtyMsk;
|
||||||
tmr10ms_t storageDirtyTime10ms;
|
tmr10ms_t storageDirtyTime10ms;
|
||||||
|
|
||||||
#if defined(RTC_BACKUP_RAM)
|
#if defined(RTC_BACKUP_RAM)
|
||||||
uint8_t rambackupDirtyMsk;
|
uint8_t rambackupDirtyMsk = EE_GENERAL | EE_MODEL;
|
||||||
tmr10ms_t rambackupDirtyTime10ms;
|
tmr10ms_t rambackupDirtyTime10ms;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -20,9 +20,9 @@
|
||||||
|
|
||||||
#include "opentx.h"
|
#include "opentx.h"
|
||||||
|
|
||||||
|
#if defined(INTMODULE_HEARTBEAT_GPIO)
|
||||||
volatile HeartbeatCapture heartbeatCapture;
|
volatile HeartbeatCapture heartbeatCapture;
|
||||||
|
|
||||||
#if defined(INTMODULE_HEARTBEAT_GPIO)
|
|
||||||
void init_intmodule_heartbeat()
|
void init_intmodule_heartbeat()
|
||||||
{
|
{
|
||||||
GPIO_InitTypeDef GPIO_InitStructure;
|
GPIO_InitTypeDef GPIO_InitStructure;
|
||||||
|
@ -69,11 +69,13 @@ void check_intmodule_heartbeat()
|
||||||
{
|
{
|
||||||
if (EXTI_GetITStatus(INTMODULE_HEARTBEAT_EXTI_LINE) != RESET) {
|
if (EXTI_GetITStatus(INTMODULE_HEARTBEAT_EXTI_LINE) != RESET) {
|
||||||
#if defined(INTMODULE_USART)
|
#if defined(INTMODULE_USART)
|
||||||
heartbeatCapture.timestamp = RTOS_GET_MS();
|
nextMixerTime[INTERNAL_MODULE] = RTOS_GET_MS();
|
||||||
#else
|
#else
|
||||||
heartbeatCapture.timestamp = getTmr2MHz();
|
heartbeatCapture.timestamp = getTmr2MHz();
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(DEBUG_LATENCY)
|
||||||
heartbeatCapture.count++;
|
heartbeatCapture.count++;
|
||||||
|
#endif
|
||||||
EXTI_ClearITPendingBit(INTMODULE_HEARTBEAT_EXTI_LINE);
|
EXTI_ClearITPendingBit(INTMODULE_HEARTBEAT_EXTI_LINE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -73,9 +73,9 @@ bool isForcePowerOffRequested()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isModuleSynchronous(uint8_t module)
|
bool isModuleSynchronous(uint8_t moduleIdx)
|
||||||
{
|
{
|
||||||
uint8_t protocol = moduleState[module].protocol;
|
uint8_t protocol = moduleState[moduleIdx].protocol;
|
||||||
if (protocol == PROTOCOL_CHANNELS_PXX2_HIGHSPEED || protocol == PROTOCOL_CHANNELS_PXX2_LOWSPEED || protocol == PROTOCOL_CHANNELS_CROSSFIRE || protocol == PROTOCOL_CHANNELS_NONE)
|
if (protocol == PROTOCOL_CHANNELS_PXX2_HIGHSPEED || protocol == PROTOCOL_CHANNELS_PXX2_LOWSPEED || protocol == PROTOCOL_CHANNELS_CROSSFIRE || protocol == PROTOCOL_CHANNELS_NONE)
|
||||||
return true;
|
return true;
|
||||||
#if defined(INTMODULE_USART) || defined(EXTMODULE_USART)
|
#if defined(INTMODULE_USART) || defined(EXTMODULE_USART)
|
||||||
|
@ -85,16 +85,16 @@ bool isModuleSynchronous(uint8_t module)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendSynchronousPulses()
|
void sendSynchronousPulses(uint8_t runMask)
|
||||||
{
|
{
|
||||||
#if defined(HARDWARE_INTERNAL_MODULE)
|
#if defined(HARDWARE_INTERNAL_MODULE)
|
||||||
if (isModuleSynchronous(INTERNAL_MODULE)) {
|
if ((runMask & (1 << INTERNAL_MODULE)) && isModuleSynchronous(INTERNAL_MODULE)) {
|
||||||
if (setupPulsesInternalModule())
|
if (setupPulsesInternalModule())
|
||||||
intmoduleSendNextFrame();
|
intmoduleSendNextFrame();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (isModuleSynchronous(EXTERNAL_MODULE)) {
|
if ((runMask & (1 << EXTERNAL_MODULE)) && isModuleSynchronous(EXTERNAL_MODULE)) {
|
||||||
if (setupPulsesExternalModule())
|
if (setupPulsesExternalModule())
|
||||||
extmoduleSendNextFrame();
|
extmoduleSendNextFrame();
|
||||||
}
|
}
|
||||||
|
@ -104,7 +104,6 @@ uint32_t nextMixerTime[NUM_MODULES];
|
||||||
|
|
||||||
TASK_FUNCTION(mixerTask)
|
TASK_FUNCTION(mixerTask)
|
||||||
{
|
{
|
||||||
static uint32_t lastRunTime;
|
|
||||||
s_pulses_paused = true;
|
s_pulses_paused = true;
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
|
@ -134,35 +133,22 @@ TASK_FUNCTION(mixerTask)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
uint32_t now = RTOS_GET_MS();
|
uint32_t now = RTOS_GET_MS();
|
||||||
bool run = false;
|
uint8_t runMask = 0;
|
||||||
|
|
||||||
if (now - lastRunTime >= 10) {
|
if (now >= nextMixerTime[0]) {
|
||||||
// run at least every 10ms
|
runMask |= (1 << 0);
|
||||||
run = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(INTMODULE_USART) && defined(INTMODULE_HEARTBEAT)
|
|
||||||
if ((moduleState[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX2_HIGHSPEED || moduleState[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX1_SERIAL) && heartbeatCapture.valid && heartbeatCapture.timestamp > lastRunTime) {
|
|
||||||
run = true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (now == nextMixerTime[0]) {
|
|
||||||
run = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if NUM_MODULES >= 2
|
#if NUM_MODULES >= 2
|
||||||
if (now == nextMixerTime[1]) {
|
if (now >= nextMixerTime[1]) {
|
||||||
run = true;
|
runMask |= (1 << 1);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!run) {
|
if (!runMask) {
|
||||||
continue; // go back to sleep
|
continue; // go back to sleep
|
||||||
}
|
}
|
||||||
|
|
||||||
lastRunTime = now;
|
|
||||||
|
|
||||||
if (!s_pulses_paused) {
|
if (!s_pulses_paused) {
|
||||||
uint16_t t0 = getTmr2MHz();
|
uint16_t t0 = getTmr2MHz();
|
||||||
|
|
||||||
|
@ -197,12 +183,12 @@ TASK_FUNCTION(mixerTask)
|
||||||
if (t0 > maxMixerDuration)
|
if (t0 > maxMixerDuration)
|
||||||
maxMixerDuration = t0;
|
maxMixerDuration = t0;
|
||||||
|
|
||||||
sendSynchronousPulses();
|
sendSynchronousPulses(runMask);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void scheduleNextMixerCalculation(uint8_t module, uint16_t period_ms)
|
void scheduleNextMixerCalculation(uint8_t module, uint32_t period_ms)
|
||||||
{
|
{
|
||||||
// Schedule next mixer calculation time,
|
// Schedule next mixer calculation time,
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue