1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +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

@ -19,11 +19,80 @@
#include "drivers/io_types.h"
bool transponderIrInit();
/*** ARCITIMER ***/
#define TRANSPONDER_BITS_PER_BYTE_ARCITIMER 8
#define TRANSPONDER_DATA_LENGTH_ARCITIMER 9
#define TRANSPONDER_TOGGLES_PER_BIT_ARCITIMER 4
#define TRANSPONDER_GAP_TOGGLES_ARCITIMER 0
#define TRANSPONDER_TOGGLES_ARCITIMER (TRANSPONDER_TOGGLES_PER_BIT_ARCITIMER + TRANSPONDER_GAP_TOGGLES_ARCITIMER)
#define TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER 155 * TRANSPONDER_TOGGLES_PER_BIT_ARCITIMER // 620
#define TRANSPONDER_TIMER_MHZ_ARCITIMER 24
#define TRANSPONDER_CARRIER_HZ_ARCITIMER 41886
/*** ******** ***/
/*** ILAP ***/
#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
/*** ******** ***/
/*
* 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) || defined(UNIT_TEST)
typedef union transponderIrDMABuffer_s {
uint8_t arcitimer[TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER]; // 620
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_ILAP]; // 720
} transponderIrDMABuffer_t;
#endif
typedef struct transponder_s {
uint8_t gap_toggles;
uint32_t timer_hz;
uint32_t timer_carrier_hz;
uint16_t bitToggleOne;
uint32_t dma_buffer_size;
#if defined(STM32F3) || defined(STM32F4)|| defined(UNIT_TEST)
transponderIrDMABuffer_t transponderIrDMABuffer;
#endif
const struct transponderVTable *vTable;
} transponder_t;
typedef enum TransponderProvider{
ARCITIMER,
ILAP
} TransponderProvider;
struct transponderVTable {
void (*updateTransponderDMABuffer)(transponder_t *transponder, const uint8_t* transponderData);
};
bool transponderIrInit(const TransponderProvider* transponderProvider);
void transponderIrDisable(void);
void transponderIrHardwareInit(ioTag_t ioTag);
void transponderIrDMAEnable(void);
void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder);
void transponderIrDMAEnable(transponder_t *transponder);
void transponderIrWaitForTransmitComplete(void);