mirror of
https://github.com/opentx/opentx.git
synced 2025-07-23 08:15:17 +03:00
[Pulses] Refactoring
This commit is contained in:
parent
9deaa04a71
commit
fd012a52c7
14 changed files with 132 additions and 138 deletions
|
@ -1670,6 +1670,7 @@ void menuModelSetup(event_t event)
|
||||||
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if !defined(PCBXLITE)
|
#if !defined(PCBXLITE)
|
||||||
case ITEM_MODEL_EXTERNAL_MODULE_FREQ:
|
case ITEM_MODEL_EXTERNAL_MODULE_FREQ:
|
||||||
{
|
{
|
||||||
|
|
|
@ -73,7 +73,7 @@ void DeviceFirmwareUpdate::startup()
|
||||||
switch(module) {
|
switch(module) {
|
||||||
case INTERNAL_MODULE:
|
case INTERNAL_MODULE:
|
||||||
#if defined(INTMODULE_USART)
|
#if defined(INTMODULE_USART)
|
||||||
intmoduleSerialStart(57600);
|
intmoduleSerialStart(57600, true);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -209,11 +209,7 @@ void setupPulsesPXXInternalModule()
|
||||||
|
|
||||||
void setupPulsesPXXExternalModule()
|
void setupPulsesPXXExternalModule()
|
||||||
{
|
{
|
||||||
#if defined(EXTMODULE_USART)
|
|
||||||
extmodulePulsesData.pxx_uart.setupFrame(EXTERNAL_MODULE);
|
|
||||||
#elif !defined(INTMODULE_USART) && !defined(EXTMODULE_USART)
|
|
||||||
extmodulePulsesData.pxx.setupFrame(EXTERNAL_MODULE);
|
extmodulePulsesData.pxx.setupFrame(EXTERNAL_MODULE);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -152,12 +152,9 @@ union InternalModulePulsesData {
|
||||||
|
|
||||||
union ExternalModulePulsesData {
|
union ExternalModulePulsesData {
|
||||||
#if defined(PXX1)
|
#if defined(PXX1)
|
||||||
#if defined(INTMODULE_USART) || defined(EXTMODULE_USART)
|
|
||||||
UartPxx1Pulses pxx_uart;
|
|
||||||
#endif
|
|
||||||
#if defined(PPM_PIN_SERIAL)
|
#if defined(PPM_PIN_SERIAL)
|
||||||
SerialPxx1Pulses pxx;
|
SerialPxx1Pulses pxx;
|
||||||
#elif !defined(INTMODULE_USART) || !defined(EXTMODULE_USART)
|
#else
|
||||||
PwmPxx1Pulses pxx;
|
PwmPxx1Pulses pxx;
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -22,38 +22,38 @@
|
||||||
#include "pulses/pxx1.h"
|
#include "pulses/pxx1.h"
|
||||||
|
|
||||||
const uint16_t Pxx1CrcMixin::CRCTable[] = {
|
const uint16_t Pxx1CrcMixin::CRCTable[] = {
|
||||||
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
|
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
|
||||||
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
|
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
|
||||||
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
|
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
|
||||||
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
|
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
|
||||||
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
|
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
|
||||||
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
|
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
|
||||||
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
|
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
|
||||||
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
|
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
|
||||||
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
|
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
|
||||||
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
|
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
|
||||||
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
|
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
|
||||||
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
|
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
|
||||||
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
|
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
|
||||||
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
|
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
|
||||||
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
|
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
|
||||||
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
|
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
|
||||||
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
|
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
|
||||||
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
|
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
|
||||||
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
|
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
|
||||||
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
|
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
|
||||||
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
|
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
|
||||||
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
|
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
|
||||||
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
|
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
|
||||||
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
|
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
|
||||||
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
|
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
|
||||||
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
|
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
|
||||||
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
|
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
|
||||||
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
|
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
|
||||||
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
|
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
|
||||||
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
|
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
|
||||||
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
|
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
|
||||||
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
|
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
|
||||||
};
|
};
|
||||||
|
|
||||||
template <class PxxTransport>
|
template <class PxxTransport>
|
||||||
|
|
|
@ -30,10 +30,10 @@ void intmoduleStop()
|
||||||
|
|
||||||
void intmodulePxxStart()
|
void intmodulePxxStart()
|
||||||
{
|
{
|
||||||
// shouldn't be used anymore
|
intmoduleSerialStart(INTMODULE_USART_PXX_BAUDRATE, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
void intmoduleSerialStart(uint32_t baudrate)
|
void intmoduleSerialStart(uint32_t baudrate, uint8_t rxEnable)
|
||||||
{
|
{
|
||||||
INTERNAL_MODULE_ON();
|
INTERNAL_MODULE_ON();
|
||||||
|
|
||||||
|
@ -66,11 +66,12 @@ void intmoduleSerialStart(uint32_t baudrate)
|
||||||
USART_Init(INTMODULE_USART, &USART_InitStructure);
|
USART_Init(INTMODULE_USART, &USART_InitStructure);
|
||||||
USART_Cmd(INTMODULE_USART, ENABLE);
|
USART_Cmd(INTMODULE_USART, ENABLE);
|
||||||
|
|
||||||
intmoduleFifo.clear();
|
if (rxEnable) {
|
||||||
|
intmoduleFifo.clear();
|
||||||
USART_ITConfig(INTMODULE_USART, USART_IT_RXNE, ENABLE);
|
USART_ITConfig(INTMODULE_USART, USART_IT_RXNE, ENABLE);
|
||||||
NVIC_SetPriority(INTMODULE_USART_IRQn, 6);
|
NVIC_SetPriority(INTMODULE_USART_IRQn, 6);
|
||||||
NVIC_EnableIRQ(INTMODULE_USART_IRQn);
|
NVIC_EnableIRQ(INTMODULE_USART_IRQn);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#define USART_FLAG_ERRORS (USART_FLAG_ORE | USART_FLAG_NE | USART_FLAG_FE | USART_FLAG_PE)
|
#define USART_FLAG_ERRORS (USART_FLAG_ORE | USART_FLAG_NE | USART_FLAG_FE | USART_FLAG_PE)
|
||||||
|
@ -119,10 +120,17 @@ void intmoduleSendBuffer(const uint8_t * data, uint8_t size)
|
||||||
|
|
||||||
void intmoduleSendNextFrame()
|
void intmoduleSendNextFrame()
|
||||||
{
|
{
|
||||||
|
switch(moduleSettings[INTERNAL_MODULE].protocol) {
|
||||||
#if defined(PXX2)
|
#if defined(PXX2)
|
||||||
if (moduleSettings[INTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX2) {
|
case PROTOCOL_CHANNELS_PXX2:
|
||||||
intmoduleSendBuffer(intmodulePulsesData.pxx2.getData(), intmodulePulsesData.pxx2.getSize());
|
intmoduleSendBuffer(intmodulePulsesData.pxx2.getData(), intmodulePulsesData.pxx2.getSize());
|
||||||
}
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(PXX1)
|
||||||
|
case PROTOCOL_CHANNELS_PXX1:
|
||||||
|
intmoduleSendBuffer(intmodulePulsesData.pxx_uart.getData(), intmodulePulsesData.pxx_uart.getSize());
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -212,6 +212,7 @@ void disable_pxx(uint8_t module);
|
||||||
void init_pxx2(uint8_t module);
|
void init_pxx2(uint8_t module);
|
||||||
void disable_pxx2(uint8_t module);
|
void disable_pxx2(uint8_t module);
|
||||||
void init_serial(uint8_t module, uint32_t baudrate, uint32_t period_half_us);
|
void init_serial(uint8_t module, uint32_t baudrate, uint32_t period_half_us);
|
||||||
|
void intmoduleSerialStart(uint32_t baudrate, uint8_t rxEnable);
|
||||||
void disable_serial(uint8_t module);
|
void disable_serial(uint8_t module);
|
||||||
void intmoduleSendNextFrame();
|
void intmoduleSendNextFrame();
|
||||||
void extmoduleSendNextFrame();
|
void extmoduleSendNextFrame();
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
void intmoduleStop();
|
void intmoduleStop();
|
||||||
void intmodulePxxStart();
|
void intmodulePxxStart();
|
||||||
void intmoduleSerialStart(uint32_t baudrate);
|
void intmoduleSerialStart(uint32_t baudrate, uint8_t rxEnable);
|
||||||
|
|
||||||
void extmoduleStop();
|
void extmoduleStop();
|
||||||
void extmodulePpmStart();
|
void extmodulePpmStart();
|
||||||
|
@ -48,7 +48,7 @@ void disable_ppm(uint8_t module)
|
||||||
void init_pxx2(uint8_t module)
|
void init_pxx2(uint8_t module)
|
||||||
{
|
{
|
||||||
if (module == INTERNAL_MODULE)
|
if (module == INTERNAL_MODULE)
|
||||||
intmoduleSerialStart(INTMODULE_USART_PXX_BAUDRATE);
|
intmoduleSerialStart(INTMODULE_USART_PXX_BAUDRATE, true);
|
||||||
else
|
else
|
||||||
extmodulePxx2Start();
|
extmodulePxx2Start();
|
||||||
}
|
}
|
||||||
|
|
|
@ -122,7 +122,7 @@ elseif(PCB STREQUAL XLITE)
|
||||||
set(GVAR_SCREEN model_gvars.cpp)
|
set(GVAR_SCREEN model_gvars.cpp)
|
||||||
set(STATUS_LEDS YES)
|
set(STATUS_LEDS YES)
|
||||||
elseif(PCB STREQUAL XLITES)
|
elseif(PCB STREQUAL XLITES)
|
||||||
set(PXX_FREQUENCY "HIGH" CACHE STRING "PXX frequency (LOW / HIGH)")
|
set(PXX_FREQUENCY "HIGH")
|
||||||
set(PWR_BUTTON "PRESS" CACHE STRING "Pwr button type (PRESS/SWITCH)")
|
set(PWR_BUTTON "PRESS" CACHE STRING "Pwr button type (PRESS/SWITCH)")
|
||||||
set(CPU_TYPE STM32F2)
|
set(CPU_TYPE STM32F2)
|
||||||
set(CPU_TYPE_FULL STM32F205xE) # for size report
|
set(CPU_TYPE_FULL STM32F205xE) # for size report
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#ifndef _BOARD_H_
|
#ifndef _BOARD_H_
|
||||||
#define _BOARD_H_
|
#define _BOARD_H_
|
||||||
|
|
||||||
|
#include <inttypes.h>
|
||||||
#include "../definitions.h"
|
#include "../definitions.h"
|
||||||
#include "cpu_id.h"
|
#include "cpu_id.h"
|
||||||
|
|
||||||
|
@ -180,7 +181,7 @@ void init_serial(uint8_t module, uint32_t baudrate, uint32_t period);
|
||||||
void disable_serial(uint8_t module);
|
void disable_serial(uint8_t module);
|
||||||
void intmoduleStop();
|
void intmoduleStop();
|
||||||
void intmodulePxxStart();
|
void intmodulePxxStart();
|
||||||
void intmoduleSerialStart(uint32_t baudrate);
|
void intmoduleSerialStart(uint32_t baudrate, uint8_t rxEnable);
|
||||||
#if defined(TARANIS_INTERNAL_PPM)
|
#if defined(TARANIS_INTERNAL_PPM)
|
||||||
void intmodulePpmStart(void);
|
void intmodulePpmStart(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -195,16 +195,18 @@ extern "C" void EXTMODULE_USART_IRQHandler(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void extmodulePxxStart()
|
|
||||||
{
|
|
||||||
extmoduleInvertedSerialStart(EXTMODULE_USART_PXX_BAUDRATE);
|
|
||||||
}
|
|
||||||
|
|
||||||
void extmodulePxx2Start()
|
void extmodulePxx2Start()
|
||||||
{
|
{
|
||||||
extmoduleInvertedSerialStart(EXTMODULE_USART_PXX_BAUDRATE);
|
extmoduleInvertedSerialStart(EXTMODULE_USART_PXX_BAUDRATE);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
void extmodulePxx2Start()
|
||||||
|
{
|
||||||
|
// TODO just enable the S.PORT line (or let telemetry init do it)
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(PXX1)
|
||||||
void extmodulePxxStart()
|
void extmodulePxxStart()
|
||||||
{
|
{
|
||||||
EXTERNAL_MODULE_ON();
|
EXTERNAL_MODULE_ON();
|
||||||
|
@ -239,90 +241,72 @@ void extmodulePxxStart()
|
||||||
NVIC_EnableIRQ(EXTMODULE_TIMER_CC_IRQn);
|
NVIC_EnableIRQ(EXTMODULE_TIMER_CC_IRQn);
|
||||||
NVIC_SetPriority(EXTMODULE_TIMER_CC_IRQn, 7);
|
NVIC_SetPriority(EXTMODULE_TIMER_CC_IRQn, 7);
|
||||||
}
|
}
|
||||||
|
|
||||||
void extmodulePxx2Start()
|
|
||||||
{
|
|
||||||
// TODO just enable the S.PORT line (or let telemetry init do it)
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void extmoduleSendNextFrame()
|
void extmoduleSendNextFrame()
|
||||||
{
|
{
|
||||||
if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PPM) {
|
switch(moduleSettings[EXTERNAL_MODULE].protocol) {
|
||||||
EXTMODULE_TIMER->CCR1 = GET_MODULE_PPM_DELAY(EXTERNAL_MODULE) * 2;
|
case PROTOCOL_CHANNELS_PPM:
|
||||||
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->CCR1 = GET_MODULE_PPM_DELAY(EXTERNAL_MODULE) * 2;
|
||||||
EXTMODULE_TIMER->CCR2 = *(extmodulePulsesData.ppm.ptr - 1) - 4000; // 2mS in advance
|
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_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
EXTMODULE_TIMER->CCR2 = *(extmodulePulsesData.ppm.ptr - 1) - 4000; // 2mS in advance
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||||
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
||||||
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.ppm.pulses);
|
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
||||||
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.ppm.ptr - extmodulePulsesData.ppm.pulses;
|
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.ppm.pulses);
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.ppm.ptr - extmodulePulsesData.ppm.pulses;
|
||||||
}
|
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||||
|
break;
|
||||||
|
|
||||||
#if defined(PXX1)
|
#if defined(PXX1)
|
||||||
else if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX1) {
|
case PROTOCOL_CHANNELS_PXX1:
|
||||||
#if defined(EXTMODULE_USART)
|
EXTMODULE_TIMER->CCR2 = extmodulePulsesData.pxx.getLast() - 4000; // 2mS in advance
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||||
DMA_DeInit(EXTMODULE_USART_DMA_STREAM);
|
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
||||||
DMA_InitStructure.DMA_Channel = EXTMODULE_USART_DMA_CHANNEL;
|
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = CONVERT_PTR_UINT(&EXTMODULE_USART->DR);
|
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.pxx.getData());
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.pxx.getSize();
|
||||||
DMA_InitStructure.DMA_Memory0BaseAddr = CONVERT_PTR_UINT(extmodulePulsesData.pxx_uart.getData());
|
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||||
DMA_InitStructure.DMA_BufferSize = extmodulePulsesData.pxx_uart.getSize();
|
break;
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
|
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable;
|
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_Full;
|
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
|
||||||
DMA_Init(EXTMODULE_USART_DMA_STREAM, &DMA_InitStructure);
|
|
||||||
DMA_Cmd(EXTMODULE_USART_DMA_STREAM, ENABLE);
|
|
||||||
USART_DMACmd(EXTMODULE_USART, USART_DMAReq_Tx, ENABLE);
|
|
||||||
EXTMODULE_TIMER->DIER |= TIM_DIER_CC2IE;
|
|
||||||
#else
|
|
||||||
EXTMODULE_TIMER->CCR2 = extmodulePulsesData.pxx.getLast() - 4000; // 2mS in advance
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.pxx.getData());
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.pxx.getSize();
|
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PXX2)
|
#if defined(PXX2)
|
||||||
else if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_PXX2) {
|
case PROTOCOL_CHANNELS_PXX2:
|
||||||
#if defined(EXTMODULE_USART)
|
#if defined(EXTMODULE_USART)
|
||||||
extmoduleSendBuffer(extmodulePulsesData.pxx2.getData(), extmodulePulsesData.pxx2.getSize());
|
extmoduleSendBuffer(extmodulePulsesData.pxx2.getData(), extmodulePulsesData.pxx2.getSize());
|
||||||
#else
|
#else
|
||||||
sportSendBuffer(extmodulePulsesData.pxx2.getData(), extmodulePulsesData.pxx2.getSize());
|
sportSendBuffer(extmodulePulsesData.pxx2.getData(), extmodulePulsesData.pxx2.getSize());
|
||||||
#endif
|
#endif
|
||||||
}
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(DSM2)
|
#if defined(DSM2)
|
||||||
else if (IS_DSM2_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_MULTIMODULE_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol) || IS_SBUS_PROTOCOL(moduleSettings[EXTERNAL_MODULE].protocol)) {
|
case PROTOCOL_CHANNELS_SBUS:
|
||||||
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->CCER = EXTMODULE_TIMER_OUTPUT_ENABLE | (GET_SBUS_POLARITY(EXTERNAL_MODULE) ? EXTMODULE_TIMER_OUTPUT_POLARITY : 0); // reverse polarity for Sbus if needed
|
||||||
EXTMODULE_TIMER->CCR2 = *(extmodulePulsesData.dsm2.ptr - 1) - 4000; // 2mS in advance
|
// no break
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
case PROTOCOL_CHANNELS_DSM2_LP45:
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
case PROTOCOL_CHANNELS_DSM2_DSM2:
|
||||||
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
case PROTOCOL_CHANNELS_DSM2_DSMX:
|
||||||
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.dsm2.pulses);
|
case PROTOCOL_CHANNELS_MULTIMODULE:
|
||||||
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.dsm2.ptr - extmodulePulsesData.dsm2.pulses;
|
EXTMODULE_TIMER->CCR2 = *(extmodulePulsesData.dsm2.ptr - 1) - 4000; // 2mS in advance
|
||||||
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
EXTMODULE_TIMER_DMA_STREAM->CR &= ~DMA_SxCR_EN; // Disable DMA
|
||||||
}
|
EXTMODULE_TIMER_DMA_STREAM->CR |= EXTMODULE_TIMER_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;
|
||||||
|
EXTMODULE_TIMER_DMA_STREAM->PAR = CONVERT_PTR_UINT(&EXTMODULE_TIMER->ARR);
|
||||||
|
EXTMODULE_TIMER_DMA_STREAM->M0AR = CONVERT_PTR_UINT(extmodulePulsesData.dsm2.pulses);
|
||||||
|
EXTMODULE_TIMER_DMA_STREAM->NDTR = extmodulePulsesData.dsm2.ptr - extmodulePulsesData.dsm2.pulses;
|
||||||
|
EXTMODULE_TIMER_DMA_STREAM->CR |= DMA_SxCR_EN | DMA_SxCR_TCIE; // Enable DMA
|
||||||
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(CROSSFIRE)
|
#if defined(CROSSFIRE)
|
||||||
else if (moduleSettings[EXTERNAL_MODULE].protocol == PROTOCOL_CHANNELS_CROSSFIRE) {
|
case PROTOCOL_CHANNELS_CROSSFIRE:
|
||||||
sportSendBuffer(extmodulePulsesData.crossfire.pulses, extmodulePulsesData.crossfire.length);
|
sportSendBuffer(extmodulePulsesData.crossfire.pulses, extmodulePulsesData.crossfire.length);
|
||||||
}
|
break;
|
||||||
#endif
|
#endif
|
||||||
else {
|
|
||||||
EXTMODULE_TIMER->DIER |= TIM_DIER_CC2IE;
|
default:
|
||||||
|
EXTMODULE_TIMER->DIER |= TIM_DIER_CC2IE;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -65,7 +65,7 @@ void intmoduleSendNextFrame()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void intmoduleSerialStart(uint32_t baudrate)
|
void intmoduleSerialStart(uint32_t baudrate, uint8_t rxEnable)
|
||||||
{
|
{
|
||||||
// nothing, the pulses will be sent through telemetry port
|
// nothing, the pulses will be sent through telemetry port
|
||||||
}
|
}
|
||||||
|
|
|
@ -39,7 +39,7 @@ void disable_pxx(uint8_t module)
|
||||||
void init_pxx2(uint8_t module)
|
void init_pxx2(uint8_t module)
|
||||||
{
|
{
|
||||||
if (module == INTERNAL_MODULE)
|
if (module == INTERNAL_MODULE)
|
||||||
intmoduleSerialStart(INTMODULE_USART_PXX_BAUDRATE);
|
intmoduleSerialStart(INTMODULE_USART_PXX_BAUDRATE, true);
|
||||||
else
|
else
|
||||||
extmodulePxx2Start();
|
extmodulePxx2Start();
|
||||||
}
|
}
|
||||||
|
|
|
@ -73,16 +73,22 @@ bool isForcePowerOffRequested()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isProtocolSynchronous(uint8_t protocol)
|
bool isModuleSynchronous(uint8_t module)
|
||||||
{
|
{
|
||||||
return (protocol == PROTOCOL_CHANNELS_PXX2 || protocol == PROTOCOL_CHANNELS_CROSSFIRE || protocol == PROTOCOL_CHANNELS_NONE);
|
uint8_t protocol = moduleSettings[module].protocol;
|
||||||
|
if (protocol == PROTOCOL_CHANNELS_PXX2 || protocol == PROTOCOL_CHANNELS_CROSSFIRE || protocol == PROTOCOL_CHANNELS_NONE)
|
||||||
|
return true;
|
||||||
|
#if defined(INTMODULE_USART)
|
||||||
|
if (protocol == PROTOCOL_CHANNELS_PXX1 && module == INTERNAL_MODULE)
|
||||||
|
return true;
|
||||||
|
#endif
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendSynchronousPulses()
|
void sendSynchronousPulses()
|
||||||
{
|
{
|
||||||
for (uint8_t module = 0; module < NUM_MODULES; module++) {
|
for (uint8_t module = 0; module < NUM_MODULES; module++) {
|
||||||
uint8_t protocol = moduleSettings[module].protocol;
|
if (isModuleSynchronous(module) && setupPulses(module)) {
|
||||||
if (isProtocolSynchronous(protocol) && setupPulses(module)) {
|
|
||||||
if (module == INTERNAL_MODULE)
|
if (module == INTERNAL_MODULE)
|
||||||
intmoduleSendNextFrame();
|
intmoduleSendNextFrame();
|
||||||
else
|
else
|
||||||
|
@ -184,7 +190,7 @@ void scheduleNextMixerCalculation(uint8_t module, uint16_t period_ms)
|
||||||
{
|
{
|
||||||
// Schedule next mixer calculation time,
|
// Schedule next mixer calculation time,
|
||||||
|
|
||||||
if (isProtocolSynchronous(moduleSettings[module].protocol)) {
|
if (isModuleSynchronous(module)) {
|
||||||
nextMixerTime[module] += period_ms / RTOS_MS_PER_TICK;
|
nextMixerTime[module] += period_ms / RTOS_MS_PER_TICK;
|
||||||
if (nextMixerTime[module] < RTOS_GET_TIME()) {
|
if (nextMixerTime[module] < RTOS_GET_TIME()) {
|
||||||
// we are late ... let's add some small delay
|
// we are late ... let's add some small delay
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue