mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Rename HAL dshot file and cleanup
This commit is contained in:
parent
a50192f71c
commit
5214f4bdec
2 changed files with 16 additions and 44 deletions
2
Makefile
2
Makefile
|
@ -985,7 +985,7 @@ STM32F7xx_COMMON_SRC = \
|
|||
drivers/gpio_stm32f7xx.c \
|
||||
drivers/light_ws2811strip_hal.c \
|
||||
drivers/bus_spi_hal.c \
|
||||
drivers/pwm_output_stm32f7xx.c \
|
||||
drivers/pwm_output_dshot_hal.c \
|
||||
drivers/timer_hal.c \
|
||||
drivers/timer_stm32f7xx.c \
|
||||
drivers/system_stm32f7xx.c \
|
||||
|
|
|
@ -81,18 +81,13 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
|
|||
packet <<= 1;
|
||||
}
|
||||
|
||||
if(motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
|
||||
{
|
||||
if(HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK)
|
||||
{
|
||||
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) {
|
||||
/* Starting PWM generation Error */
|
||||
return;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if(HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK)
|
||||
{
|
||||
} else {
|
||||
if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) {
|
||||
/* Starting PWM generation Error */
|
||||
return;
|
||||
}
|
||||
|
@ -102,15 +97,6 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
|
|||
void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
|
||||
{
|
||||
UNUSED(motorCount);
|
||||
|
||||
if (!pwmMotorsEnabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
|
||||
//TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||
//TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||
|
@ -119,16 +105,6 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
|||
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaSource]);
|
||||
}
|
||||
|
||||
/*static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||
DMA_Cmd(descriptor->stream, DISABLE);
|
||||
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}*/
|
||||
|
||||
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||
{
|
||||
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
|
||||
|
@ -147,14 +123,13 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||
|
||||
motor->TimHandle.Instance = timerHardware->tim;
|
||||
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;;
|
||||
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;
|
||||
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
||||
motor->TimHandle.Init.RepetitionCounter = 0;
|
||||
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
|
||||
{
|
||||
if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) {
|
||||
/* Initialization Error */
|
||||
return;
|
||||
}
|
||||
|
@ -177,8 +152,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
|
||||
/* Set hdma_tim instance */
|
||||
if(timerHardware->dmaRef == NULL)
|
||||
{
|
||||
if (timerHardware->dmaRef == NULL) {
|
||||
/* Initialization Error */
|
||||
return;
|
||||
}
|
||||
|
@ -191,8 +165,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||
|
||||
/* Initialize TIMx DMA handle */
|
||||
if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK)
|
||||
{
|
||||
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK) {
|
||||
/* Initialization Error */
|
||||
return;
|
||||
}
|
||||
|
@ -215,8 +188,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
|
||||
TIM_OCInitStructure.Pulse = 0;
|
||||
|
||||
if(HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK)
|
||||
{
|
||||
if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) {
|
||||
/* Configuration Error */
|
||||
return;
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue