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

Cherry-pick CF/9f7f2f2

This commit is contained in:
Dominic Clifton 2017-04-01 18:07:19 +01:00 committed by jflyper
parent 5bc79368be
commit a4ee4102d7
12 changed files with 446 additions and 90 deletions

View file

@ -30,36 +30,8 @@
#include "timer.h"
#include "transponder_ir.h"
#define TRANSPONDER_TIMER_MHZ 24
#define TRANSPONDER_CARRIER_HZ 460750
static uint8_t bitToggleOne = 0;
#define BIT_TOGGLE_0 0
#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)
/*
* Implementation note:
* Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast
* ISR to generate the output signal dynamically based on state would be more memory efficient and would likely be more appropriate for
* other targets. However this approach requires very little CPU time and is just fire-and-forget.
*
* On an STM32F303CC 720 bytes is currently fine and that is the target for which this code was designed for.
*/
#if defined(STM32F3)
uint8_t transponderIrDMABuffer[TRANSPONDER_DMA_BUFFER_SIZE];
#elif defined(STM32F4)
uint32_t transponderIrDMABuffer[TRANSPONDER_DMA_BUFFER_SIZE];
#else
#error "Transponder not supported on this MCU."
#endif
#include "drivers/transponder_ir_arcitimer.h"
#include "drivers/transponder_ir_ilap.h"
volatile uint8_t transponderIrDataTransferInProgress = 0;
@ -74,6 +46,8 @@ static DMA_Stream_TypeDef *dmaRef = NULL;
#error "Transponder not supported on this MCU."
#endif
transponder_t transponder;
static void TRANSPONDER_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
{
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
@ -84,7 +58,7 @@ static void TRANSPONDER_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
}
}
void transponderIrHardwareInit(ioTag_t ioTag)
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
{
if (!ioTag) {
return;
@ -110,11 +84,10 @@ void transponderIrHardwareInit(ioTag_t ioTag)
RCC_ClockCmd(timerRCC(timer), ENABLE);
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, TRANSPONDER_TIMER_MHZ);
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, TRANSPONDER_CARRIER_HZ);
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, transponder->timer_hz);
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, transponder->timer_carrier_hz);
bitToggleOne = period / 2;
transponder->bitToggleOne = period / 2;
/* Time base configuration */
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = period;
@ -149,15 +122,15 @@ void transponderIrHardwareInit(ioTag_t ioTag)
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
#if defined(STM32F3)
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)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)transponderIrDMABuffer;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&(transponder->transponderIrDMABuffer);
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
#endif
DMA_InitStructure.DMA_BufferSize = TRANSPONDER_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)
@ -178,10 +151,8 @@ void transponderIrHardwareInit(ioTag_t ioTag)
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
}
bool transponderIrInit(void)
bool transponderIrInit(const TransponderProvider* transponderProvider)
{
memset(&transponderIrDMABuffer, 0, TRANSPONDER_DMA_BUFFER_SIZE);
ioTag_t ioTag = IO_TAG_NONE;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_TRANSPONDER) {
@ -194,8 +165,17 @@ bool transponderIrInit(void)
return false;
}
uint8_t transponderProviderLocal = *transponderProvider;
switch(transponderProviderLocal){
case ARCITIMER:
transponderIrInitArcitimer(&transponder);
break;
case ILAP:
transponderIrInitIlap(&transponder);
break;
}
transponderIrHardwareInit(ioTag);
transponderIrHardwareInit(ioTag, &transponder);
return true;
}
@ -207,42 +187,6 @@ bool isTransponderIrReady(void)
static uint16_t dmaBufferOffset;
void updateTransponderDMABuffer(const uint8_t* transponderData)
{
uint8_t byteIndex;
uint8_t bitIndex;
uint8_t toggleIndex;
for (byteIndex = 0; byteIndex < TRANSPONDER_DATA_LENGTH; byteIndex++) {
uint8_t byteToSend = *transponderData;
transponderData++;
for (bitIndex = 0; bitIndex < TRANSPONDER_BITS_PER_BYTE; bitIndex++)
{
bool doToggles = false;
if (bitIndex == 0) {
doToggles = true;
} else if (bitIndex == TRANSPONDER_BITS_PER_BYTE - 1) {
doToggles = false;
} else {
doToggles = byteToSend & (1 << (bitIndex - 1));
}
for (toggleIndex = 0; toggleIndex < TRANSPONDER_TOGGLES_PER_BIT; toggleIndex++)
{
if (doToggles) {
transponderIrDMABuffer[dmaBufferOffset] = bitToggleOne;
} else {
transponderIrDMABuffer[dmaBufferOffset] = BIT_TOGGLE_0;
}
dmaBufferOffset++;
}
transponderIrDMABuffer[dmaBufferOffset] = BIT_TOGGLE_0;
dmaBufferOffset++;
}
}
}
void transponderIrWaitForTransmitComplete(void)
{
static uint32_t waitCounter = 0;
@ -254,14 +198,13 @@ void transponderIrWaitForTransmitComplete(void)
void transponderIrUpdateData(const uint8_t* transponderData)
{
transponderIrWaitForTransmitComplete();
updateTransponderDMABuffer(transponderData);
transponderIrWaitForTransmitComplete();
transponder.vTable->updateTransponderDMABuffer(&transponder, transponderData);
}
void transponderIrDMAEnable(void)
void transponderIrDMAEnable(transponder_t *transponder)
{
DMA_SetCurrDataCounter(dmaRef, TRANSPONDER_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);
@ -289,6 +232,6 @@ void transponderIrTransmit(void)
dmaBufferOffset = 0;
transponderIrDataTransferInProgress = 1;
transponderIrDMAEnable();
transponderIrDMAEnable(&transponder);
}
#endif