1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

update according to the review comment

This commit is contained in:
jianpingwu1 2025-07-09 16:32:00 +08:00
parent a4af1c1d57
commit 20e5d47aab
34 changed files with 203 additions and 357 deletions

View file

@ -70,10 +70,10 @@
#define STATIC_ASSERT(condition, name) static_assert((condition), #name)
#endif
#if defined(USE_GDBSP_DRIVER)
#ifdef BIT
#undef BIT
#endif
#define BIT(x) (1 << (x))
#endif
/*
http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html

View file

@ -25,12 +25,10 @@
#include "drivers/io_types.h"
#include "drivers/time.h"
#ifndef ADC_INSTANCE
#if defined(USE_ADC_DEVICE_0)
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC0
#endif
#else
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1
#endif
#endif

View file

@ -41,15 +41,10 @@
#define NVIC_PRIO_SERIALUART0_TXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART0_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART0 NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 2)
#else
#endif
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 1)
#endif
#define NVIC_PRIO_SERIALUART2_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART2_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART2 NVIC_BUILD_PRIORITY(1, 2)

View file

@ -301,8 +301,6 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture
pwmInputPort->state = 1;
#if defined(USE_HAL_DRIVER)
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPOLARITY_FALLING);
#elif defined(USE_GDBSP_DRIVER)
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIMER_IC_POLARITY_FALLING);
#else
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
#endif
@ -317,8 +315,6 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture
pwmInputPort->state = 0;
#if defined(USE_HAL_DRIVER)
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPOLARITY_RISING);
#elif defined(USE_GDBSP_DRIVER)
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIMER_IC_POLARITY_RISING);
#else
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
#endif
@ -418,8 +414,6 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
#if defined(USE_HAL_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING);
#elif defined(USE_GDBSP_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIMER_IC_POLARITY_RISING);
#else
pwmICConfig(timer->tim, timer->channel, TIM_ICPolarity_Rising);
#endif
@ -430,34 +424,22 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
#define FIRST_PWM_PORT 0
#ifdef USE_PWM_OUTPUT
static void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
{
pwmOutputPort_t *motors = pwmGetMotors();
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
if (!motors[motorIndex].enabled || motors[motorIndex].channel.tim != pwmTimer) {
continue;
}
#if defined(USE_GDBSP_DRIVER)
static void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
{
pwmOutputPort_t *motors = pwmGetMotors();
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
if (!motors[motorIndex].enabled || motors[motorIndex].channel.tim != pwmTimer) {
continue;
}
ppmCountDivisor = timerClock(pwmTimer) / (TIMER_PSC((uint32_t)pwmTimer) + 1);
return;
}
}
ppmCountDivisor = timerClock(pwmTimer) / timerPrescaler(pwmTimer);
#else
static void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
{
pwmOutputPort_t *motors = pwmGetMotors();
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
if (!motors[motorIndex].enabled || motors[motorIndex].channel.tim != pwmTimer) {
continue;
}
ppmCountDivisor = timerClock(pwmTimer) / (pwmTimer->PSC + 1);
#endif
return;
}
}
#endif
#endif
void ppmRxInit(const ppmConfig_t *ppmConfig)
{
@ -489,8 +471,6 @@ void ppmRxInit(const ppmConfig_t *ppmConfig)
#if defined(USE_HAL_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING);
#elif defined(USE_GDBSP_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIMER_IC_POLARITY_RISING);
#else
pwmICConfig(timer->tim, timer->channel, TIM_ICPolarity_Rising);
#endif

View file

@ -444,6 +444,17 @@ const struct serialPortVTable uartVTable[] = {
}
};
#ifdef USE_GDBSP_DRIVER
// GDBSP driver uses IRQ handlers with different naming scheme
#define UART_IRQHandler(type, number, dev) \
FAST_IRQ_HANDLER void CONCAT( \
_UART_GET_PREFIX(dev), \
number ## _IRQHandler)(void) \
{ \
uartPort_t *uartPort = &(uartDevice[(dev)].port); \
uartIrqHandler(uartPort); \
}
#else
#define UART_IRQHandler(type, number, dev) \
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
{ \
@ -451,57 +462,8 @@ const struct serialPortVTable uartVTable[] = {
uartIrqHandler(uartPort); \
} \
/**/
#ifdef USE_GDBSP_DRIVER
UART_IRQHandler(USART, 0, UARTDEV_0) // USART0 Rx/Tx IRQ Handler
#ifdef USE_UART1
UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART2
UART_IRQHandler(USART, 2, UARTDEV_2) // USART2 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART3
UART_IRQHandler(UART, 3, UARTDEV_3) // UART3 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART4
UART_IRQHandler(UART, 4, UARTDEV_4) // UART4 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART5
UART_IRQHandler(USART, 5, UARTDEV_5) // USART5 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART6
UART_IRQHandler(UART, 6, UARTDEV_6) // UART6 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART7
UART_IRQHandler(UART, 7, UARTDEV_7) // UART7 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART8
UART_IRQHandler(UART, 8, UARTDEV_8) // UART8 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART9
UART_IRQHandler(UART, 9, UARTDEV_9) // UART9 Rx/Tx IRQ Handler
#endif
#ifdef USE_UART10
UART_IRQHandler(USART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
#endif
#ifdef USE_LPUART1
UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
#endif
#else // USE_GDBSP_DRIVER
#ifdef USE_UART1
UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
#endif
@ -546,6 +508,4 @@ UART_IRQHandler(USART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
#endif
#endif // USE_GDBSP_DRIVER
#endif // USE_UART

View file

@ -41,12 +41,8 @@ void pgResetFn_adcConfig(adcConfig_t *adcConfig)
adcConfig->device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_INSTANCE));
#if defined(USE_ADC_DEVICE_0)
adcConfig->dmaopt[ADCDEV_0] = ADC0_DMA_OPT;
#if defined(ADC1)
adcConfig->dmaopt[ADCDEV_1] = ADC1_DMA_OPT;
#endif
#else
adcConfig->dmaopt[ADCDEV_1] = ADC1_DMA_OPT;
#endif
// These conditionals need to match the ones used in 'src/main/drivers/adc.h'.
#if defined(ADC2)
adcConfig->dmaopt[ADCDEV_2] = ADC2_DMA_OPT;

View file

@ -43,7 +43,7 @@
const adcDevice_t adcHardware[] = {
{
.ADCx = (void *)ADC0,
.ADCx = (ADC_TypeDef *)ADC0,
.rccADC = RCC_APB2(ADC0),
#if !defined(USE_DMA_SPEC)
.dmaResource = (dmaResource_t *)ADC0_DMA_STREAM,
@ -51,7 +51,7 @@ const adcDevice_t adcHardware[] = {
#endif
},
{
.ADCx = (void *)ADC1,
.ADCx = (ADC_TypeDef *)ADC1,
.rccADC = RCC_APB2(ADC1),
#if !defined(USE_DMA_SPEC)
.dmaResource = (dmaResource_t *)ADC1_DMA_STREAM,
@ -59,7 +59,7 @@ const adcDevice_t adcHardware[] = {
#endif
},
{
.ADCx = (void *)ADC2,
.ADCx = (ADC_TypeDef *)ADC2,
.rccADC = RCC_APB2(ADC2),
#if !defined(USE_DMA_SPEC)
.dmaResource = (dmaResource_t *)ADC2_DMA_STREAM,
@ -182,7 +182,7 @@ void adcInit(const adcConfig_t *config)
}
if (config->rssi.enabled) {
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
}
if (config->external1.enabled) {
@ -230,9 +230,9 @@ void adcInit(const adcConfig_t *config)
adc_sync_delay_config(ADC_SYNC_DELAY_5CYCLE);
#ifdef USE_ADC_INTERNAL
// If device is not ADC1 or there's no active channel, then initialize ADC1 separately
if (device != ADCDEV_1 || !adcActive) {
RCC_ClockCmd(adcHardware[ADCDEV_1].rccADC, ENABLE);
// If device is not ADC0 or there's no active channel, then initialize ADC0 separately
if (device != ADCDEV_0 || !adcActive) {
RCC_ClockCmd(adcHardware[ADCDEV_0].rccADC, ENABLE);
adcInitDevice(ADC0, 2);
adc_enable(ADC0);
}
@ -282,15 +282,15 @@ void adcInit(const adcConfig_t *config)
dma_single_data_parameter_struct dma_init_struct;
dma_single_data_para_struct_init(&dma_init_struct);
dma_init_struct.periph_addr = (uint32_t)(&ADC_RDATA((uint32_t)(adc.ADCx))); // (uint32_t)(&ADC_RDATA(ADC0)) ADC0即(uint32_t)(adc.ADCx)
dma_init_struct.periph_addr = (uint32_t)(&ADC_RDATA((uint32_t)(adc.ADCx)));
uint32_t temp_dma_periph;
int temp_dma_channel;
gd32_dma_chbase_parse((uint32_t)dmaSpec->ref, &temp_dma_periph, &temp_dma_channel);
#ifdef USE_DMA_SPEC
gd32_dma_chbase_parse((uint32_t)dmaSpec->ref, &temp_dma_periph, &temp_dma_channel);
dma_channel_subperipheral_select(temp_dma_periph, temp_dma_channel, dmaSpec->channel);
#else
gd32_dma_chbase_parse((uint32_t)adc.dmaResource, &temp_dma_periph, &temp_dma_channel);
dma_channel_subperipheral_select(temp_dma_periph, temp_dma_channel, adc.channel);
#endif
@ -303,7 +303,6 @@ void adcInit(const adcConfig_t *config)
dma_init_struct.number = configuredAdcChannels;
dma_init_struct.priority = DMA_PRIORITY_HIGH;
#ifdef USE_DMA_SPEC
gd32_dma_init((uint32_t)dmaSpec->ref, &dma_init_struct);
xDMA_Cmd(dmaSpec->ref, ENABLE);

View file

@ -44,7 +44,7 @@ void audioGenerateWhiteNoise(void)
timer_deinit(TIMER5);
timer_parameter_struct timer_initpara;
timer_initpara.prescaler = 0; // 如果需要计数频率为50Mhz这里可以4-1=3进行分频。
timer_initpara.prescaler = 0;
timer_initpara.alignedmode = TIMER_COUNTER_EDGE;
timer_initpara.counterdirection = TIMER_COUNTER_UP;
timer_initpara.period = 0xFF;

View file

@ -51,7 +51,7 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_0
{
.device = I2CDEV_0,
.reg = (void *)I2C0,
.reg = (I2C_TypeDef *)I2C0,
.sclPins = {
I2CPINDEF(PB6, GPIO_AF_4),
I2CPINDEF(PB8, GPIO_AF_4),
@ -68,7 +68,7 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_1
{
.device = I2CDEV_1,
.reg = (void *)I2C1,
.reg = (I2C_TypeDef *)I2C1,
.sclPins = {
I2CPINDEF(PB10, GPIO_AF_4),
I2CPINDEF(PF1, GPIO_AF_4),
@ -85,7 +85,7 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_2
{
.device = I2CDEV_2,
.reg = (void *)I2C2,
.reg = (I2C_TypeDef *)I2C2,
.sclPins = {
I2CPINDEF(PA8, GPIO_AF_4),
},

View file

@ -127,13 +127,7 @@ static uint32_t dma_int_ftf_flag_get(uint32_t dma_chan_base)
uint32_t dma_periph;
int channel;
if(DMA1 > dma_chan_base) {
dma_periph = DMA0;
} else {
dma_periph = DMA1;
}
channel = gd32_dma_channel_get(dma_chan_base, dma_periph);
gd32_dma_chbase_parse(dma_chan_base, &dma_periph, &channel);
status = dma_interrupt_flag_get(dma_periph, channel ,DMA_INT_FLAG_FTF);
@ -146,13 +140,7 @@ uint32_t dma_enable_status_get(uint32_t dma_chan_base)
uint32_t status;
int channel;
if(DMA1 > dma_chan_base) {
dma_periph = DMA0;
} else {
dma_periph = DMA1;
}
channel = gd32_dma_channel_get(dma_chan_base, dma_periph);
gd32_dma_chbase_parse(dma_chan_base, &dma_periph, &channel);
status = (DMA_CHCTL(dma_periph, channel) & DMA_CHXCTL_CHEN);
@ -175,13 +163,13 @@ void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callbac
void gd32_dma_chbase_parse(uint32_t dma_chan_base, uint32_t *dma_periph, int *dma_channel)
{
if(DMA1 > dma_chan_base) {
if (DMA1 > dma_chan_base) {
*dma_periph = DMA0;
} else {
*dma_periph = DMA1;
}
*dma_channel = (int)(dma_chan_base - (*dma_periph) - 0x10)/0x18;
*dma_channel = gd32_dma_channel_get(dma_chan_base, *dma_periph);
}
void gd32_dma_init(uint32_t dma_chan_base, dma_single_data_parameter_struct *init_struct)
@ -262,14 +250,12 @@ void gd32_dma_transnum_config(uint32_t dma_chan_base, uint32_t number)
uint16_t gd32_dma_transnum_get(uint32_t dma_chan_base)
{
uint32_t dma_periph ;
uint16_t number;
uint32_t dma_periph;
int channel;
gd32_dma_chbase_parse(dma_chan_base, &dma_periph, &channel);
number = (uint16_t)dma_transfer_number_get(dma_periph, channel);
return number;
return (uint16_t)dma_transfer_number_get(dma_periph, channel);
}
FlagStatus gd32_dma_flag_get(uint32_t dma_chan_base, uint32_t flag)

View file

@ -287,7 +287,9 @@ FAST_IRQ_HANDLER void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor)
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, DISABLE);
if (DMA_GET_FLAG_STATUS(descriptor, DMA_INT_FLAG_TAE)) {
while (1) {};
DMA_CLEAR_FLAG(descriptor, DMA_INT_FLAG_TAE); // Clear Transfer Error flag
bbDMA_Cmd(bbPort, DISABLE);
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, DISABLE);
}
DMA_CLEAR_FLAG(descriptor, DMA_INT_FLAG_FTF);

View file

@ -97,6 +97,7 @@ extern void gd32_dma_int_config(uint32_t dma_chan_base, uint32_t source, Control
extern void gd32_dma_transnum_config(uint32_t dma_chan_base, uint32_t number);
extern uint16_t gd32_dma_transnum_get(uint32_t dma_chan_base);
extern FlagStatus gd32_dma_flag_get(uint32_t dma_chan_base, uint32_t flag);
extern void gd32_dma_flag_clear(uint32_t dma_chan_base, uint32_t flag);
extern void gd32_dma_chbase_parse(uint32_t dma_chan_base, uint32_t *dma_periph, int *dma_channel);
extern void gd32_dma_memory_addr_config(uint32_t dma_chan_base, uint32_t address, uint8_t memory_flag);

View file

@ -92,31 +92,31 @@ typedef struct
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define I2C_TypeDef void
#define I2C_HandleTypeDef void
#define GPIO_TypeDef void
#define GPIO_InitTypeDef void
#define TIM_TypeDef void
#define DMA_TypeDef void
#define DMA_Stream_TypeDef void
typedef struct I2C_TypeDef I2C_TypeDef;
typedef struct I2C_HandleTypeDef I2C_HandleTypeDef;
typedef struct GPIO_TypeDef GPIO_TypeDef;
typedef struct GPIO_InitTypeDef GPIO_InitTypeDef;
typedef struct TIM_TypeDef TIM_TypeDef;
typedef struct DMA_TypeDef DMA_TypeDef;
typedef struct DMA_Stream_TypeDef DMA_Stream_TypeDef;
typedef struct DMA_Channel_TypeDef DMA_Channel_TypeDef;
typedef struct SPI_TypeDef SPI_TypeDef;
typedef struct ADC_TypeDef ADC_TypeDef;
typedef struct USART_TypeDef USART_TypeDef;
typedef struct TIM_Cmd TIM_Cmd;
typedef struct TIM_CtrlPWMOutputs TIM_CtrlPWMOutputs;
typedef struct TIM_TimeBaseInit TIM_TimeBaseInit;
typedef struct TIM_ARRPreloadConfig TIM_ARRPreloadConfig;
typedef struct EXTI_TypeDef EXTI_TypeDef;
typedef struct EXTI_InitTypeDef EXTI_InitTypeDef;
#define DMA_InitTypeDef dma_general_config_struct
#define DMA_Channel_TypeDef void
#define SPI_TypeDef void
#define ADC_TypeDef void
#define USART_TypeDef void
#define TIM_OCInitTypeDef timer_oc_parameter_struct
#define TIM_ICInitTypeDef timer_ic_parameter_struct
#define TIM_OCStructInit timer_channel_output_struct_para_init
#define TIM_Cmd void
#define TIM_CtrlPWMOutputs void
#define TIM_TimeBaseInit void
#define TIM_TimeBaseInitTypeDef timer_parameter_struct
#define TIM_ARRPreloadConfig void
#define EXTI_TypeDef void
#define EXTI_InitTypeDef void
#define USART_TypeDef void
#define TIM_ICPolarity_Falling TIMER_IC_POLARITY_FALLING
#define TIM_ICPolarity_Rising TIMER_IC_POLARITY_RISING
#define Bit_RESET 0
@ -139,6 +139,7 @@ typedef struct
extern void timerOCModeConfig(void *tim, uint8_t channel, uint16_t ocmode);
extern void gd32_timer_input_capture_config(void* timer, uint16_t channel, uint8_t state);
extern uint32_t timerPrescaler(const TIM_TypeDef *tim);
#define UART_TX_BUFFER_ATTRIBUTE /* EMPTY */
#define UART_RX_BUFFER_ATTRIBUTE /* EMPTY */
@ -193,7 +194,7 @@ extern void gd32_timer_input_capture_config(void* timer, uint16_t channel, uint8
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT, 0, GPIO_OTYPE_PP, GPIO_PUPD_NONE) // TODO
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT, 0, GPIO_OTYPE_PP, GPIO_PUPD_NONE)
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT, 0, GPIO_OTYPE_PP, GPIO_PUPD_PULLUP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_OSPEED_25MHZ, GPIO_OTYPE_PP, GPIO_PUPD_NONE)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT, 0, GPIO_OTYPE_OD, GPIO_PUPD_NONE)
@ -258,3 +259,19 @@ extern void gd32_timer_input_capture_config(void* timer, uint16_t channel, uint8
#define SERIAL_TRAIT_PIN_CONFIG 1
#define USB_DP_PIN PA12
// Select UART prefix according to UART_DEV
#define _UART_GET_PREFIX(dev) _UART_GET_PREFIX_##dev
#define _UART_GET_PREFIX_UARTDEV_0 USART
#define _UART_GET_PREFIX_UARTDEV_1 USART
#define _UART_GET_PREFIX_UARTDEV_2 USART
#define _UART_GET_PREFIX_UARTDEV_3 UART
#define _UART_GET_PREFIX_UARTDEV_4 UART
#define _UART_GET_PREFIX_UARTDEV_5 USART
#define _UART_GET_PREFIX_UARTDEV_6 UART
#define _UART_GET_PREFIX_UARTDEV_7 UART
#define _UART_GET_PREFIX_UARTDEV_8 UART
#define _UART_GET_PREFIX_UARTDEV_9 UART
#define _UART_GET_PREFIX_UARTDEV_10 USART
#define _UART_GET_PREFIX_UARTDEV_LP1 LPUART

View file

@ -303,8 +303,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
const IO_t motorIO = IOGetByTag(timerHardware->tag);
uint8_t pupMode = 0;
pupMode = (output & TIMER_OUTPUT_INVERTED) ? GPIO_PUPD_PULLDOWN : GPIO_PUPD_PULLUP;
uint8_t pupMode = (output & TIMER_OUTPUT_INVERTED) ? GPIO_PUPD_PULLDOWN : GPIO_PUPD_PULLUP;
#ifdef USE_DSHOT_TELEMETRY
if (useDshotTelemetry) {
@ -356,7 +355,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
motor->icInitStruct.icpolarity = TIMER_IC_POLARITY_BOTH_EDGE;
motor->icInitStruct.icprescaler = TIMER_IC_PSC_DIV1;
motor->icInitStruct.icfilter = 2;
timer_input_capture_config((uint32_t)timer, timerHardware->channel, &motor->icInitStruct); // ic结构体中没有channel
timer_input_capture_config((uint32_t)timer, timerHardware->channel, &motor->icInitStruct);
#endif
#ifdef USE_DSHOT_DMAR

View file

@ -22,97 +22,24 @@
#include "platform.h"
#include "platform/rcc.h"
static void rcu_ahb1_periph_clk_config(uint32_t mask, FunctionalState NewState)
void rcu_periph_clk_config(volatile uint32_t *reg, uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB1EN |= mask;
*reg |= mask;
} else {
RCU_AHB1EN &= ~mask;
*reg &= ~mask;
}
}
static void rcu_ahb2_periph_clk_config(uint32_t mask, FunctionalState NewState)
static void rcu_periph_rst_config(volatile uint32_t *reg, uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB2EN |= mask;
*reg |= mask;
} else {
RCU_AHB2EN &= ~mask;
*reg &= ~mask;
}
}
static void rcu_ahb3_periph_clk_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB3EN |= mask;
} else {
RCU_AHB3EN &= ~mask;
}
}
static void rcu_apb1_periph_clk_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_APB1EN |= mask;
} else {
RCU_APB1EN &= ~mask;
}
}
static void rcu_apb2_periph_clk_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_APB2EN |= mask;
} else {
RCU_APB2EN &= ~mask;
}
}
static void rcu_ahb1_periph_rst_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB1RST |= mask;
} else {
RCU_AHB1RST &= ~mask;
}
}
static void rcu_ahb2_periph_rst_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB2RST |= mask;
} else {
RCU_AHB2RST &= ~mask;
}
}
static void rcu_ahb3_periph_rst_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_AHB3RST |= mask;
} else {
RCU_AHB3RST &= ~mask;
}
}
static void rcu_apb1_periph_rst_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_APB1RST |= mask;
} else {
RCU_APB1RST &= ~mask;
}
}
static void rcu_apb2_periph_rst_config(uint32_t mask, FunctionalState NewState)
{
if (NewState == ENABLE) {
RCU_APB2RST |= mask;
} else {
RCU_APB2RST &= ~mask;
}
}
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
{
int tag = periphTag >> 5;
@ -120,19 +47,19 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
switch (tag) {
case RCC_AHB1:
rcu_ahb1_periph_clk_config(mask, NewState);
rcu_periph_clk_config(&RCU_AHB1EN, mask, NewState);
break;
case RCC_AHB2:
rcu_ahb2_periph_clk_config(mask, NewState);
rcu_periph_clk_config(&RCU_AHB2EN, mask, NewState);
break;
case RCC_AHB3:
rcu_ahb3_periph_clk_config(mask, NewState);
rcu_periph_clk_config(&RCU_AHB3EN, mask, NewState);
break;
case RCC_APB1:
rcu_apb1_periph_clk_config(mask, NewState);
rcu_periph_clk_config(&RCU_APB1EN, mask, NewState);
break;
case RCC_APB2:
rcu_apb2_periph_clk_config(mask, NewState);
rcu_periph_clk_config(&RCU_APB2EN, mask, NewState);
break;
}
}
@ -144,19 +71,19 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
switch (tag) {
case RCC_AHB1:
rcu_ahb1_periph_rst_config(mask, NewState);
rcu_periph_rst_config(&RCU_AHB1RST, mask, NewState);
break;
case RCC_AHB2:
rcu_ahb2_periph_rst_config(mask, NewState);
rcu_periph_rst_config(&RCU_AHB2RST, mask, NewState);
break;
case RCC_AHB3:
rcu_ahb3_periph_rst_config(mask, NewState);
rcu_periph_rst_config(&RCU_AHB3RST, mask, NewState);
break;
case RCC_APB1:
rcu_apb1_periph_rst_config(mask, NewState);
rcu_periph_rst_config(&RCU_APB1RST, mask, NewState);
break;
case RCC_APB2:
rcu_apb2_periph_rst_config(mask, NewState);
rcu_periph_rst_config(&RCU_APB2RST, mask, NewState);
break;
}
}

View file

@ -42,27 +42,6 @@
#include "build/debug.h"
#define DMA_INTF0_TAEIF3 ((uint32_t)0x02000000)
#define DMA_INTC0_TAEIFC3 ((uint32_t)0x02000000)
#define DMA_INTF0_FEEIF3 ((uint32_t)0x00400000)
#define DMA_INTC0_FEEIFC3 ((uint32_t)0x00400000)
#define DMA_INTF0_DMEIF3 ((uint32_t)0x01000000)
#define DMA_INTC0_CDMEIF3 ((uint32_t)0x01000000)
#define DMA_INTF0_HTIF3 ((uint32_t)0x04000000)
#define DMA_INTC0_CHTIF3 ((uint32_t)0x04000000)
#define DMA_INTF0_TCIF3 ((uint32_t)0x08000000)
#define DMA_INTC0_CTCIF3 ((uint32_t)0x08000000)
#define DMA_HISR_TEIF6 ((uint32_t)0x00080000)
#define DMA_HIFCR_CTEIF6 ((uint32_t)0x00080000)
#define DMA_HISR_FEIF6 ((uint32_t)0x00010000)
#define DMA_HIFCR_CFEIF6 ((uint32_t)0x00010000)
#define DMA_HISR_DMEIF6 ((uint32_t)0x00040000)
#define DMA_HIFCR_CDMEIF6 ((uint32_t)0x00040000)
#define DMA_HIFCR_CHTIF6 ((uint32_t)0x00100000)
#define DMA_HISR_HTIF6 ((uint32_t)0x00100000)
#define DMA_HISR_TCIF6 ((uint32_t)0x00200000)
#define DMA_HIFCR_CTCIF6 ((uint32_t)0x00200000)
#define DMA_CHANNEL_4 ((uint32_t)0x08000000)
#define DMA_MINC_ENABLE ((uint32_t)DMA_CHXCTL_MNAGA)
#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_MEMORY_WIDTH_32BIT)
@ -184,6 +163,8 @@
#define SD_CMD_APP_CMD ((uint8_t)55) // Indicates to the card that the next command is an application specific command rather
// than a standard command.
#define SD_NO_RESPONSE ((int8_t)-1)
/* Following commands are SD Card Specific commands.
SDIO_APP_CMD should be sent before sending these commands. */
#define SD_CMD_APP_SD_SET_BUSWIDTH ((uint8_t)6) // (ACMD6) Defines the data bus width to be used for data transfer. The allowed data bus
@ -233,9 +214,9 @@ static uint32_t SD_Status;
static uint32_t SD_CardRCA;
SD_CardType_t SD_CardType;
static volatile uint32_t TimeOut;
DMA_Stream_TypeDef *dmaStream;
uint32_t dma_periph_sdio;
int dma_channel_sdio;
static DMA_Stream_TypeDef *dmaStream;
static uint32_t dma_periph_sdio;
static int dma_channel_sdio;
static void SD_DataTransferInit (uint32_t Size, uint32_t DataBlockSize, bool IsItReadFromCard);
@ -285,14 +266,14 @@ static SD_Error_t SD_TransmitCommand(uint32_t Command, uint32_t Argument, int8_t
{
SD_Error_t ErrorState;
SDIO_INTC = SDIO_INTC_STATIC_FLAGS; // Clear the Command Flags
SDIO_INTC = SDIO_INTC_STATIC_FLAGS; // Clear the Command Flags
/* disable the CSM */
SDIO_CMDCTL &= ~SDIO_CMDCTL_CSMEN;
SDIO_CMDAGMT = (uint32_t)Argument; // Set the SDIO Argument value
SDIO_CMDCTL = (uint32_t)(Command | SDIO_CMDCTL_CSMEN); // Set SDIO command parameters
if((Argument == 0) && (ResponseType == 0)) ResponseType = -1; // Go idle command
SDIO_CMDAGMT = (uint32_t)Argument; // Set the SDIO Argument value
SDIO_CMDCTL = (uint32_t)(Command | SDIO_CMDCTL_CSMEN); // Set SDIO command parameters
if((Argument == 0) && (ResponseType == 0)) ResponseType = SD_NO_RESPONSE; // Go idle command
ErrorState = SD_CmdResponse(Command & SDIO_CMDCTL_CMDIDX, ResponseType);
SDIO_INTC = SDIO_INTC_STATIC_FLAGS; // Clear the Command Flags
SDIO_INTC = SDIO_INTC_STATIC_FLAGS; // Clear the Command Flags
return ErrorState;
}
@ -310,7 +291,7 @@ static SD_Error_t SD_CmdResponse(uint8_t SD_CMD, int8_t ResponseType)
uint32_t TimeOut;
uint32_t Flag;
if(ResponseType == -1) {
if(ResponseType == SD_NO_RESPONSE) {
Flag = SDIO_STAT_CMDSEND;
} else {
Flag = SDIO_STAT_CCRCERR | SDIO_STAT_CMDRECV | SDIO_STAT_CMDTMOUT;
@ -538,11 +519,11 @@ static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32
DMA_CHCTL(dma_periph_sdio,dma_channel_sdio) |= DMA_MEMORY_TO_PERIPH; // Sets memory to peripheral
}
if ((uint32_t)dmaStream == DMA1_CH3_BASE) {
DMA_INTC0(dma_periph_sdio) = DMA_INTC0_TAEIFC3 | DMA_INTC0_CDMEIF3 |
DMA_INTC0_FEEIFC3 | DMA_INTC0_CHTIF3 | DMA_INTC0_CTCIF3; // Clear the transfer error flag
// clear dma flags
dma_flag_clear(DMA1, DMA1_CH3, DMA_FLAG_FEE | DMA_FLAG_SDE | DMA_FLAG_TAE | DMA_FLAG_HTF | DMA_FLAG_FTF);
} else {
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CTEIF6 | DMA_HIFCR_CDMEIF6 |
DMA_HIFCR_CFEIF6 | DMA_HIFCR_CHTIF6 | DMA_HIFCR_CTCIF6; // Clear the transfer error flag
// clear dma flags
dma_flag_clear(DMA1, DMA1_CH6, DMA_FLAG_FEE | DMA_FLAG_SDE | DMA_FLAG_TAE | DMA_FLAG_HTF | DMA_FLAG_FTF); // Clear the transfer error flag
}
DMA_CHCTL(dma_periph_sdio,dma_channel_sdio) |= DMA_CHXCTL_FTFIE | DMA_CHXCTL_HTFIE | DMA_CHXCTL_TAEIE | DMA_CHXCTL_SDEIE; // Enable all interrupts
DMA_CHFCTL(dma_periph_sdio,dma_channel_sdio) |= DMA_CHXFCTL_FEEIE;
@ -1484,55 +1465,55 @@ void SDIO_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma)
{
UNUSED(dma);
// Transfer Error Interrupt management
if((DMA_INTF0(DMA1) & DMA_INTF0_TAEIF3) != 0) {
if((DMA_INTF0(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_TAE, DMA_CH3)) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_TAEIE) != 0) {
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_TAEIE; // Disable the transfer error interrupt
DMA_INTC0(DMA1) = DMA_INTC0_TAEIFC3; // Clear the transfer error flag
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_TAEIE; // Disable the transfer error interrupt
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_TAE, DMA_CH3); // Clear the transfer error flag
}
}
// FIFO Error Interrupt management
if((DMA_INTF0(DMA1) & DMA_INTF0_FEEIF3) != 0) {
if((DMA_INTF0(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_FEE, DMA_CH3)) != 0) {
if((DMA_CHFCTL(DMA1, DMA_CH3) & DMA_CHXFCTL_FEEIE) != 0) {
DMA_CHFCTL(DMA1, DMA_CH3) &= ~DMA_CHXFCTL_FEEIE; // Disable the FIFO Error interrupt
DMA_INTC0(DMA1) = DMA_INTC0_FEEIFC3; // Clear the FIFO error flag
DMA_CHFCTL(DMA1, DMA_CH3) &= ~DMA_CHXFCTL_FEEIE; // Disable the FIFO Error interrupt
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_FEE, DMA_CH3); // Clear the FIFO error flag
}
}
// Direct Mode Error Interrupt management
if((DMA_INTF0(DMA1) & DMA_INTF0_DMEIF3) != 0) {
// Single data mode exception flag
if((DMA_INTF0(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_SDE, DMA_CH3)) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_SDEIE) != 0) {
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_SDEIE; // Disable the direct mode Error interrupt
DMA_INTC0(DMA1) = DMA_INTC0_CDMEIF3; // Clear the FIFO error flag
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_SDEIE; // Disable the single data mode Error interrupt
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_SDE, DMA_CH3);
}
}
// Half Transfer Complete Interrupt management
if((DMA_INTF0(DMA1) & DMA_INTF0_HTIF3) != 0) {
if((DMA_INTF0(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_HTF, DMA_CH3)) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_HTFIE) != 0) {
if(((DMA_CHCTL(DMA1, DMA_CH3)) & (uint32_t)(DMA_CHXCTL_SBMEN)) != 0) {
DMA_INTC0(DMA1) = DMA_INTC0_CHTIF3;
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_HTF, DMA_CH3);
} else {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_CMEN) == 0) {
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_HTFIE;
}
DMA_INTC0(DMA1) = DMA_INTC0_CHTIF3;
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_HTF, DMA_CH3);
}
}
}
// Transfer Complete Interrupt management
if((DMA_INTF0(DMA1) & DMA_INTF0_TCIF3) != 0) {
if((DMA_INTF0(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_FTF, DMA_CH3)) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_FTFIE) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH3) & (uint32_t)(DMA_CHXCTL_SBMEN)) != 0) {
DMA_INTC0(DMA1) = DMA_INTC0_CTCIF3;
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_FTF, DMA_CH3);
} else {
if((DMA_CHCTL(DMA1, DMA_CH3) & DMA_CHXCTL_CMEN) == 0) {
DMA_CHCTL(DMA1, DMA_CH3) &= ~DMA_CHXCTL_FTFIE;
}
DMA_INTC0(DMA1) = DMA_INTC0_CTCIF3;
DMA_INTC0(DMA1) = DMA_FLAG_ADD(DMA_INT_FLAG_FTF, DMA_CH3);
SD_DMA_Complete(DMA1, DMA_CH3);
}
}
@ -1548,56 +1529,59 @@ void SDIO_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma)
void SDIO_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
{
UNUSED(dma);
dma_channel_enum channel_flag_offset = channelx;
// Transfer Error Interrupt management
if((DMA_INTF1(DMA1) & DMA_HISR_TEIF6) != 0) {
if((DMA_INTF1(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_TAE, (DMA_CH6-DMA_CH4))) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_TAEIE) != 0) {
DMA_CHCTL(DMA1, DMA_CH6) &= ~DMA_CHXCTL_TAEIE;
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CTEIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_TAE, (DMA_CH6-DMA_CH4));
}
}
// FIFO Error Interrupt management
if((DMA_INTF1(DMA1) & DMA_HISR_FEIF6) != 0) {
if((DMA_INTF1(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_FEE, (DMA_CH6-DMA_CH4))) != 0) {
if((DMA_CHFCTL(DMA1, DMA_CH6) & DMA_CHXFCTL_FEEIE) != 0) {
DMA_CHFCTL(DMA1, DMA_CH6) &= ~DMA_CHXFCTL_FEEIE;
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CFEIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_FEE, (DMA_CH6-DMA_CH4));
}
}
// Direct Mode Error Interrupt management
if((DMA_INTF1(DMA1) & DMA_HISR_DMEIF6) != 0) {
// Single data mode exception flag
if((DMA_INTF1(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_SDE, (DMA_CH6-DMA_CH4))) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_SDEIE) != 0) {
DMA_CHCTL(DMA1, DMA_CH6) &= ~DMA_CHXCTL_SDEIE;
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CDMEIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_SDE, (DMA_CH6-DMA_CH4));
}
}
// Half Transfer Complete Interrupt management
if((DMA_INTF1(DMA1) & DMA_HISR_HTIF6) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_HTFIE) != 0) {
if((DMA_INTF1(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_HTF, (DMA_CH6-DMA_CH4))) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6) & DMA_CHXCTL_HTFIE) != 0) {
if(((DMA_CHCTL(DMA1, DMA_CH6)) & (uint32_t)(DMA_CHXCTL_SBMEN)) != 0) {
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CHTIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_HTF, (DMA_CH6-DMA_CH4));
} else {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_CMEN) == 0) {
DMA_CHCTL(DMA1, DMA_CH6)&= ~DMA_CHXCTL_HTFIE;
}
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CHTIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_HTF, (DMA_CH6-DMA_CH4));
}
}
}
// Transfer Complete Interrupt management
if((DMA_INTF1(DMA1) & DMA_HISR_TCIF6) != 0) {
if((DMA_INTF1(DMA1) & DMA_FLAG_ADD(DMA_INT_FLAG_FTF, (DMA_CH6-DMA_CH4))) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_FTFIE) != 0) {
if((DMA_CHCTL(DMA1, DMA_CH6)& (uint32_t)(DMA_CHXCTL_SBMEN)) != 0) {
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CTCIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_FTF, (DMA_CH6-DMA_CH4));
} else {
if((DMA_CHCTL(DMA1, DMA_CH6)& DMA_CHXCTL_CMEN) == 0) {
DMA_CHCTL(DMA1, DMA_CH6) &= ~DMA_CHXCTL_FTFIE;
}
DMA_INTC1(dma_periph_sdio) = DMA_HIFCR_CTCIF6;
DMA_INTC1(dma_periph_sdio) = DMA_FLAG_ADD(DMA_INT_FLAG_FTF, (DMA_CH6-DMA_CH4));
SD_DMA_Complete(DMA1, DMA_CH6);
}
}

View file

@ -46,7 +46,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART0
{
.identifier = SERIAL_PORT_UART0,
.reg = (void *)USART0,
.reg = (USART_TypeDef *)USART0,
.rxDMAChannel = DMA_SUBPERI4,
.txDMAChannel = DMA_SUBPERI4,
#ifdef USE_UART0_RX_DMA
@ -72,7 +72,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.identifier = SERIAL_PORT_USART1,
.reg = (void *)USART1,
.reg = (USART_TypeDef *)USART1,
.rxDMAChannel = DMA_SUBPERI4,
.txDMAChannel = DMA_SUBPERI4,
#ifdef USE_UART1_RX_DMA
@ -98,7 +98,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART2
{
.identifier = SERIAL_PORT_USART2,
.reg = (void *)USART2,
.reg = (USART_TypeDef *)USART2,
.rxDMAChannel = DMA_SUBPERI4,
.txDMAChannel = DMA_SUBPERI4,
#ifdef USE_UART2_RX_DMA
@ -124,7 +124,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART3
{
.identifier = SERIAL_PORT_UART3,
.reg = (void *)UART3,
.reg = (USART_TypeDef *)UART3,
.rxDMAChannel = DMA_SUBPERI4,
.txDMAChannel = DMA_SUBPERI4,
#ifdef USE_UART3_RX_DMA
@ -150,7 +150,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART4
{
.identifier = SERIAL_PORT_UART4,
.reg = (void *)UART4,
.reg = (USART_TypeDef *)UART4,
.rxDMAChannel = DMA_SUBPERI4,
.txDMAChannel = DMA_SUBPERI4,
#ifdef USE_UART4_RX_DMA
@ -176,7 +176,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART5
{
.identifier = SERIAL_PORT_UART5,
.reg = (void *)USART5,
.reg = (USART_TypeDef *)USART5,
.rxDMAChannel = DMA_SUBPERI5,
.txDMAChannel = DMA_SUBPERI5,
#ifdef USE_UART5_RX_DMA

View file

@ -77,8 +77,6 @@ void uartReconfigure(uartPort_t *uartPort)
usart_halfduplex_disable((uint32_t)uartPort->USARTx);
}
usart_enable((uint32_t)uartPort->USARTx);
if (uartPort->port.mode & MODE_RX) {
#ifdef USE_DMA
if (uartPort->rxDMAResource) {

View file

@ -68,7 +68,7 @@ static void usbVcpSetMode(serialPort_t *instance, portMode_e mode)
static void usbVcpSetCtrlLineStateCb(serialPort_t *instance, void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
UNUSED(instance); UNUSED((void (*)(void *context, uint16_t ctrlLineState))cb);UNUSED(context);
UNUSED(instance);
// Register upper driver control line state callback routine with USB driver
CDC_SetCtrlLineStateCb((void (*)(void *context, uint16_t ctrlLineState))cb, context);
@ -76,7 +76,7 @@ static void usbVcpSetCtrlLineStateCb(serialPort_t *instance, void (*cb)(void *co
static void usbVcpSetBaudRateCb(serialPort_t *instance, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context)
{
UNUSED(instance); UNUSED((void (*)(void *context, uint32_t baud))cb); UNUSED(context);
UNUSED(instance);
// Register upper driver baud rate callback routine with USB driver
CDC_SetBaudRateCb((void (*)(void *context, uint32_t baud))cb, (void *)context);

View file

@ -1,7 +1,7 @@
.syntax unified
.cpu cortex-m4
.fpu softvfp
.fpu fpv4-sp-d16
.thumb
.global Default_Handler

View file

@ -648,8 +648,6 @@ static void system_clock_168m_irc16m(void)
while(0U == (PMU_CS & PMU_CS_HDSRF)){
}
FMC_WS = 0x00000705;
reg_temp = RCU_CFG0;
/* select PLL as system clock */
reg_temp &= ~RCU_CFG0_SCS;

View file

@ -103,7 +103,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
rcu_periph_clock_enable(RCU_SPI1);
rcu_periph_clock_enable(RCU_SPI2);
rcu_periph_clock_enable(RCU_USART1);
rcu_periph_clock_enable(RCU_USART1);
rcu_periph_clock_enable(RCU_USART2);
rcu_periph_clock_enable(RCU_UART3);
rcu_periph_clock_enable(RCU_UART4);
rcu_periph_clock_enable(RCU_I2C0);

View file

@ -40,12 +40,6 @@
#define I2C1_CLOCKSPEED 400
#define I2C2_CLOCKSPEED 400
#if defined(USE_I2C_PULLUP)
#define I2C0_PULLUP true
#else
#define I2C0_PULLUP false
#endif
#define USE_VCP
#define USE_SOFTSERIAL
@ -109,8 +103,6 @@
#define ADC_INSTANCE ADC0
#endif
#define USE_SPI_DEVICE_0
#define USE_EXTI
#define USE_PID_DENOM_CHECK

View file

@ -165,6 +165,12 @@ uint32_t timerClock(const TIM_TypeDef *tim)
}
}
uint32_t timerPrescaler(const TIM_TypeDef *tim)
{
uint32_t timer = (uint32_t)tim;
return TIMER_PSC(timer) + 1;
}
void gd32_timer_input_capture_config(void* timer, uint16_t channel, uint8_t state)
{
switch(channel) {

View file

@ -101,6 +101,9 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
RCC_ClockCmd(timerRCC(timer), ENABLE);
if (transponder->timer_hz == 0 || transponder->timer_carrier_hz == 0) {
return;
}
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, transponder->timer_hz);
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, transponder->timer_carrier_hz);

View file

@ -128,7 +128,7 @@ void USBFS_WKUP_IRQHandler(void)
*/
void USBHS_WKUP_IRQHandler(void)
{
if(cdc_acm.bp.low_power) {
if(USB_OTG_dev.bp.low_power) {
resume_mcu_clk();
#ifdef USE_EMBEDDED_PHY

View file

@ -208,7 +208,8 @@ void usb_udelay(const uint32_t usec)
{
uint32_t count = 0;
const uint32_t utime = (120 * usec / 7);
const uint32_t ticks_per_us = SystemCoreClock / 1000000U;
const uint32_t utime = (ticks_per_us * usec / 7);
do {
if ( ++count > utime )
{

View file

@ -1,5 +1,5 @@
/*!
\file cdc_hid_wrapper.c
\file usb_cdc_hid.c
\brief this file calls to the separate CDC and HID class layer handlers
\version 2018-06-01, V1.0.0, application for GD32 USBD

View file

@ -1,5 +1,5 @@
/*!
\file cdc_hid_wrapper.h
\file usb_cdc_hid.h
\brief the header file of cdc hid wrapper driver
\version 2018-06-01, V1.0.0, application for GD32 USBD
@ -34,8 +34,8 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
OF SUCH DAMAGE.
*/
#ifndef __USB_HID_CORE_H_
#define __USB_HID_CORE_H_
#ifndef USB_CDC_HID_H
#define USB_CDC_HID_H
#include "usbd_desc.h"
#include "standard_hid_core.h"
@ -80,4 +80,4 @@ typedef struct
extern usb_desc bf_cdc_hid_desc;
extern usb_class_core bf_usbd_cdc_hid_cb;
#endif /* __CDC_HID_WRAPPER_H */
#endif /* USB_CDC_HID_H */

View file

@ -36,6 +36,9 @@ OF SUCH DAMAGE.
#include "platform.h"
#include "build/version.h"
#include "build/atomic.h"
#include "drivers/nvic.h"
#include "pg/pg.h"
#include "pg/usb.h"
@ -45,7 +48,7 @@ OF SUCH DAMAGE.
volatile uint32_t APP_Rx_ptr_in = 0;
volatile uint32_t APP_Rx_ptr_out = 0;
uint32_t APP_Rx_length = 0;
volatile uint32_t APP_Rx_length = 0;
uint8_t USB_Tx_State = USB_CDC_IDLE;
__ALIGN_BEGIN uint8_t USB_Rx_Buffer [USB_CDC_DATA_PACKET_SIZE] __ALIGN_END ;
@ -525,8 +528,10 @@ static uint8_t bf_cdc_acm_in(usb_dev *udev, uint8_t ep_num)
usbd_ep_send(udev, CDC_DATA_IN_EP, (uint8_t*)&APP_Rx_Buffer[APP_Rx_ptr_out], USB_Tx_length);
// Advance the out pointer
APP_Rx_ptr_out = (APP_Rx_ptr_out + USB_Tx_length) % APP_RX_DATA_SIZE;
APP_Rx_length -= USB_Tx_length;
ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) {
APP_Rx_ptr_out = (APP_Rx_ptr_out + USB_Tx_length) % APP_RX_DATA_SIZE;
APP_Rx_length -= USB_Tx_length;
}
return USBD_OK;
}

View file

@ -31,8 +31,8 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef __USBD_DESC_H
#define __USBD_DESC_H
#ifndef USBD_DESC_H
#define USBD_DESC_H
#include "usbd_enum.h"
#include "usb_cdc.h"
@ -50,7 +50,7 @@ extern usb_desc bf_cdc_desc;
extern usb_class_core bf_cdc_class;
extern volatile uint32_t APP_Rx_ptr_in;
extern volatile uint32_t APP_Rx_ptr_out;
extern uint32_t APP_Rx_length;
extern volatile uint32_t APP_Rx_length;
/* function declarations */
/* check CDC ACM is ready for data transfer */
@ -60,4 +60,4 @@ void bf_cdc_acm_data_send(usb_dev *udev);
/* receive CDC ACM data */
void bf_cdc_acm_data_receive(usb_dev *udev);
#endif /* __USBD_DESC_H */
#endif /* USBD_DESC_H */

View file

@ -1,6 +1,6 @@
/*!
\file usbd_msc_core.c
\brief USB MSC device class core functions
\file usbd_msc_desc.c
\brief USB MSC device class descriptor functions
\version 2024-12-20, V3.3.1, firmware for GD32F4xx
*/
@ -223,7 +223,7 @@ static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = {
};
/* USB product string */
static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = {
static __ALIGN_BEGIN usb_desc_str product_string __ALIGN_END = {
.header =
{
.bLength = USB_STRING_LEN(34U),
@ -266,6 +266,7 @@ usb_desc bf_msc_desc = {
};
static __ALIGN_BEGIN uint8_t usbd_msc_maxlun __ALIGN_END = 0U ;
static __ALIGN_BEGIN usbd_msc_handler msc_handler __ALIGN_END;
/*!
\brief usbd string get
@ -312,8 +313,6 @@ void usbd_msc_desc_string_update(void)
static uint8_t bf_msc_core_init(usb_dev *udev, uint8_t config_index)
{
(void)(config_index);
static __ALIGN_BEGIN usbd_msc_handler msc_handler __ALIGN_END;
memset((void *)&msc_handler, 0U, sizeof(usbd_msc_handler));

View file

@ -1,6 +1,6 @@
/*!
\file usbd_msc_core.h
\brief the header file of USB MSC device class core functions
\file usbd_msc_desc.h
\brief the header file of USB MSC device class descriptor functions
\version 2024-12-20, V3.3.1, firmware for GD32F4xx
*/
@ -32,8 +32,8 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
OF SUCH DAMAGE.
*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
#ifndef USB_MSC_DESC_H
#define USB_MSC_DESC_H
#include "usbd_msc_core.h"
@ -45,5 +45,5 @@ OF SUCH DAMAGE.
extern usb_desc bf_msc_desc;
extern usb_class_core bf_msc_class;
#endif /* __USBD_DESC_H */
#endif /* USB_MSC_DESC_H */

View file

@ -19,8 +19,8 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __USBD_CDC_VCP_H
#define __USBD_CDC_VCP_H
#ifndef USBD_CDC_VCP_H
#define USBD_CDC_VCP_H
#include "gd32f4xx.h"
@ -78,4 +78,4 @@ typedef struct _CDC_IF_PROP
}
CDC_IF_Prop_TypeDef;
#endif /* __USBD_CDC_VCP_H */
#endif /* USBD_CDC_VCP_H */