Merge branch 'patch_v3.1.7' of https://github.com/betaflight/betaflight into patch_v3.1.7
This commit is contained in:
commit
ba995ac52b
|
@ -57,6 +57,8 @@ env:
|
||||||
# - TARGET=SPRACINGF3
|
# - TARGET=SPRACINGF3
|
||||||
# - TARGET=SPRACINGF3EVO
|
# - TARGET=SPRACINGF3EVO
|
||||||
# - TARGET=SPRACINGF3MINI
|
# - TARGET=SPRACINGF3MINI
|
||||||
|
# - TARGET=SPRACINGF3NEO
|
||||||
|
# - TARGET=SPRACINGF4EVO
|
||||||
# - TARGET=STM32F3DISCOVERY
|
# - TARGET=STM32F3DISCOVERY
|
||||||
# - TARGET=VRRACE
|
# - TARGET=VRRACE
|
||||||
# - TARGET=X_RACERSPI
|
# - TARGET=X_RACERSPI
|
||||||
|
|
|
@ -224,6 +224,58 @@ void writeEEPROM(void)
|
||||||
resumeRxSignal();
|
resumeRxSignal();
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(STM32F4)
|
||||||
|
/*
|
||||||
|
Sector 0 0x08000000 - 0x08003FFF 16 Kbytes
|
||||||
|
Sector 1 0x08004000 - 0x08007FFF 16 Kbytes
|
||||||
|
Sector 2 0x08008000 - 0x0800BFFF 16 Kbytes
|
||||||
|
Sector 3 0x0800C000 - 0x0800FFFF 16 Kbytes
|
||||||
|
Sector 4 0x08010000 - 0x0801FFFF 64 Kbytes
|
||||||
|
Sector 5 0x08020000 - 0x0803FFFF 128 Kbytes
|
||||||
|
Sector 6 0x08040000 - 0x0805FFFF 128 Kbytes
|
||||||
|
Sector 7 0x08060000 - 0x0807FFFF 128 Kbytes
|
||||||
|
Sector 8 0x08080000 - 0x0809FFFF 128 Kbytes
|
||||||
|
Sector 9 0x080A0000 - 0x080BFFFF 128 Kbytes
|
||||||
|
Sector 10 0x080C0000 - 0x080DFFFF 128 Kbytes
|
||||||
|
Sector 11 0x080E0000 - 0x080FFFFF 128 Kbytes
|
||||||
|
*/
|
||||||
|
|
||||||
|
static uint32_t getFLASHSectorForEEPROM(void)
|
||||||
|
{
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x08003FFF)
|
||||||
|
return FLASH_Sector_0;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x08007FFF)
|
||||||
|
return FLASH_Sector_1;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0800BFFF)
|
||||||
|
return FLASH_Sector_2;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0800FFFF)
|
||||||
|
return FLASH_Sector_3;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0801FFFF)
|
||||||
|
return FLASH_Sector_4;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0803FFFF)
|
||||||
|
return FLASH_Sector_5;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0805FFFF)
|
||||||
|
return FLASH_Sector_6;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0807FFFF)
|
||||||
|
return FLASH_Sector_7;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x0809FFFF)
|
||||||
|
return FLASH_Sector_8;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x080DFFFF)
|
||||||
|
return FLASH_Sector_9;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x080BFFFF)
|
||||||
|
return FLASH_Sector_10;
|
||||||
|
if (CONFIG_START_FLASH_ADDRESS <= 0x080FFFFF)
|
||||||
|
return FLASH_Sector_11;
|
||||||
|
|
||||||
|
// Not good
|
||||||
|
while (1) {
|
||||||
|
failureMode(FAILURE_FLASH_WRITE_FAILED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void writeEEPROM(void)
|
void writeEEPROM(void)
|
||||||
{
|
{
|
||||||
// Generate compile time error if the config does not fit in the reserved area of flash.
|
// Generate compile time error if the config does not fit in the reserved area of flash.
|
||||||
|
@ -255,10 +307,8 @@ void writeEEPROM(void)
|
||||||
#endif
|
#endif
|
||||||
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
|
for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
|
||||||
if (wordOffset % FLASH_PAGE_SIZE == 0) {
|
if (wordOffset % FLASH_PAGE_SIZE == 0) {
|
||||||
#if defined(STM32F40_41xxx)
|
#if defined(STM32F4)
|
||||||
status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000
|
status = FLASH_EraseSector(getFLASHSectorForEEPROM(), VoltageRange_3); //0x08060000 to 0x08080000
|
||||||
#elif defined (STM32F411xE)
|
|
||||||
status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000
|
|
||||||
#else
|
#else
|
||||||
status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
|
status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -318,8 +318,8 @@
|
||||||
#define DEF_TIM_DMA_STR_1__TIM8_CH1 DMA2_ST2
|
#define DEF_TIM_DMA_STR_1__TIM8_CH1 DMA2_ST2
|
||||||
#define DEF_TIM_DMA_STR_0__TIM8_CH1N DMA2_ST2
|
#define DEF_TIM_DMA_STR_0__TIM8_CH1N DMA2_ST2
|
||||||
#define DEF_TIM_DMA_STR_1__TIM8_CH1N DMA2_ST2
|
#define DEF_TIM_DMA_STR_1__TIM8_CH1N DMA2_ST2
|
||||||
#define DEF_TIM_DMA_STR_0__TIM8_CH2 DMA2_ST3
|
#define DEF_TIM_DMA_STR_0__TIM8_CH2 DMA2_ST2
|
||||||
#define DEF_TIM_DMA_STR_1__TIM8_CH2 DMA2_ST2
|
#define DEF_TIM_DMA_STR_1__TIM8_CH2 DMA2_ST3
|
||||||
#define DEF_TIM_DMA_STR_0__TIM8_CH2N DMA2_ST3
|
#define DEF_TIM_DMA_STR_0__TIM8_CH2N DMA2_ST3
|
||||||
#define DEF_TIM_DMA_STR_1__TIM8_CH2N DMA2_ST2
|
#define DEF_TIM_DMA_STR_1__TIM8_CH2N DMA2_ST2
|
||||||
#define DEF_TIM_DMA_STR_0__TIM8_CH3 DMA2_ST2
|
#define DEF_TIM_DMA_STR_0__TIM8_CH3 DMA2_ST2
|
||||||
|
|
|
@ -24,9 +24,35 @@
|
||||||
#include "dma.h"
|
#include "dma.h"
|
||||||
#include "nvic.h"
|
#include "nvic.h"
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
|
#include "rcc.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
#if defined(STM32F4)
|
||||||
|
#include "timer_stm32f4xx.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "transponder_ir.h"
|
#include "transponder_ir.h"
|
||||||
|
|
||||||
|
#if defined(STM32F3)
|
||||||
|
#define TRANSPONDER_TIMER_PERIOD 156
|
||||||
|
#define TRANSPONDER_TIMER_HZ 72000000
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
#define TRANSPONDER_TIMER_PERIOD 184
|
||||||
|
#define TRANSPONDER_TIMER_HZ 84000000
|
||||||
|
#else
|
||||||
|
#error "Transponder not supported on this MCU."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BIT_TOGGLE_1 (TRANSPONDER_TIMER_PERIOD / 2)
|
||||||
|
#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:
|
* Implementation note:
|
||||||
* Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast
|
* Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast
|
||||||
|
@ -35,10 +61,153 @@
|
||||||
*
|
*
|
||||||
* On an STM32F303CC 720 bytes is currently fine and that is the target for which this code was designed for.
|
* 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];
|
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
|
||||||
|
|
||||||
volatile uint8_t transponderIrDataTransferInProgress = 0;
|
volatile uint8_t transponderIrDataTransferInProgress = 0;
|
||||||
|
|
||||||
|
static IO_t transponderIO = IO_NONE;
|
||||||
|
static TIM_TypeDef *timer = NULL;
|
||||||
|
#if defined(STM32F3)
|
||||||
|
static DMA_Channel_TypeDef *dmaChannel = NULL;
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
static DMA_Stream_TypeDef *stream = NULL;
|
||||||
|
#else
|
||||||
|
#error "Transponder not supported on this MCU."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static void TRANSPONDER_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
|
{
|
||||||
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||||
|
transponderIrDataTransferInProgress = 0;
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_Cmd(descriptor->channel, DISABLE);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_Cmd(descriptor->stream, DISABLE);
|
||||||
|
#endif
|
||||||
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void transponderIrHardwareInit(ioTag_t ioTag)
|
||||||
|
{
|
||||||
|
if (!ioTag) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
|
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
||||||
|
timer = timerHardware->tim;
|
||||||
|
|
||||||
|
#if defined(STM32F3)
|
||||||
|
if (timerHardware->dmaChannel == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
if (timerHardware->dmaStream == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
transponderIO = IOGetByTag(ioTag);
|
||||||
|
IOInit(transponderIO, OWNER_TRANSPONDER, 0);
|
||||||
|
IOConfigGPIOAF(transponderIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN), timerHardware->alternateFunction);
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_TRANSPONDER, 0);
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, TRANSPONDER_DMA_IRQHandler, NVIC_PRIO_TRANSPONDER_DMA, 0);
|
||||||
|
|
||||||
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
|
|
||||||
|
uint16_t prescalerValue = (uint16_t)(SystemCoreClock / timerClockDivisor(timer) / TRANSPONDER_TIMER_HZ) - 1;
|
||||||
|
|
||||||
|
/* Time base configuration */
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
TIM_TimeBaseStructure.TIM_Period = TRANSPONDER_TIMER_PERIOD;
|
||||||
|
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||||
|
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||||
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
|
/* PWM1 Mode configuration: Channel1 */
|
||||||
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||||
|
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||||
|
} else {
|
||||||
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
|
}
|
||||||
|
|
||||||
|
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||||
|
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||||
|
#if defined(STM32F3)
|
||||||
|
TIM_OC1Init(timer, &TIM_OCInitStructure);
|
||||||
|
TIM_OC1PreloadConfig(timer, TIM_OCPreload_Enable);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
|
||||||
|
timerOCPreloadConfig(timer, timerHardware->channel, TIM_OCPreload_Enable);
|
||||||
|
#endif
|
||||||
|
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||||
|
|
||||||
|
/* configure DMA */
|
||||||
|
#if defined(STM32F3)
|
||||||
|
dmaChannel = timerHardware->dmaChannel;
|
||||||
|
DMA_DeInit(dmaChannel);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
stream = timerHardware->dmaStream;
|
||||||
|
DMA_Cmd(stream, DISABLE);
|
||||||
|
DMA_DeInit(stream);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)transponderIrDMABuffer;
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)transponderIrDMABuffer;
|
||||||
|
#endif
|
||||||
|
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)
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||||
|
#endif
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
|
||||||
|
DMA_Init(dmaChannel, &DMA_InitStructure);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||||
|
|
||||||
|
DMA_Init(stream, &DMA_InitStructure);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
||||||
|
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_ITConfig(dmaChannel, DMA_IT_TC, ENABLE);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_ITConfig(stream, DMA_IT_TC, ENABLE);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
bool transponderIrInit(void)
|
bool transponderIrInit(void)
|
||||||
{
|
{
|
||||||
memset(&transponderIrDMABuffer, 0, TRANSPONDER_DMA_BUFFER_SIZE);
|
memset(&transponderIrDMABuffer, 0, TRANSPONDER_DMA_BUFFER_SIZE);
|
||||||
|
@ -57,6 +226,7 @@ bool transponderIrInit(void)
|
||||||
|
|
||||||
|
|
||||||
transponderIrHardwareInit(ioTag);
|
transponderIrHardwareInit(ioTag);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -119,6 +289,40 @@ void transponderIrUpdateData(const uint8_t* transponderData)
|
||||||
updateTransponderDMABuffer(transponderData);
|
updateTransponderDMABuffer(transponderData);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void transponderIrDMAEnable(void)
|
||||||
|
{
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_SetCurrDataCounter(dmaChannel, TRANSPONDER_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_SetCurrDataCounter(stream, TRANSPONDER_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||||
|
#endif
|
||||||
|
TIM_SetCounter(timer, 0);
|
||||||
|
TIM_Cmd(timer, ENABLE);
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_Cmd(dmaChannel, ENABLE);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_Cmd(stream, ENABLE);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void transponderIrDisable(void)
|
||||||
|
{
|
||||||
|
#if defined(STM32F3)
|
||||||
|
DMA_Cmd(dmaChannel, DISABLE);
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
DMA_Cmd(stream, DISABLE);
|
||||||
|
#endif
|
||||||
|
TIM_Cmd(timer, DISABLE);
|
||||||
|
|
||||||
|
IOInit(transponderIO, OWNER_TRANSPONDER, 0);
|
||||||
|
IOConfigGPIOAF(transponderIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN), timerHardware->alternateFunction);
|
||||||
|
|
||||||
|
#ifdef TRANSPONDER_INVERTED
|
||||||
|
IOHi(transponderIO);
|
||||||
|
#else
|
||||||
|
IOLo(transponderIO);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
void transponderIrTransmit(void)
|
void transponderIrTransmit(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -19,17 +19,6 @@
|
||||||
|
|
||||||
#include "io_types.h"
|
#include "io_types.h"
|
||||||
|
|
||||||
#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)
|
|
||||||
|
|
||||||
#define BIT_TOGGLE_1 78 // (156 / 2)
|
|
||||||
#define BIT_TOGGLE_0 0
|
|
||||||
|
|
||||||
bool transponderIrInit();
|
bool transponderIrInit();
|
||||||
void transponderIrDisable(void);
|
void transponderIrDisable(void);
|
||||||
|
|
||||||
|
@ -43,5 +32,4 @@ void transponderIrTransmit(void);
|
||||||
|
|
||||||
bool isTransponderIrReady(void);
|
bool isTransponderIrReady(void);
|
||||||
|
|
||||||
extern uint8_t transponderIrDMABuffer[TRANSPONDER_DMA_BUFFER_SIZE];
|
|
||||||
extern volatile uint8_t transponderIrDataTransferInProgress;
|
extern volatile uint8_t transponderIrDataTransferInProgress;
|
||||||
|
|
|
@ -1,139 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include <platform.h>
|
|
||||||
|
|
||||||
#include "io.h"
|
|
||||||
#include "nvic.h"
|
|
||||||
|
|
||||||
#include "dma.h"
|
|
||||||
#include "rcc.h"
|
|
||||||
#include "timer.h"
|
|
||||||
|
|
||||||
#include "transponder_ir.h"
|
|
||||||
|
|
||||||
static IO_t transponderIO = IO_NONE;
|
|
||||||
static DMA_Channel_TypeDef *dmaChannel = NULL;
|
|
||||||
static TIM_TypeDef *timer = NULL;
|
|
||||||
|
|
||||||
static void TRANSPONDER_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
|
||||||
{
|
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
|
||||||
transponderIrDataTransferInProgress = 0;
|
|
||||||
DMA_Cmd(descriptor->channel, DISABLE);
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void transponderIrHardwareInit(ioTag_t ioTag)
|
|
||||||
{
|
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
|
||||||
|
|
||||||
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
|
||||||
timer = timerHardware->tim;
|
|
||||||
|
|
||||||
if (timerHardware->dmaChannel == NULL) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
transponderIO = IOGetByTag(ioTag);
|
|
||||||
IOInit(transponderIO, OWNER_TRANSPONDER, 0);
|
|
||||||
IOConfigGPIOAF(transponderIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN), timerHardware->alternateFunction);
|
|
||||||
|
|
||||||
dmaInit(timerHardware->dmaIrqHandler, OWNER_TRANSPONDER, 0);
|
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, TRANSPONDER_DMA_IRQHandler, NVIC_PRIO_TRANSPONDER_DMA, 0);
|
|
||||||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
|
||||||
|
|
||||||
/* Time base configuration */
|
|
||||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
|
||||||
TIM_TimeBaseStructure.TIM_Period = 156;
|
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = 0;
|
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
|
||||||
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
|
||||||
|
|
||||||
/* PWM1 Mode configuration: Channel1 */
|
|
||||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
|
||||||
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
|
||||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
|
||||||
} else {
|
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
|
||||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
|
||||||
}
|
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
|
||||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
|
||||||
TIM_OC1Init(timer, &TIM_OCInitStructure);
|
|
||||||
TIM_OC1PreloadConfig(timer, TIM_OCPreload_Enable);
|
|
||||||
|
|
||||||
TIM_CtrlPWMOutputs(timer, ENABLE);
|
|
||||||
|
|
||||||
/* configure DMA */
|
|
||||||
dmaChannel = timerHardware->dmaChannel;
|
|
||||||
DMA_DeInit(dmaChannel);
|
|
||||||
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)transponderIrDMABuffer;
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
|
||||||
DMA_InitStructure.DMA_BufferSize = TRANSPONDER_DMA_BUFFER_SIZE;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
|
||||||
|
|
||||||
DMA_Init(dmaChannel, &DMA_InitStructure);
|
|
||||||
|
|
||||||
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
|
||||||
|
|
||||||
DMA_ITConfig(dmaChannel, DMA_IT_TC, ENABLE);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void transponderIrDMAEnable(void)
|
|
||||||
{
|
|
||||||
DMA_SetCurrDataCounter(dmaChannel, TRANSPONDER_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
|
||||||
TIM_SetCounter(timer, 0);
|
|
||||||
TIM_Cmd(timer, ENABLE);
|
|
||||||
DMA_Cmd(dmaChannel, ENABLE);
|
|
||||||
}
|
|
||||||
|
|
||||||
void transponderIrDisable(void)
|
|
||||||
{
|
|
||||||
DMA_Cmd(dmaChannel, DISABLE);
|
|
||||||
TIM_Cmd(timer, DISABLE);
|
|
||||||
|
|
||||||
IOInit(transponderIO, OWNER_TRANSPONDER, 0);
|
|
||||||
IOConfigGPIOAF(transponderIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN), timerHardware->alternateFunction);
|
|
||||||
|
|
||||||
#ifdef TRANSPONDER_INVERTED
|
|
||||||
IOHi(transponderIO);
|
|
||||||
#else
|
|
||||||
IOLo(transponderIO);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
|
@ -12,5 +12,4 @@ TARGET_SRC = \
|
||||||
drivers/max7456.c \
|
drivers/max7456.c \
|
||||||
drivers/serial_usb_vcp.c \
|
drivers/serial_usb_vcp.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
io/transponder_ir.c
|
io/transponder_ir.c
|
||||||
|
|
|
@ -5,6 +5,5 @@ TARGET_SRC = \
|
||||||
drivers/accgyro_mpu.c \
|
drivers/accgyro_mpu.c \
|
||||||
drivers/accgyro_spi_mpu6000.c \
|
drivers/accgyro_spi_mpu6000.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
io/transponder_ir.c
|
io/transponder_ir.c
|
||||||
|
|
||||||
|
|
|
@ -8,7 +8,6 @@ TARGET_SRC = \
|
||||||
drivers/light_ws2811strip_stm32f30x.c \
|
drivers/light_ws2811strip_stm32f30x.c \
|
||||||
drivers/serial_usb_vcp.c \
|
drivers/serial_usb_vcp.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
io/transponder_ir.c
|
io/transponder_ir.c
|
||||||
|
|
||||||
HSE_VALUE = 12000000
|
HSE_VALUE = 12000000
|
||||||
|
|
|
@ -9,6 +9,5 @@ TARGET_SRC = \
|
||||||
drivers/compass_ak8963.c \
|
drivers/compass_ak8963.c \
|
||||||
drivers/serial_usb_vcp.c \
|
drivers/serial_usb_vcp.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
io/transponder_ir.c
|
io/transponder_ir.c
|
||||||
|
|
||||||
|
|
|
@ -10,7 +10,6 @@ TARGET_SRC = \
|
||||||
drivers/compass_ak8963.c \
|
drivers/compass_ak8963.c \
|
||||||
drivers/flash_m25p16.c \
|
drivers/flash_m25p16.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
io/transponder_ir.c
|
io/transponder_ir.c
|
||||||
|
|
||||||
ifeq ($(TARGET), TINYBEEF3)
|
ifeq ($(TARGET), TINYBEEF3)
|
||||||
|
|
|
@ -13,7 +13,6 @@ TARGET_SRC = \
|
||||||
drivers/light_ws2811strip_stm32f30x.c \
|
drivers/light_ws2811strip_stm32f30x.c \
|
||||||
drivers/serial_usb_vcp.c \
|
drivers/serial_usb_vcp.c \
|
||||||
drivers/transponder_ir.c \
|
drivers/transponder_ir.c \
|
||||||
drivers/transponder_ir_stm32f30x.c \
|
|
||||||
drivers/max7456.c \
|
drivers/max7456.c \
|
||||||
drivers/vtx_rtc6705.c \
|
drivers/vtx_rtc6705.c \
|
||||||
io/osd.c \
|
io/osd.c \
|
||||||
|
|
|
@ -0,0 +1,64 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "drivers/sensor.h"
|
||||||
|
#include "drivers/compass.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
#include "flight/failsafe.h"
|
||||||
|
#include "flight/mixer.h"
|
||||||
|
#include "flight/pid.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
#include "sensors/compass.h"
|
||||||
|
#include "sensors/barometer.h"
|
||||||
|
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#ifdef TARGET_CONFIG
|
||||||
|
void targetConfiguration(master_t *config)
|
||||||
|
{
|
||||||
|
UNUSED(config);
|
||||||
|
|
||||||
|
barometerConfig()->baro_hardware = BARO_DEFAULT;
|
||||||
|
rxConfig()->sbus_inversion = 1;
|
||||||
|
serialConfig()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything.
|
||||||
|
serialConfig()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_RX_SERIAL;
|
||||||
|
serialConfig()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||||
|
telemetryConfig()->telemetry_inversion = 0;
|
||||||
|
telemetryConfig()->sportHalfDuplex = 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -0,0 +1,65 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
#include "drivers/timer_def.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
|
||||||
|
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
|
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // PPM / PWM1 / UART2 RX
|
||||||
|
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PPM / PWM2 / UART2 TX
|
||||||
|
|
||||||
|
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 1, 1), // ESC 1
|
||||||
|
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 1, 1), // ESC 2
|
||||||
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 1, 0), // ESC 3
|
||||||
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 1, 1), // ESC 4
|
||||||
|
|
||||||
|
#if (SPRACINGF4EVO_REV >= 2)
|
||||||
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 1, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0
|
||||||
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 1, 0), // ESC 6 / Conflicts with USART3_RX
|
||||||
|
#else
|
||||||
|
#ifdef USE_TIM10_TIM11_FOR_MOTORS
|
||||||
|
DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR, 1, 0), // ESC 5
|
||||||
|
DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR, 1, 0), // ESC 6
|
||||||
|
#else
|
||||||
|
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 1, 0), // ESC 5
|
||||||
|
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 1, 0), // ESC 6
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // ESC 7
|
||||||
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // ESC 8
|
||||||
|
|
||||||
|
DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 1, 0), // LED Strip
|
||||||
|
// Additional 2 PWM channels available on UART3 RX/TX pins
|
||||||
|
// However, when using led strip the timer cannot be used, but no code appears to prevent that right now
|
||||||
|
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 1, 0), // Shared with UART3 TX PIN and SPI3 TX (OSD)
|
||||||
|
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 1, 1), // Shared with UART3 RX PIN
|
||||||
|
|
||||||
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1, 0), // Transponder
|
||||||
|
// Additional 2 PWM channels available on UART1 RX/TX pins
|
||||||
|
// However, when using transponder the timer cannot be used, but no code appears to prevent that right now
|
||||||
|
DEF_TIM(TIM1, CH2, PA9, TIM_USE_SERVO | TIM_USE_PWM, 1, 1), // PWM 3
|
||||||
|
DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_PWM, 1, 1), // PWM 4
|
||||||
|
|
||||||
|
};
|
|
@ -0,0 +1,192 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "SP4E"
|
||||||
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
|
#ifndef SPRACINGF4EVO_REV
|
||||||
|
#define SPRACINGF4EVO_REV 2
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define USBD_PRODUCT_STRING "SP Racing F4 NEO"
|
||||||
|
|
||||||
|
#define LED0 PA0
|
||||||
|
|
||||||
|
#define BEEPER PC15
|
||||||
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
#define INVERTER_PIN_USART2 PB2
|
||||||
|
|
||||||
|
#define USE_EXTI
|
||||||
|
#define MPU_INT_EXTI PC13
|
||||||
|
|
||||||
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
|
#define ACC
|
||||||
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
|
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||||
|
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
#define BARO
|
||||||
|
#define USE_BARO_BMP280
|
||||||
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
|
#define MAG
|
||||||
|
#define USE_MAG_AK8975
|
||||||
|
#define USE_MAG_HMC5883
|
||||||
|
|
||||||
|
#define USB_IO
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_UART1
|
||||||
|
#define USE_UART2
|
||||||
|
#define USE_UART3
|
||||||
|
#define USE_UART4
|
||||||
|
#define USE_UART5
|
||||||
|
#define SERIAL_PORT_COUNT 6
|
||||||
|
|
||||||
|
#define UART1_TX_PIN PA9
|
||||||
|
#define UART1_RX_PIN PA10
|
||||||
|
|
||||||
|
#define UART2_TX_PIN PA2
|
||||||
|
#define UART2_RX_PIN PA3
|
||||||
|
|
||||||
|
#define UART3_TX_PIN PB10
|
||||||
|
#define UART3_RX_PIN PB11
|
||||||
|
|
||||||
|
#define UART4_TX_PIN PC10
|
||||||
|
#define UART4_RX_PIN PC11
|
||||||
|
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
#define UART5_RX_PIN PD2
|
||||||
|
|
||||||
|
// TODO
|
||||||
|
// #define USE_ESCSERIAL
|
||||||
|
// #define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
#if (SPRACINGF4EVO_REV >= 2)
|
||||||
|
#define I2C1_SCL PB8
|
||||||
|
#define I2C1_SDA PB9
|
||||||
|
#else
|
||||||
|
#define I2C1_SCL PB6
|
||||||
|
#define I2C1_SDA PB7
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define USE_SPI
|
||||||
|
#define USE_SPI_DEVICE_1 // MPU
|
||||||
|
#define USE_SPI_DEVICE_2 // SDCard
|
||||||
|
#define USE_SPI_DEVICE_3 // External
|
||||||
|
|
||||||
|
#define SPI1_NSS_PIN PA4
|
||||||
|
#define SPI1_SCK_PIN PA5
|
||||||
|
#define SPI1_MISO_PIN PA6
|
||||||
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
|
#define SPI2_NSS_PIN PB12
|
||||||
|
#define SPI2_SCK_PIN PB13
|
||||||
|
#define SPI2_MISO_PIN PB14
|
||||||
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
|
#define SPI3_NSS_PIN PA15 // NC
|
||||||
|
#define SPI3_SCK_PIN PB3 // NC
|
||||||
|
#define SPI3_MISO_PIN PB4 // NC
|
||||||
|
#define SPI3_MOSI_PIN PB5 // NC
|
||||||
|
|
||||||
|
#define USE_SDCARD
|
||||||
|
#define USE_SDCARD_SPI2
|
||||||
|
|
||||||
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
|
||||||
|
#define SDCARD_DETECT_PIN PC14
|
||||||
|
#define SDCARD_SPI_INSTANCE SPI2
|
||||||
|
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
|
|
||||||
|
// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||||
|
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||||
|
// Divide to under 25MHz for normal operation:
|
||||||
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||||
|
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
||||||
|
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||||
|
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||||
|
|
||||||
|
|
||||||
|
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||||
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
|
#define USE_ADC
|
||||||
|
#define ADC_INSTANCE ADC1
|
||||||
|
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||||
|
|
||||||
|
#define VBAT_ADC_PIN PC1
|
||||||
|
#define CURRENT_METER_ADC_PIN PC2
|
||||||
|
#define RSSI_ADC_PIN PC0
|
||||||
|
|
||||||
|
// PC4 - NC - Free for ADC12_IN14 / VTX CS
|
||||||
|
// PC5 - NC - Free for ADC12_IN15 / VTX Enable / OSD VSYNC
|
||||||
|
|
||||||
|
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||||
|
|
||||||
|
|
||||||
|
#define LED_STRIP
|
||||||
|
#define TRANSPONDER
|
||||||
|
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_LED_STRIP)
|
||||||
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
|
#define TELEMETRY_UART SERIAL_PORT_USART5
|
||||||
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART3
|
||||||
|
#define BIND_PIN UART2_RX_PIN
|
||||||
|
|
||||||
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
#define TARGET_IO_PORTD (BIT(2))
|
||||||
|
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 16 // 4xPWM, 8xESC, 2xESC via UART3 RX/TX, 1xLED Strip, 1xIR.
|
||||||
|
#if (SPRACINGF4NEO_REV >= 2)
|
||||||
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9))
|
||||||
|
#else
|
||||||
|
#define USE_TIM10_TIM11_FOR_MOTORS
|
||||||
|
#ifdef USE_TIM10_TIM11_FOR_MOTORS
|
||||||
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))
|
||||||
|
#else
|
||||||
|
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9))
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,18 @@
|
||||||
|
F405_TARGETS += $(TARGET)
|
||||||
|
FEATURES = VCP SDCARD
|
||||||
|
|
||||||
|
TARGET_SRC = \
|
||||||
|
drivers/accgyro_mpu6500.c \
|
||||||
|
drivers/accgyro_spi_mpu6500.c \
|
||||||
|
drivers/barometer_bmp280.c \
|
||||||
|
drivers/barometer_ms5611.c \
|
||||||
|
drivers/compass_ak8975.c \
|
||||||
|
drivers/compass_hmc5883l.c \
|
||||||
|
drivers/max7456.c \
|
||||||
|
drivers/transponder_ir.c \
|
||||||
|
drivers/vtx_rtc6705.c \
|
||||||
|
io/osd.c \
|
||||||
|
io/transponder_ir.c \
|
||||||
|
io/vtx.c
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue