/**
******************************************************************************
* @file tim.c
* @brief This file provides code for the configuration
* of the TIM instances.
******************************************************************************
* @attention
*
*
© Copyright (c) 2021 STMicroelectronics.
* All rights reserved.
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "tim.h"
/* USER CODE BEGIN 0 */
volatile int64_t encCntLoop[2];
/* USER CODE END 0 */
TIM_HandleTypeDef htim2;
TIM_HandleTypeDef htim3;
TIM_HandleTypeDef htim7;
TIM_HandleTypeDef htim9;
TIM_HandleTypeDef htim10;
TIM_HandleTypeDef htim11;
TIM_HandleTypeDef htim12;
TIM_HandleTypeDef htim13;
TIM_HandleTypeDef htim14;
/* TIM2 init function */
void MX_TIM2_Init(void)
{
/* USER CODE BEGIN TIM2_Init 0 */
/* USER CODE END TIM2_Init 0 */
TIM_Encoder_InitTypeDef sConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM2_Init 1 */
/* USER CODE END TIM2_Init 1 */
htim2.Instance = TIM2;
htim2.Init.Prescaler = 0;
htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
htim2.Init.Period = 65535;
htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
sConfig.EncoderMode = TIM_ENCODERMODE_TI12;
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
sConfig.IC1Filter = 4;
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
sConfig.IC2Filter = 4;
if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM2_Init 2 */
TIM2->CNT = 0;
TIM2->SR = TIM2->SR & 0xFE; // clear flag
/* USER CODE END TIM2_Init 2 */
}
/* TIM3 init function */
void MX_TIM3_Init(void)
{
/* USER CODE BEGIN TIM3_Init 0 */
/* USER CODE END TIM3_Init 0 */
TIM_Encoder_InitTypeDef sConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM3_Init 1 */
/* USER CODE END TIM3_Init 1 */
htim3.Instance = TIM3;
htim3.Init.Prescaler = 0;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 65535;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
sConfig.EncoderMode = TIM_ENCODERMODE_TI12;
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
sConfig.IC1Filter = 4;
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
sConfig.IC2Filter = 4;
if (HAL_TIM_Encoder_Init(&htim3, &sConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM3_Init 2 */
TIM3->CNT = 0;
TIM3->SR = TIM3->SR & 0xFE; // clear flag
/* USER CODE END TIM3_Init 2 */
}
/* TIM7 init function */
void MX_TIM7_Init(void)
{
/* USER CODE BEGIN TIM7_Init 0 */
/* USER CODE END TIM7_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM7_Init 1 */
/* USER CODE END TIM7_Init 1 */
htim7.Instance = TIM7;
htim7.Init.Prescaler = 83;
htim7.Init.CounterMode = TIM_COUNTERMODE_UP;
htim7.Init.Period = 9999;
htim7.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
if (HAL_TIM_Base_Init(&htim7) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim7, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM7_Init 2 */
/* USER CODE END TIM7_Init 2 */
}
/* TIM9 init function */
void MX_TIM9_Init(void)
{
/* USER CODE BEGIN TIM9_Init 0 */
/* USER CODE END TIM9_Init 0 */
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM9_Init 1 */
/* USER CODE END TIM9_Init 1 */
htim9.Instance = TIM9;
htim9.Init.Prescaler = 7;
htim9.Init.CounterMode = TIM_COUNTERMODE_UP;
htim9.Init.Period = 999;
htim9.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim9.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim9) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim9, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim9, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM9_Init 2 */
/* USER CODE END TIM9_Init 2 */
HAL_TIM_MspPostInit(&htim9);
}
/* TIM10 init function */
void MX_TIM10_Init(void)
{
/* USER CODE BEGIN TIM10_Init 0 */
/* USER CODE END TIM10_Init 0 */
/* USER CODE BEGIN TIM10_Init 1 */
/* USER CODE END TIM10_Init 1 */
htim10.Instance = TIM10;
htim10.Init.Prescaler = 167;
htim10.Init.CounterMode = TIM_COUNTERMODE_UP;
htim10.Init.Period = 9999;
htim10.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim10.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
if (HAL_TIM_Base_Init(&htim10) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM10_Init 2 */
/* USER CODE END TIM10_Init 2 */
}
/* TIM11 init function */
void MX_TIM11_Init(void)
{
/* USER CODE BEGIN TIM11_Init 0 */
/* USER CODE END TIM11_Init 0 */
/* USER CODE BEGIN TIM11_Init 1 */
/* USER CODE END TIM11_Init 1 */
htim11.Instance = TIM11;
htim11.Init.Prescaler = 167;
htim11.Init.CounterMode = TIM_COUNTERMODE_UP;
htim11.Init.Period = 9999;
htim11.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim11.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim11) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM11_Init 2 */
/* USER CODE END TIM11_Init 2 */
}
/* TIM12 init function */
void MX_TIM12_Init(void)
{
/* USER CODE BEGIN TIM12_Init 0 */
/* USER CODE END TIM12_Init 0 */
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM12_Init 1 */
/* USER CODE END TIM12_Init 1 */
htim12.Instance = TIM12;
htim12.Init.Prescaler = 3;
htim12.Init.CounterMode = TIM_COUNTERMODE_UP;
htim12.Init.Period = 999;
htim12.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim12.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim12) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim12, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim12, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM12_Init 2 */
/* USER CODE END TIM12_Init 2 */
HAL_TIM_MspPostInit(&htim12);
}
/* TIM13 init function */
void MX_TIM13_Init(void)
{
/* USER CODE BEGIN TIM13_Init 0 */
/* USER CODE END TIM13_Init 0 */
/* USER CODE BEGIN TIM13_Init 1 */
/* USER CODE END TIM13_Init 1 */
htim13.Instance = TIM13;
htim13.Init.Prescaler = 83;
htim13.Init.CounterMode = TIM_COUNTERMODE_UP;
htim13.Init.Period = 9999;
htim13.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim13.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim13) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM13_Init 2 */
/* USER CODE END TIM13_Init 2 */
}
/* TIM14 init function */
void MX_TIM14_Init(void)
{
/* USER CODE BEGIN TIM14_Init 0 */
/* USER CODE END TIM14_Init 0 */
/* USER CODE BEGIN TIM14_Init 1 */
/* USER CODE END TIM14_Init 1 */
htim14.Instance = TIM14;
htim14.Init.Prescaler = 83;
htim14.Init.CounterMode = TIM_COUNTERMODE_UP;
htim14.Init.Period = 9999;
htim14.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim14.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim14) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM14_Init 2 */
/* USER CODE END TIM14_Init 2 */
}
void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* tim_encoderHandle)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(tim_encoderHandle->Instance==TIM2)
{
/* USER CODE BEGIN TIM2_MspInit 0 */
/* USER CODE END TIM2_MspInit 0 */
/* TIM2 clock enable */
__HAL_RCC_TIM2_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM2 GPIO Configuration
PA15 ------> TIM2_CH1
PB3 ------> TIM2_CH2
*/
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* TIM2 interrupt Init */
HAL_NVIC_SetPriority(TIM2_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM2_IRQn);
/* USER CODE BEGIN TIM2_MspInit 1 */
/* USER CODE END TIM2_MspInit 1 */
}
else if(tim_encoderHandle->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspInit 0 */
/* USER CODE END TIM3_MspInit 0 */
/* TIM3 clock enable */
__HAL_RCC_TIM3_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
/**TIM3 GPIO Configuration
PC6 ------> TIM3_CH1
PC7 ------> TIM3_CH2
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF2_TIM3;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* TIM3 interrupt Init */
HAL_NVIC_SetPriority(TIM3_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM3_IRQn);
/* USER CODE BEGIN TIM3_MspInit 1 */
/* USER CODE END TIM3_MspInit 1 */
}
}
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
{
if(tim_baseHandle->Instance==TIM7)
{
/* USER CODE BEGIN TIM7_MspInit 0 */
/* USER CODE END TIM7_MspInit 0 */
/* TIM7 clock enable */
__HAL_RCC_TIM7_CLK_ENABLE();
/* TIM7 interrupt Init */
HAL_NVIC_SetPriority(TIM7_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM7_IRQn);
/* USER CODE BEGIN TIM7_MspInit 1 */
/* USER CODE END TIM7_MspInit 1 */
}
else if(tim_baseHandle->Instance==TIM10)
{
/* USER CODE BEGIN TIM10_MspInit 0 */
/* USER CODE END TIM10_MspInit 0 */
/* TIM10 clock enable */
__HAL_RCC_TIM10_CLK_ENABLE();
/* TIM10 interrupt Init */
HAL_NVIC_SetPriority(TIM1_UP_TIM10_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn);
/* USER CODE BEGIN TIM10_MspInit 1 */
/* USER CODE END TIM10_MspInit 1 */
}
else if(tim_baseHandle->Instance==TIM11)
{
/* USER CODE BEGIN TIM11_MspInit 0 */
/* USER CODE END TIM11_MspInit 0 */
/* TIM11 clock enable */
__HAL_RCC_TIM11_CLK_ENABLE();
/* TIM11 interrupt Init */
HAL_NVIC_SetPriority(TIM1_TRG_COM_TIM11_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM1_TRG_COM_TIM11_IRQn);
/* USER CODE BEGIN TIM11_MspInit 1 */
/* USER CODE END TIM11_MspInit 1 */
}
else if(tim_baseHandle->Instance==TIM13)
{
/* USER CODE BEGIN TIM13_MspInit 0 */
/* USER CODE END TIM13_MspInit 0 */
/* TIM13 clock enable */
__HAL_RCC_TIM13_CLK_ENABLE();
/* TIM13 interrupt Init */
HAL_NVIC_SetPriority(TIM8_UP_TIM13_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM8_UP_TIM13_IRQn);
/* USER CODE BEGIN TIM13_MspInit 1 */
/* USER CODE END TIM13_MspInit 1 */
}
else if(tim_baseHandle->Instance==TIM14)
{
/* USER CODE BEGIN TIM14_MspInit 0 */
/* USER CODE END TIM14_MspInit 0 */
/* TIM14 clock enable */
__HAL_RCC_TIM14_CLK_ENABLE();
/* TIM14 interrupt Init */
HAL_NVIC_SetPriority(TIM8_TRG_COM_TIM14_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM8_TRG_COM_TIM14_IRQn);
/* USER CODE BEGIN TIM14_MspInit 1 */
/* USER CODE END TIM14_MspInit 1 */
}
}
void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* tim_pwmHandle)
{
if(tim_pwmHandle->Instance==TIM9)
{
/* USER CODE BEGIN TIM9_MspInit 0 */
/* USER CODE END TIM9_MspInit 0 */
/* TIM9 clock enable */
__HAL_RCC_TIM9_CLK_ENABLE();
/* USER CODE BEGIN TIM9_MspInit 1 */
/* USER CODE END TIM9_MspInit 1 */
}
else if(tim_pwmHandle->Instance==TIM12)
{
/* USER CODE BEGIN TIM12_MspInit 0 */
/* USER CODE END TIM12_MspInit 0 */
/* TIM12 clock enable */
__HAL_RCC_TIM12_CLK_ENABLE();
/* USER CODE BEGIN TIM12_MspInit 1 */
/* USER CODE END TIM12_MspInit 1 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(timHandle->Instance==TIM9)
{
/* USER CODE BEGIN TIM9_MspPostInit 0 */
/* USER CODE END TIM9_MspPostInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**TIM9 GPIO Configuration
PA2 ------> TIM9_CH1
PA3 ------> TIM9_CH2
*/
GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF3_TIM9;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN TIM9_MspPostInit 1 */
/* USER CODE END TIM9_MspPostInit 1 */
}
else if(timHandle->Instance==TIM12)
{
/* USER CODE BEGIN TIM12_MspPostInit 0 */
/* USER CODE END TIM12_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM12 GPIO Configuration
PB14 ------> TIM12_CH1
PB15 ------> TIM12_CH2
*/
GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_TIM12;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM12_MspPostInit 1 */
/* USER CODE END TIM12_MspPostInit 1 */
}
}
void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* tim_encoderHandle)
{
if(tim_encoderHandle->Instance==TIM2)
{
/* USER CODE BEGIN TIM2_MspDeInit 0 */
/* USER CODE END TIM2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM2_CLK_DISABLE();
/**TIM2 GPIO Configuration
PA15 ------> TIM2_CH1
PB3 ------> TIM2_CH2
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_3);
/* TIM2 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM2_IRQn);
/* USER CODE BEGIN TIM2_MspDeInit 1 */
/* USER CODE END TIM2_MspDeInit 1 */
}
else if(tim_encoderHandle->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspDeInit 0 */
/* USER CODE END TIM3_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM3_CLK_DISABLE();
/**TIM3 GPIO Configuration
PC6 ------> TIM3_CH1
PC7 ------> TIM3_CH2
*/
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_6|GPIO_PIN_7);
/* TIM3 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM3_IRQn);
/* USER CODE BEGIN TIM3_MspDeInit 1 */
/* USER CODE END TIM3_MspDeInit 1 */
}
}
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
{
if(tim_baseHandle->Instance==TIM7)
{
/* USER CODE BEGIN TIM7_MspDeInit 0 */
/* USER CODE END TIM7_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM7_CLK_DISABLE();
/* TIM7 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM7_IRQn);
/* USER CODE BEGIN TIM7_MspDeInit 1 */
/* USER CODE END TIM7_MspDeInit 1 */
}
else if(tim_baseHandle->Instance==TIM10)
{
/* USER CODE BEGIN TIM10_MspDeInit 0 */
/* USER CODE END TIM10_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM10_CLK_DISABLE();
/* TIM10 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn);
/* USER CODE BEGIN TIM10_MspDeInit 1 */
/* USER CODE END TIM10_MspDeInit 1 */
}
else if(tim_baseHandle->Instance==TIM11)
{
/* USER CODE BEGIN TIM11_MspDeInit 0 */
/* USER CODE END TIM11_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM11_CLK_DISABLE();
/* TIM11 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM1_TRG_COM_TIM11_IRQn);
/* USER CODE BEGIN TIM11_MspDeInit 1 */
/* USER CODE END TIM11_MspDeInit 1 */
}
else if(tim_baseHandle->Instance==TIM13)
{
/* USER CODE BEGIN TIM13_MspDeInit 0 */
/* USER CODE END TIM13_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM13_CLK_DISABLE();
/* TIM13 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM8_UP_TIM13_IRQn);
/* USER CODE BEGIN TIM13_MspDeInit 1 */
/* USER CODE END TIM13_MspDeInit 1 */
}
else if(tim_baseHandle->Instance==TIM14)
{
/* USER CODE BEGIN TIM14_MspDeInit 0 */
/* USER CODE END TIM14_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM14_CLK_DISABLE();
/* TIM14 interrupt Deinit */
HAL_NVIC_DisableIRQ(TIM8_TRG_COM_TIM14_IRQn);
/* USER CODE BEGIN TIM14_MspDeInit 1 */
/* USER CODE END TIM14_MspDeInit 1 */
}
}
void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* tim_pwmHandle)
{
if(tim_pwmHandle->Instance==TIM9)
{
/* USER CODE BEGIN TIM9_MspDeInit 0 */
/* USER CODE END TIM9_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM9_CLK_DISABLE();
/* USER CODE BEGIN TIM9_MspDeInit 1 */
/* USER CODE END TIM9_MspDeInit 1 */
}
else if(tim_pwmHandle->Instance==TIM12)
{
/* USER CODE BEGIN TIM12_MspDeInit 0 */
/* USER CODE END TIM12_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM12_CLK_DISABLE();
/* USER CODE BEGIN TIM12_MspDeInit 1 */
/* USER CODE END TIM12_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim)
{
if (htim->Instance->SR & 0x01) // count overflow
{
if (htim->Instance->CR1 & 0x10) // count up
{
if (htim->Instance == TIM2)
encCntLoop[0]--;
else if (htim->Instance == TIM3)
encCntLoop[1]--;
} else // count down
{
if (htim->Instance == TIM2)
encCntLoop[0]++;
else if (htim->Instance == TIM3)
encCntLoop[1]++;
}
htim->Instance->SR = htim->Instance->SR & 0xFE; // clear flag
}
}
int64_t GetCntLoop(TIM_TypeDef *tim)
{
if (tim == TIM2)
{
return encCntLoop[0];
} else if (tim == TIM3)
{
return encCntLoop[1];
}
}
void ClearCntLoop(TIM_TypeDef *tim)
{
if (tim == TIM2)
{
encCntLoop[0] = 0;
} else if (tim == TIM3)
{
encCntLoop[1] = 0;
}
}
int64_t GetEncoderCount(TIM_TypeDef *tim)
{
if (tim == TIM2)
{
return encCntLoop[0] * 65536 + TIM2->CNT;
} else if (tim == TIM3)
{
return encCntLoop[1] * 65536 + TIM3->CNT;
}
}
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/