1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-27 02:05:31 +03:00

fix after revision code

This commit is contained in:
error414 2017-03-31 19:04:05 +02:00
parent 9a240a1f3b
commit 5d24bd3cc5
10 changed files with 134 additions and 70 deletions

View file

@ -58,7 +58,7 @@ static void TRANSPONDER_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
}
}
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t* transponder_instance)
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
{
if (!ioTag) {
return;
@ -84,10 +84,10 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t* transponder_instanc
RCC_ClockCmd(timerRCC(timer), ENABLE);
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, transponder_instance->timer_hz);
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, transponder_instance->timer_carrier_hz);
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, transponder->timer_hz);
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, transponder->timer_carrier_hz);
transponder_instance->bitToggleOne = period / 2;
transponder->bitToggleOne = period / 2;
/* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = period;
@ -122,15 +122,15 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t* transponder_instanc
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
#if defined(STM32F3)
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&(transponder_instance->transponderIrDMABuffer);
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&(transponder->transponderIrDMABuffer);
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
#elif defined(STM32F4)
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&(transponder_instance->transponderIrDMABuffer);
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&(transponder->transponderIrDMABuffer);
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
#endif
DMA_InitStructure.DMA_BufferSize = transponder_instance->dma_buffer_size;
DMA_InitStructure.DMA_BufferSize = transponder->dma_buffer_size;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
#if defined(STM32F3)
@ -202,9 +202,9 @@ void transponderIrUpdateData(const uint8_t* transponderData)
transponder.vTable->updateTransponderDMABuffer(&transponder, transponderData);
}
void transponderIrDMAEnable(transponder_t* transponder_instance)
void transponderIrDMAEnable(transponder_t *transponder)
{
DMA_SetCurrDataCounter(dmaRef, transponder_instance->dma_buffer_size); // load number of bytes to be transferred
DMA_SetCurrDataCounter(dmaRef, transponder->dma_buffer_size); // load number of bytes to be transferred
TIM_SetCounter(timer, 0);
TIM_Cmd(timer, ENABLE);
DMA_Cmd(dmaRef, ENABLE);

View file

@ -32,14 +32,14 @@
/*** ILAP ***/
#define TRANSPONDER_BITS_PER_BYTE 10 // start + 8 data + stop
#define TRANSPONDER_DATA_LENGTH 6
#define TRANSPONDER_TOGGLES_PER_BIT 11
#define TRANSPONDER_GAP_TOGGLES 1
#define TRANSPONDER_TOGGLES (TRANSPONDER_TOGGLES_PER_BIT + TRANSPONDER_GAP_TOGGLES)
#define TRANSPONDER_DMA_BUFFER_SIZE ((TRANSPONDER_TOGGLES_PER_BIT + 1) * TRANSPONDER_BITS_PER_BYTE * TRANSPONDER_DATA_LENGTH) //720
#define TRANSPONDER_TIMER_MHZ 24
#define TRANSPONDER_CARRIER_HZ 460750
#define TRANSPONDER_BITS_PER_BYTE_ILAP 10 // start + 8 data + stop
#define TRANSPONDER_DATA_LENGTH_ILAP 6
#define TRANSPONDER_TOGGLES_PER_BIT_ILAP 11
#define TRANSPONDER_GAP_TOGGLES_ILAP 1
#define TRANSPONDER_TOGGLES (TRANSPONDER_TOGGLES_PER_BIT_ILAP + TRANSPONDER_GAP_TOGGLES_ILAP)
#define TRANSPONDER_DMA_BUFFER_SIZE_ILAP ((TRANSPONDER_TOGGLES_PER_BIT_ILAP + 1) * TRANSPONDER_BITS_PER_BYTE_ILAP * TRANSPONDER_DATA_LENGTH_ILAP) //720
#define TRANSPONDER_TIMER_MHZ_ILAP 24
#define TRANSPONDER_CARRIER_HZ_ILAP 460750
/*** ******** ***/
/*
@ -54,14 +54,14 @@
typedef union transponderIrDMABuffer_s {
uint8_t arcitimer[TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER]; // 620
uint8_t ilap[TRANSPONDER_DMA_BUFFER_SIZE]; // 720
uint8_t ilap[TRANSPONDER_DMA_BUFFER_SIZE_ILAP]; // 720
} transponderIrDMABuffer_t;
#elif defined(STM32F4)
typedef union transponderIrDMABuffer_s {
uint32_t arcitimer[TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER]; // 620
uint32_t ilap[TRANSPONDER_DMA_BUFFER_SIZE]; // 720
uint32_t ilap[TRANSPONDER_DMA_BUFFER_SIZE_ILAP]; // 720
} transponderIrDMABuffer_t;
#endif
@ -85,14 +85,14 @@ typedef enum TransponderProvider{
} TransponderProvider;
struct transponderVTable {
void (*updateTransponderDMABuffer)(transponder_t* transponder, const uint8_t* transponderData);
void (*updateTransponderDMABuffer)(transponder_t *transponder, const uint8_t* transponderData);
};
bool transponderIrInit(const TransponderProvider* transponderProvider);
void transponderIrDisable(void);
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t* transponder_instance);
void transponderIrDMAEnable(transponder_t* transponder_instance);
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder);
void transponderIrDMAEnable(transponder_t *transponder);
void transponderIrWaitForTransmitComplete(void);

View file

@ -26,7 +26,7 @@
extern const struct transponderVTable arcitimerTansponderVTable;
static uint16_t dmaBufferOffset;
void transponderIrInitArcitimer(transponder_t* transponder){
void transponderIrInitArcitimer(transponder_t *transponder){
// from drivers/transponder_ir.h
transponder->gap_toggles = TRANSPONDER_GAP_TOGGLES_ARCITIMER;
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER;
@ -36,20 +36,20 @@ void transponderIrInitArcitimer(transponder_t* transponder){
memset(&(transponder->transponderIrDMABuffer.arcitimer), 0, TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER);
}
void updateTransponderDMABufferArcitimer(transponder_t* transponder_instance, const uint8_t* transponderData)
void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData)
{
uint8_t byteIndex;
uint8_t bitIndex;
uint8_t toggleIndex;
uint8_t hightStateIndex;
for (byteIndex = 0; byteIndex < TRANSPONDER_DATA_LENGTH_ARCITIMER; byteIndex++) {
uint8_t byteToSend = *transponderData;
transponderData++;
for (bitIndex = 0; bitIndex < TRANSPONDER_BITS_PER_BYTE_ARCITIMER; bitIndex++)
{
bool doToggles = byteToSend & (1 << (bitIndex));
for (toggleIndex = 0; toggleIndex < TRANSPONDER_TOGGLES_PER_BIT_ARCITIMER; toggleIndex++)
bool isHightState = byteToSend & (1 << (bitIndex));
for (hightStateIndex = 0; hightStateIndex < TRANSPONDER_TOGGLES_PER_BIT_ARCITIMER; hightStateIndex++)
{
transponder_instance->transponderIrDMABuffer.arcitimer[dmaBufferOffset] = doToggles ? transponder_instance->bitToggleOne : 0;
transponder->transponderIrDMABuffer.arcitimer[dmaBufferOffset] = isHightState ? transponder->bitToggleOne : 0;
dmaBufferOffset++;
}
}
@ -63,4 +63,4 @@ const struct transponderVTable arcitimerTansponderVTable = {
updateTransponderDMABufferArcitimer,
};
#endif
#endif

View file

@ -30,5 +30,5 @@
void transponderIrInitArcitimer(transponder_t* transponder);
void updateTransponderDMABufferArcitimer(transponder_t* transponder_instance, const uint8_t* transponderData);
void transponderIrInitArcitimer(transponder_t *transponder);
void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData);

View file

@ -26,48 +26,48 @@
static uint16_t dmaBufferOffset;
extern const struct transponderVTable ilapTansponderVTable;
void transponderIrInitIlap(transponder_t* transponder){
void transponderIrInitIlap(transponder_t *transponder){
// from drivers/transponder_ir.h
transponder->gap_toggles = TRANSPONDER_GAP_TOGGLES;
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE;
transponder->gap_toggles = TRANSPONDER_GAP_TOGGLES_ILAP;
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ILAP;
transponder->vTable = &ilapTansponderVTable;
transponder->timer_hz = TRANSPONDER_TIMER_MHZ;
transponder->timer_carrier_hz = TRANSPONDER_CARRIER_HZ;
memset(&(transponder->transponderIrDMABuffer.ilap), 0, TRANSPONDER_DMA_BUFFER_SIZE);
transponder->timer_hz = TRANSPONDER_TIMER_MHZ_ILAP;
transponder->timer_carrier_hz = TRANSPONDER_CARRIER_HZ_ILAP;
memset(&(transponder->transponderIrDMABuffer.ilap), 0, TRANSPONDER_DMA_BUFFER_SIZE_ILAP);
}
void updateTransponderDMABufferIlap(transponder_t* transponder_instance, const uint8_t* transponderData)
void updateTransponderDMABufferIlap(transponder_t *transponder, const uint8_t* transponderData)
{
uint8_t byteIndex;
uint8_t bitIndex;
uint8_t toggleIndex;
for (byteIndex = 0; byteIndex < TRANSPONDER_DATA_LENGTH; byteIndex++) {
for (byteIndex = 0; byteIndex < TRANSPONDER_DATA_LENGTH_ILAP; byteIndex++) {
uint8_t byteToSend = *transponderData;
transponderData++;
for (bitIndex = 0; bitIndex < TRANSPONDER_BITS_PER_BYTE; bitIndex++)
for (bitIndex = 0; bitIndex < TRANSPONDER_BITS_PER_BYTE_ILAP; bitIndex++)
{
bool doToggles = false;
if (bitIndex == 0) {
doToggles = true;
}
else if (bitIndex == TRANSPONDER_BITS_PER_BYTE - 1) {
else if (bitIndex == TRANSPONDER_BITS_PER_BYTE_ILAP - 1) {
doToggles = false;
}
else {
doToggles = byteToSend & (1 << (bitIndex - 1));
}
for (toggleIndex = 0; toggleIndex < TRANSPONDER_TOGGLES_PER_BIT; toggleIndex++)
for (toggleIndex = 0; toggleIndex < TRANSPONDER_TOGGLES_PER_BIT_ILAP; toggleIndex++)
{
if (doToggles) {
transponder_instance->transponderIrDMABuffer.ilap[dmaBufferOffset] = transponder_instance->bitToggleOne;
transponder->transponderIrDMABuffer.ilap[dmaBufferOffset] = transponder->bitToggleOne;
}
else {
transponder_instance->transponderIrDMABuffer.ilap[dmaBufferOffset] = 0;
transponder->transponderIrDMABuffer.ilap[dmaBufferOffset] = 0;
}
dmaBufferOffset++;
}
transponder_instance->transponderIrDMABuffer.ilap[dmaBufferOffset] = 0;
transponder->transponderIrDMABuffer.ilap[dmaBufferOffset] = 0;
dmaBufferOffset++;
}
}
@ -78,4 +78,4 @@ const struct transponderVTable ilapTansponderVTable = {
updateTransponderDMABufferIlap,
};
#endif
#endif

View file

@ -16,5 +16,5 @@
*/
#pragma once
void transponderIrInitIlap(transponder_t* transponder);
void updateTransponderDMABufferIlap(transponder_t* transponder_instance, const uint8_t* transponderData);
void transponderIrInitIlap(transponder_t *transponder);
void updateTransponderDMABufferIlap(transponder_t *transponder, const uint8_t* transponderData);

View file

@ -1137,8 +1137,24 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
case MSP_TRANSPONDER_CONFIG:
{
#ifdef TRANSPONDER
sbufWriteU8(dst, 1); //Transponder supported
uint8_t header = 1; //transponder supported
switch(transponderConfig()->provider){
case ILAP:
header |= 0x02;
break;
case ARCITIMER:
header |= 0x04;
break;
default:
break;
}
header |= (sizeof(transponderConfig()->data) << 4);
sbufWriteU8(dst, header);
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
sbufWriteU8(dst, transponderConfig()->data[i]);
}
@ -1146,14 +1162,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, 0); // Transponder not supported
#endif
break;
case MSP_TRANSPONDER_PROVIDER:
#ifdef TRANSPONDER
sbufWriteU8(dst, transponderConfig()->provider);
#else
sbufWriteU8(dst, 0); // Transponder not supported
#endif
break;
}
case MSP_OSD_CONFIG:
#ifdef OSD
sbufWriteU8(dst, 1); // OSD supported
@ -1685,7 +1694,26 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
#ifdef TRANSPONDER
case MSP_SET_TRANSPONDER_CONFIG:
if (dataSize != sizeof(transponderConfig()->data)) {
{
uint8_t tmp = sbufReadU8(src);
uint8_t type;
switch(tmp){
case 0x02:
type = ILAP;
break;
case 0x04:
type = ARCITIMER;
break;
}
if(type != transponderConfig()->provider){
transponderStopRepeating();
}
transponderConfigMutable()->provider = type;
if (dataSize != sizeof(transponderConfig()->data) + 1) {
return MSP_RESULT_ERROR;
}
for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
@ -1693,10 +1721,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
}
transponderUpdateData();
break;
case MSP_SET_TRANSPONDER_PROVIDER:
transponderStopRepeating();
transponderConfigMutable()->provider = sbufReadU8(src);
break;
}
#endif
#ifdef OSD

View file

@ -191,9 +191,6 @@
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
#define MSP_OSD_CONFIG 84 //out message Get osd settings - betaflight
#define MSP_SET_OSD_CONFIG 85 //in message Set osd settings - betaflight
@ -216,9 +213,6 @@
#define MSP_SENSOR_CONFIG 96
#define MSP_SET_SENSOR_CONFIG 97
#define MSP_TRANSPONDER_PROVIDER 98
#define MSP_SET_TRANSPONDER_PROVIDER 99
//
// OSD specific
//

View file

@ -883,10 +883,20 @@ $(OBJECT_DIR)/drivers/transponder_ir_arcitimer.o : \
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/transponder_ir_arcitimer.c -o $@
$(OBJECT_DIR)/drivers/transponder_ir_ilap.o : \
$(USER_DIR)/drivers/transponder_ir_ilap.c \
$(USER_DIR)/drivers/transponder_ir.h \
$(USER_DIR)/drivers/transponder_ir_ilap.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/transponder_ir_ilap.c -o $@
$(OBJECT_DIR)/transponder_unittest.o : \
$(TEST_DIR)/transponder_unittest.cc \
$(USER_DIR)/drivers/transponder_ir.h \
$(USER_DIR)/drivers/transponder_ir_arcitimer.h \
$(USER_DIR)/drivers/transponder_ir_ilap.h \
$(GTEST_HEADERS)
@mkdir -p $(dir $@)
@ -894,6 +904,7 @@ $(OBJECT_DIR)/transponder_unittest.o : \
$(OBJECT_DIR)/transponder_unittest : \
$(OBJECT_DIR)/drivers/transponder_ir_arcitimer.o \
$(OBJECT_DIR)/drivers/transponder_ir_ilap.o \
$(OBJECT_DIR)/transponder_unittest.o \
$(OBJECT_DIR)/gtest_main.a

View file

@ -64,5 +64,39 @@ TEST(transponderTest, updateTransponderDMABufferArcitimer) {
}
}
TEST(transponderTest, updateTransponderDMABufferIlap) {
//not implemented so far
}
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0x0, 0x0, 0x0};
uint8_t excepted[TRANSPONDER_DMA_BUFFER_SIZE_ILAP] = {
78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,
78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,78,78,
78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,
78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,
78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,78,78,78,78,78,
78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,
78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,
78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,0,0,0,0,0,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,
0,78,78,78,78,78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,78,78,78,78,
78,78,78,78,78,78,78,0,78,78,78,78,78,78,78,78,78,78,78,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
};
uint8_t* transponderData = data;
transponder_t transponder;
transponder.dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ILAP;
transponder.bitToggleOne = 78;
updateTransponderDMABufferIlap(&transponder, transponderData);
uint16_t i;
for(i = 0; i < transponder.dma_buffer_size; i++) {
EXPECT_EQ(transponder.transponderIrDMABuffer.ilap[i], excepted[i]);
}
}