F7 Dshot hack

This commit is contained in:
Sami Korhonen 2017-09-17 13:06:34 +03:00
parent b67dcdbeb2
commit fa6112e1b8
7 changed files with 260 additions and 111 deletions

View File

@ -69,7 +69,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_ll_rng.c \
stm32f7xx_ll_rtc.c \
stm32f7xx_ll_sdmmc.c \
stm32f7xx_ll_tim.c \
stm32f7xx_ll_usart.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))

View File

@ -36,16 +36,11 @@ bool ws2811Initialised = false;
static TIM_HandleTypeDef TimHandle;
static uint16_t timerChannel = 0;
static bool timerNChannel = false;
void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
{
HAL_DMA_IRQHandler(TimHandle.hdma[descriptor->userParam]);
if(timerNChannel) {
HAL_TIMEx_PWMN_Stop_DMA(&TimHandle,timerChannel);
} else {
HAL_TIM_PWM_Stop_DMA(&TimHandle,timerChannel);
}
TIM_DMACmd(&TimHandle, timerChannel, DISABLE);
ws2811LedDataTransferInProgress = 0;
}
@ -105,16 +100,16 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
/* Set hdma_tim instance */
hdma_tim.Instance = timerHardware->dmaRef;
uint16_t dmaSource = timerDmaSource(timerChannel);
uint16_t dmaIndex = timerDmaIndex(timerChannel);
/* Link hdma_tim to hdma[x] (channelx) */
__HAL_LINKDMA(&TimHandle, hdma[dmaSource], hdma_tim);
__HAL_LINKDMA(&TimHandle, hdma[dmaIndex], hdma_tim);
dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, dmaSource);
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, dmaIndex);
/* Initialize TIMx DMA handle */
if (HAL_DMA_Init(TimHandle.hdma[dmaSource]) != HAL_OK) {
if (HAL_DMA_Init(TimHandle.hdma[dmaIndex]) != HAL_OK) {
/* Initialization Error */
return;
}
@ -124,7 +119,6 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
/* PWM1 Mode configuration: Channel1 */
TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
timerNChannel = true;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH: TIM_OCPOLARITY_LOW;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
@ -141,7 +135,17 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
/* Configuration Error */
return;
}
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start(&TimHandle, timerChannel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
} else {
if (HAL_TIM_PWM_Start(&TimHandle, timerChannel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
}
ws2811Initialised = true;
}
@ -152,18 +156,14 @@ void ws2811LedStripDMAEnable(void)
return;
}
if (timerNChannel) {
if (HAL_TIMEx_PWMN_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
ws2811LedDataTransferInProgress = 0;
return;
}
} else {
if (HAL_TIM_PWM_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
ws2811LedDataTransferInProgress = 0;
return;
}
if (DMA_SetCurrDataCounter(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK) {
/* DMA set error */
ws2811LedDataTransferInProgress = 0;
return;
}
/* Reset timer counter */
__HAL_TIM_SET_COUNTER(&TimHandle,0);
/* Enable channel DMA requests */
TIM_DMACmd(&TimHandle,timerChannel,ENABLE);
}
#endif

View File

@ -125,6 +125,7 @@ typedef struct {
#if defined(STM32F7)
TIM_HandleTypeDef TimHandle;
DMA_HandleTypeDef hdma_tim;
uint16_t timerDmaIndex;
#endif
} motorDmaOutput_t;

View File

@ -61,33 +61,29 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value)
uint8_t bufferSize = loadDmaBuffer(motor, packet);
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
} else {
if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
/* DMA set error */
return;
}
}
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
{
UNUSED(motorCount);
for (int i = 0; i < dmaMotorTimerCount; i++) {
/* Reset timer counter */
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
/* Enable channel DMA requests */
dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources;
}
}
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
{
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaSource]);
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
HAL_TIMEx_PWMN_Stop_DMA(&motor->TimHandle,motor->timerHardware->channel);
} else {
HAL_TIM_PWM_Stop_DMA(&motor->TimHandle,motor->timerHardware->channel);
}
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]);
__HAL_DMA_DISABLE(&motor->hdma_tim);
TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE);
}
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
@ -119,9 +115,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
return;
}
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
motor->timerDmaIndex = timerDmaIndex(timerHardware->channel);
motor->timer = &dmaMotorTimers[timerIndex];
dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource;
dmaMotorTimers[timerIndex].timerDmaSources |= timerDmaSource(timerHardware->channel);
/* Set the parameters to be configured */
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
@ -145,13 +141,13 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
motor->hdma_tim.Instance = timerHardware->dmaRef;
/* Link hdma_tim to hdma[x] (channelx) */
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
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->timerDmaIndex]) != HAL_OK) {
/* Initialization Error */
return;
}
@ -178,6 +174,17 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
/* Configuration Error */
return;
}
if (output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
} else {
if (HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
}
}
#endif

View File

@ -193,6 +193,9 @@ const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);
#if defined(USE_HAL_DRIVER)
TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim);
HAL_StatusTypeDef TIM_DMACmd(TIM_HandleTypeDef *htim, uint32_t Channel, FunctionalState NewState);
HAL_StatusTypeDef DMA_SetCurrDataCounter(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
uint16_t timerDmaIndex(uint8_t channel);
#else
void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init);
void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload);

View File

@ -44,9 +44,7 @@
TIM4 4 channels
*/
/// TODO: HAL in a lot af calls lookupTimerIndex is used. Instead of passing the timer instance the index should be passed.
#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
@ -58,7 +56,7 @@ typedef struct timerConfig_s {
timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
uint32_t forcedOverflowTimerValue;
} timerConfig_t;
timerConfig_t timerConfig[USED_TIMER_COUNT+1];
timerConfig_t timerConfig[USED_TIMER_COUNT + 1];
typedef struct {
channelType_t type;
@ -68,13 +66,12 @@ timerChannelInfo_t timerChannelInfo[USABLE_TIMER_CHANNEL_COUNT];
typedef struct {
uint8_t priority;
} timerInfo_t;
timerInfo_t timerInfo[USED_TIMER_COUNT+1];
timerInfo_t timerInfo[USED_TIMER_COUNT + 1];
typedef struct
{
typedef struct {
TIM_HandleTypeDef Handle;
} timerHandle_t;
timerHandle_t timerHandle[USED_TIMER_COUNT+1];
timerHandle_t timerHandle[USED_TIMER_COUNT + 1];
// return index of timer in timer table. Lowest timer has index 0
#define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
@ -247,8 +244,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz)
if (timerIndex >= USED_TIMER_COUNT) {
return;
}
if (timerHandle[timerIndex].Handle.Instance == tim)
{
if (timerHandle[timerIndex].Handle.Instance == tim) {
// already configured
return;
}
@ -263,23 +259,19 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz)
timerHandle[timerIndex].Handle.Init.RepetitionCounter = 0x0000;
HAL_TIM_Base_Init(&timerHandle[timerIndex].Handle);
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
{
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9) {
TIM_ClockConfigTypeDef sClockSourceConfig;
memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig));
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&timerHandle[timerIndex].Handle, &sClockSourceConfig) != HAL_OK)
{
if (HAL_TIM_ConfigClockSource(&timerHandle[timerIndex].Handle, &sClockSourceConfig) != HAL_OK) {
return;
}
}
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
{
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8) {
TIM_MasterConfigTypeDef sMasterConfig;
memset(&sMasterConfig, 0, sizeof(sMasterConfig));
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle[timerIndex].Handle, &sMasterConfig) != HAL_OK)
{
if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle[timerIndex].Handle, &sMasterConfig) != HAL_OK) {
return;
}
}
@ -332,7 +324,6 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori
configTimeBase(usedTimers[timer], 0, 1);
HAL_TIM_Base_Start(&timerHandle[timerIndex].Handle);
HAL_NVIC_SetPriority(irq, NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
HAL_NVIC_EnableIRQ(irq);
@ -353,7 +344,8 @@ void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *
// update overflow callback list
// some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) {
static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim)
{
uint8_t timerIndex = lookupTimerIndex(tim);
if (timerIndex >= USED_TIMER_COUNT) {
return;
@ -437,16 +429,17 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
//}
// enable/disable IRQ for low channel in dual configuration
void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState)
{
uint8_t timerIndex = lookupTimerIndex(timHw->tim);
if (timerIndex >= USED_TIMER_COUNT) {
return;
}
if (newState)
__HAL_TIM_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel&~TIM_CHANNEL_2));
__HAL_TIM_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TIM_CHANNEL_2));
else
__HAL_TIM_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel&~TIM_CHANNEL_2));
__HAL_TIM_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TIM_CHANNEL_2));
}
//// enable or disable IRQ
@ -524,7 +517,7 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned
TIM_ICInitStructure.ICSelection = TIM_ICSELECTION_DIRECTTI;
TIM_ICInitStructure.ICPrescaler = TIM_ICPSC_DIV1;
TIM_ICInitStructure.ICFilter = getFilter(inputFilterTicks);
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle,&TIM_ICInitStructure, timHw->channel);
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle, &TIM_ICInitStructure, timHw->channel);
}
// configure dual channel input channel for capture
@ -543,12 +536,12 @@ void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsi
TIM_ICInitStructure.ICSelection = TIM_ICSELECTION_DIRECTTI;
TIM_ICInitStructure.ICPrescaler = TIM_ICPSC_DIV1;
TIM_ICInitStructure.ICFilter = getFilter(inputFilterTicks);
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle,&TIM_ICInitStructure, timHw->channel);
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle, &TIM_ICInitStructure, timHw->channel);
// configure indirect channel
TIM_ICInitStructure.ICPolarity = directRising ? TIM_ICPOLARITY_FALLING : TIM_ICPOLARITY_RISING;
TIM_ICInitStructure.ICSelection = TIM_ICSELECTION_INDIRECTTI;
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle,&TIM_ICInitStructure, timHw->channel ^ TIM_CHANNEL_2);
HAL_TIM_IC_ConfigChannel(&timerHandle[timer].Handle, &TIM_ICInitStructure, timHw->channel ^ TIM_CHANNEL_2);
}
void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising)
@ -569,8 +562,6 @@ volatile timCCR_t* timerChCCRLo(const timerHardware_t *timHw)
return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_CHANNEL_2));
}
volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
{
return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel);
@ -582,7 +573,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
if (timer >= USED_TIMER_COUNT)
return;
TIM_OC_InitTypeDef TIM_OCInitStructure;
TIM_OC_InitTypeDef TIM_OCInitStructure;
TIM_OCInitStructure.OCMode = TIM_OCMODE_INACTIVE;
TIM_OCInitStructure.Pulse = 0x00000000;
@ -618,34 +609,34 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
tim->SR = mask;
tim_status &= mask;
switch (bit) {
case __builtin_clz(TIM_IT_UPDATE): {
case __builtin_clz(TIM_IT_UPDATE): {
if (timerConfig->forcedOverflowTimerValue != 0) {
capture = timerConfig->forcedOverflowTimerValue - 1;
timerConfig->forcedOverflowTimerValue = 0;
} else {
capture = tim->ARR;
}
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
while (cb) {
cb->fn(cb, capture);
cb = cb->next;
}
break;
if (timerConfig->forcedOverflowTimerValue != 0) {
capture = timerConfig->forcedOverflowTimerValue - 1;
timerConfig->forcedOverflowTimerValue = 0;
} else {
capture = tim->ARR;
}
case __builtin_clz(TIM_IT_CC1):
timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
break;
case __builtin_clz(TIM_IT_CC2):
timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
break;
case __builtin_clz(TIM_IT_CC3):
timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
break;
case __builtin_clz(TIM_IT_CC4):
timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
break;
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
while (cb) {
cb->fn(cb, capture);
cb = cb->next;
}
break;
}
case __builtin_clz(TIM_IT_CC1):
timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
break;
case __builtin_clz(TIM_IT_CC2):
timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
break;
case __builtin_clz(TIM_IT_CC3):
timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
break;
case __builtin_clz(TIM_IT_CC4):
timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
break;
}
}
#else
@ -746,7 +737,6 @@ void timerInit(void)
{
memset(timerConfig, 0, sizeof (timerConfig));
#if USED_TIMERS & TIM_N(1)
__HAL_RCC_TIM1_CLK_ENABLE();
#endif
@ -833,14 +823,15 @@ void timerStart(void)
for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
int priority = -1;
int irq = -1;
for (unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
for (unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++) {
if ((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
// TODO - move IRQ to timer info
irq = timerHardware[hwc].irq;
}
}
// TODO - aggregate required timer paramaters
configTimeBase(usedTimers[timer], 0, 1);
TIM_Cmd(usedTimers[timer], ENABLE);
TIM_Cmd(usedTimers[timer], ENABLE);
if (priority >= 0) { // maybe none of the channels was configured
NVIC_InitTypeDef NVIC_InitStructure;
@ -885,17 +876,34 @@ const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
return NULL;
}
// DMA_Handle_index
uint16_t timerDmaIndex(uint8_t channel)
{
switch (channel) {
case TIM_CHANNEL_1:
return TIM_DMA_ID_CC1;
case TIM_CHANNEL_2:
return TIM_DMA_ID_CC2;
case TIM_CHANNEL_3:
return TIM_DMA_ID_CC3;
case TIM_CHANNEL_4:
return TIM_DMA_ID_CC4;
}
return 0;
}
// TIM_DMA_sources
uint16_t timerDmaSource(uint8_t channel)
{
switch (channel) {
case TIM_CHANNEL_1:
return TIM_DMA_ID_CC1;
case TIM_CHANNEL_2:
return TIM_DMA_ID_CC2;
case TIM_CHANNEL_3:
return TIM_DMA_ID_CC3;
case TIM_CHANNEL_4:
return TIM_DMA_ID_CC4;
case TIM_CHANNEL_1:
return TIM_DMA_CC1;
case TIM_CHANNEL_2:
return TIM_DMA_CC2;
case TIM_CHANNEL_3:
return TIM_DMA_CC3;
case TIM_CHANNEL_4:
return TIM_DMA_CC4;
}
return 0;
}
@ -916,5 +924,135 @@ uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
if (hz > timerClock(tim)) {
return 0;
}
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
return (uint16_t)((timerClock(tim) + hz / 2) / hz) - 1;
}
HAL_StatusTypeDef TIM_DMACmd(TIM_HandleTypeDef *htim, uint32_t Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
switch (Channel) {
case TIM_CHANNEL_1: {
if (NewState != DISABLE) {
/* Enable the TIM Capture/Compare 1 DMA request */
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
} else {
/* Disable the TIM Capture/Compare 1 DMA request */
__HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
}
}
break;
case TIM_CHANNEL_2: {
if (NewState != DISABLE) {
/* Enable the TIM Capture/Compare 2 DMA request */
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
} else {
/* Disable the TIM Capture/Compare 2 DMA request */
__HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
}
}
break;
case TIM_CHANNEL_3: {
if (NewState != DISABLE) {
/* Enable the TIM Capture/Compare 3 DMA request */
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
} else {
/* Disable the TIM Capture/Compare 3 DMA request */
__HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
}
}
break;
case TIM_CHANNEL_4: {
if (NewState != DISABLE) {
/* Enable the TIM Capture/Compare 4 DMA request */
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4);
} else {
/* Disable the TIM Capture/Compare 4 DMA request */
__HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4);
}
}
break;
default:
break;
}
/* Change the htim state */
htim->State = HAL_TIM_STATE_READY;
/* Return function status */
return HAL_OK;
}
HAL_StatusTypeDef DMA_SetCurrDataCounter(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
{
/* Check the parameters */
assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
if ((htim->State == HAL_TIM_STATE_BUSY)) {
return HAL_BUSY;
} else if ((htim->State == HAL_TIM_STATE_READY)) {
if (((uint32_t) pData == 0) && (Length > 0)) {
return HAL_ERROR;
} else {
htim->State = HAL_TIM_STATE_BUSY;
}
}
switch (Channel) {
case TIM_CHANNEL_1: {
/* Set the DMA Period elapsed callback */
htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = HAL_TIM_DMADelayPulseCplt;
/* Set the DMA error callback */
htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = HAL_TIM_DMAError;
/* Enable the DMA Stream */
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t) pData, (uint32_t) & htim->Instance->CCR1, Length);
}
break;
case TIM_CHANNEL_2: {
/* Set the DMA Period elapsed callback */
htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = HAL_TIM_DMADelayPulseCplt;
/* Set the DMA error callback */
htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = HAL_TIM_DMAError;
/* Enable the DMA Stream */
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t) pData, (uint32_t) & htim->Instance->CCR2, Length);
}
break;
case TIM_CHANNEL_3: {
/* Set the DMA Period elapsed callback */
htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = HAL_TIM_DMADelayPulseCplt;
/* Set the DMA error callback */
htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = HAL_TIM_DMAError;
/* Enable the DMA Stream */
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t) pData, (uint32_t) & htim->Instance->CCR3, Length);
}
break;
case TIM_CHANNEL_4: {
/* Set the DMA Period elapsed callback */
htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = HAL_TIM_DMADelayPulseCplt;
/* Set the DMA error callback */
htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = HAL_TIM_DMAError;
/* Enable the DMA Stream */
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t) pData, (uint32_t) & htim->Instance->CCR4, Length);
}
break;
default:
break;
}
/* Return function status */
return HAL_OK;
}

View File

@ -30,6 +30,7 @@
#include "stm32f7xx_ll_dma.h"
#include "stm32f7xx_ll_rcc.h"
#include "stm32f7xx_ll_bus.h"
#include "stm32f7xx_ll_tim.h"
// Chip Unique ID on F7
#if defined(STM32F722xx)