MCU Phase Detector using DMA in the STM32F303RE

In an earlier blog I described a BLDC motor control using a phase detector (PD) implemented in an FPGA, along with the other closed loop compensation. In this blog I will describe a similar control loop but instead implemented in a STM32F303RE MCU. The challenge in this design is to move all control internal to the MCU and to not use any peripheral logic in the FPGA. The key performance specification for this design is to achieve less than 3 usec peak-to-peak jitter in the once around optical feedback. A block diagram of the system is shown in Figure 1. The inner velocity control loop is implemented using the Field Oriented Control (FOC) library from the ST tools. The outer loop is the PD with PID compensation. In this case the outer loop PID function will use the ST library. This blog will focus on the implementation of the PD. My intention is to help those just getting started with the STM32 and it's tools. Those wanting a copy of the MXCube *.ioc file can contact me.

Why The Choice of DMA

The critical timing in the design is the measurement of phase between the reference and feedback without introducing measurement jitter. The choices within the MCU are software polling, interrupts and DMA. It should be obvious that given our jitter requirement the use of software polling is not considered.

In the system the motor is using 16kHz PWM and making ADC acquisitions both of which are occurring with high priority interrupts. Any interrupt scheme used for the PD would incur the latency of getting into and out of the interrupt (24 clocks total) plus the computation time in the higher priority interrupt. The interrupts for a PD could easily see a 15-30usec peak-peak jitter. For this reason the use of interrupts for the PD measurement are avoided.

It may seem like overkill to use DMA to capture a single 32-bit word but the accuracy is ideal for this application. Two DMA channels are used to capture a free running timer. The capture occurs on the rising edge of the incoming signal and the capture is accomplished in hardware, independent of the MCU Core activity. Once the timer captures are accomplished any delay in processing is simply a system delay and not a contributor to measurement jitter.

Implementation

The project was created using STMicroelectronics STM32CubeMx v5.6.1 and the Keil Tool chain. Note the size of the code exceeds the 32k limit of the 'free' Keil compiler. In addition to the code which the 'Cube' creates the user must add some initialization code. The hardware platform used is the STM32 Nucleo-F303RE MCU board plus the Nucleo Expansion IHM16M1 Driver board.

In this example Timer4 is used as the PD timer. Timer1 is dedicated to the FOC motor control.

Figure 1 shows the interconnect of the Timer4 sections to implement the phase detector.

Figure 1 - Timer Peripherals for Phase Detector 

I configured Timer4 to have a 72MHz clock with a prescale of 8 (divide by 9) giving a resolution of 125ns. The divider is chosen as 65535 to give a rollover rate of 137.3Hz. This is chosen to be considerably less than the nominal 192Hz motor reference frequency. For MCU specifics use the ST Reference Manual RM0365.

Timer4 channel 1 is used to capture the reference frequency and Timer4 channel 2 is used to capture the feedback frequency. The peripheral interconnects of the STM32F303RE are such that these particular timer captures can be connected to DMA1 channel 1 and DMA1 channel 4 respectively. The DMA channels are each configured as a single word operating in circular buffer mode.

In software DMA1 channel 1 destination address is assigned to uint32_t buffer1 and DMA1 channel 4 is assigned to uint32_t buffer2. The source address for the DMA channels is the peripheral address of the Timer4 capture registers CCR1 and CCR2.

The gist snippet below shows the main.c module. The areas of interest are the DMA configuration in the call to user function DMA_Config before entering the while loop and the enabling of Timer 4. Also of interest are the functions MX_Timer4_Init and phase_detect.

The second snippet from file stm32f3xx_it.c  shows the transfer complete interrupt handlers that do the processing after the data is captured.

/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* 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
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "motorcontrol.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <string.h>
#include <stdio.h>
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
DAC_HandleTypeDef hdac1;
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim4;
DMA_HandleTypeDef hdma_tim4_ch1;
DMA_HandleTypeDef hdma_tim4_ch2;
UART_HandleTypeDef huart2;
/* USER CODE BEGIN PV */
//bpt
uint32_t volatile buffer1[BUFFER_SIZE] = {0xdeaddead};
uint32_t volatile buffer2[BUFFER_SIZE] = {0xdeaddead};
uint8_t buf[9];
struct DmaCntDef volatile DmaCnt;
// define external variables
uint16_t volatile buffer_jit[BUFFER_SZ_JIT] = {0};
struct DmaCntDef volatile * ptr_DmaCnt = &DmaCnt;
static int32_t volatile ph_error[1] = {0}; /* phase error */
static uint32_t volatile Error_Count = 0;
static __IO uint32_t transferError1Detected; /* Set to 1 if an error transfer is detected */
static __IO uint32_t transferError3Detected; /* Set to 1 if an error transfer is detected */
static int32_t Updated_phase = 0;
//static int16_t motor_state = 0;
//static int16_t motor_fault = 0;
static int16_t motor_speed = 0;
static uint32_t g_ref;
static uint32_t g_fbk;
static int32_t g_error;
PID_Handle_t *pPIDph;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_DMA_Init(void);
static void MX_ADC1_Init(void);
static void MX_ADC2_Init(void);
static void MX_DAC1_Init(void);
static void MX_TIM1_Init(void);
static void MX_TIM4_Init(void);
static void MX_USART2_UART_Init(void);
static void MX_NVIC_Init(void);
/* USER CODE BEGIN PFP */
//bpt
static void Toggle_LED(void);
static void DMA_Config(void);
static void TransferCompleteFb(DMA_HandleTypeDef *);
static void TransferCompleteRef(DMA_HandleTypeDef *);
static void TransferErrorFb(DMA_HandleTypeDef *);
static void TransferErrorRef(DMA_HandleTypeDef *);
static void Outer_PID_Init(void);
static void update_pid(struct DmaCntDef volatile *);
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
//bpt
ptr_DmaCnt = &DmaCnt;
//uint16_t value = {0x0000} ;
ptr_DmaCnt->fbkCnt = 0;
ptr_DmaCnt->refCnt = 0;
ptr_DmaCnt->refOldCnt = 0;
ptr_DmaCnt->refNewCnt = 0;
ptr_DmaCnt->refPeriod = 0;
float temp_c;
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* Set to 1 if an transfer error is detected */
//bpt
transferError1Detected = 0;
transferError3Detected = 0;
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_DMA_Init();
MX_ADC1_Init();
MX_ADC2_Init();
MX_DAC1_Init();
MX_TIM1_Init();
MX_TIM4_Init();
MX_USART2_UART_Init();
MX_MotorControl_Init();
/* Initialize interrupts */
MX_NVIC_Init();
/* USER CODE BEGIN 2 */
//bpt
DMA_Config();
Outer_PID_Init();
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
/* Start TIM4 then enable capture */
#define PHASE_DETECT
#ifdef PHASE_DETECT
{
/* TIM4->CR1 |= TIM_CR1_CEN_Msk; start the timer */
/* *** TIM4 capture/compare enable register: CCER */
/* Set the TIM4_CCER register: */
TIM4->CCER = 0x013; // opposite polarity & enabled
/* enable TIM4 DMA interrupts */
TIM4->DIER = 0x0600;
}
#endif
/* debug help, stops clocks at breakpoints */
DBGMCU->APB1FZ |= DBGMCU_APB1_FZ_DBG_TIM2_STOP ;
/* DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP); */
while (1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
// bpt
HAL_Delay(500);
//motor_state = MC_GetSTMStateMotor1();
//motor_fault= MC_GetCurrentFaultsMotor1();
motor_speed = MC_GetMecSpeedAverageMotor1();
/* check if motor is running and if so
* start the TIM2 interrrupts else
* disable TIM2 interrupts
*/
// Send out buffer (timing or error message)
// Convert data to decimal string format
temp_c = motor_speed; // timer count
sprintf((char*)buf,
"%u counts\r\n",
((unsigned int)temp_c ));
if(ptr_DmaCnt->full)
{
for (int i=0; i < BUFFER_SZ_JIT; i++)
{
sprintf((char *) buf, "%u \r\n", ((unsigned int) buffer_jit[i] ));
HAL_UART_Transmit(&huart2, buf, strlen((const char *)buf), HAL_MAX_DELAY);
}
}
ptr_DmaCnt->full = false;
HAL_Delay(100);
//
// if (transferErrorDetected == 1)
// {
// /* Toggle LED with a period of 1000ms */
// Toggle_LED();
// HAL_Delay(500);
// }
if (Updated_phase)
{
update_pid(ptr_DmaCnt);
Updated_phase = 0;
}
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Initializes the CPU, AHB and APB busses clocks
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB busses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_TIM1
|RCC_PERIPHCLK_TIM34;
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
PeriphClkInit.Tim1ClockSelection = RCC_TIM1CLK_PLLCLK;
PeriphClkInit.Tim34ClockSelection = RCC_TIM34CLK_HCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/** Enables the Clock Security System
*/
HAL_RCC_EnableCSS();
}
/**
* @brief NVIC Configuration.
* @retval None
*/
static void MX_NVIC_Init(void)
{
/* TIM1_BRK_TIM15_IRQn interrupt configuration */
HAL_NVIC_SetPriority(TIM1_BRK_TIM15_IRQn, 4, 1);
HAL_NVIC_EnableIRQ(TIM1_BRK_TIM15_IRQn);
/* TIM1_UP_TIM16_IRQn interrupt configuration */
HAL_NVIC_SetPriority(TIM1_UP_TIM16_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM1_UP_TIM16_IRQn);
/* ADC1_2_IRQn interrupt configuration */
HAL_NVIC_SetPriority(ADC1_2_IRQn, 2, 0);
HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
/* USART2_IRQn interrupt configuration */
HAL_NVIC_SetPriority(USART2_IRQn, 3, 1);
HAL_NVIC_EnableIRQ(USART2_IRQn);
/* EXTI15_10_IRQn interrupt configuration */
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 3, 0);
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
}
/**
* @brief ADC1 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC1_Init(void)
{
/* USER CODE BEGIN ADC1_Init 0 */
/* USER CODE END ADC1_Init 0 */
ADC_MultiModeTypeDef multimode = {0};
ADC_InjectionConfTypeDef sConfigInjected = {0};
/* USER CODE BEGIN ADC1_Init 1 */
/* USER CODE END ADC1_Init 1 */
/** Common config
*/
hadc1.Instance = ADC1;
hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV1;
hadc1.Init.Resolution = ADC_RESOLUTION_12B;
hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.DataAlign = ADC_DATAALIGN_LEFT;
hadc1.Init.NbrOfConversion = 1;
hadc1.Init.DMAContinuousRequests = DISABLE;
hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc1.Init.LowPowerAutoWait = DISABLE;
hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
if (HAL_ADC_Init(&hadc1) != HAL_OK)
{
Error_Handler();
}
/** Configure the ADC multi-mode
*/
multimode.Mode = ADC_MODE_INDEPENDENT;
if (HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode) != HAL_OK)
{
Error_Handler();
}
/** Configure Injected Channel
*/
sConfigInjected.InjectedChannel = ADC_CHANNEL_2;
sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
sConfigInjected.InjectedSingleDiff = ADC_SINGLE_ENDED;
sConfigInjected.InjectedNbrOfConversion = 2;
sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_19CYCLES_5;
sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONV_EDGE_RISING;
sConfigInjected.ExternalTrigInjecConv = ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
sConfigInjected.AutoInjectedConv = DISABLE;
sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
sConfigInjected.QueueInjectedContext = ENABLE;
sConfigInjected.InjectedOffset = 0;
sConfigInjected.InjectedOffsetNumber = ADC_OFFSET_NONE;
if (HAL_ADCEx_InjectedConfigChannel(&hadc1, &sConfigInjected) != HAL_OK)
{
Error_Handler();
}
/** Configure Injected Channel
*/
sConfigInjected.InjectedChannel = ADC_CHANNEL_14;
sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
if (HAL_ADCEx_InjectedConfigChannel(&hadc1, &sConfigInjected) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN ADC1_Init 2 */
/* USER CODE END ADC1_Init 2 */
}
/**
* @brief ADC2 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC2_Init(void)
{
/* USER CODE BEGIN ADC2_Init 0 */
/* USER CODE END ADC2_Init 0 */
ADC_InjectionConfTypeDef sConfigInjected = {0};
ADC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN ADC2_Init 1 */
/* USER CODE END ADC2_Init 1 */
/** Common config
*/
hadc2.Instance = ADC2;
hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV1;
hadc2.Init.Resolution = ADC_RESOLUTION_12B;
hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc2.Init.DataAlign = ADC_DATAALIGN_LEFT;
hadc2.Init.NbrOfConversion = 2;
hadc2.Init.DMAContinuousRequests = DISABLE;
hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc2.Init.LowPowerAutoWait = DISABLE;
hadc2.Init.Overrun = ADC_OVR_DATA_PRESERVED;
if (HAL_ADC_Init(&hadc2) != HAL_OK)
{
Error_Handler();
}
/** Configure Injected Channel
*/
sConfigInjected.InjectedChannel = ADC_CHANNEL_14;
sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
sConfigInjected.InjectedSingleDiff = ADC_SINGLE_ENDED;
sConfigInjected.InjectedNbrOfConversion = 2;
sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_19CYCLES_5;
sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONV_EDGE_RISING;
sConfigInjected.ExternalTrigInjecConv = ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
sConfigInjected.AutoInjectedConv = DISABLE;
sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
sConfigInjected.QueueInjectedContext = ENABLE;
sConfigInjected.InjectedOffset = 0;
sConfigInjected.InjectedOffsetNumber = ADC_OFFSET_NONE;
if (HAL_ADCEx_InjectedConfigChannel(&hadc2, &sConfigInjected) != HAL_OK)
{
Error_Handler();
}
/** Configure Injected Channel
*/
sConfigInjected.InjectedChannel = ADC_CHANNEL_4;
sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
if (HAL_ADCEx_InjectedConfigChannel(&hadc2, &sConfigInjected) != HAL_OK)
{
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_11;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
{
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_5;
sConfig.Rank = ADC_REGULAR_RANK_2;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN ADC2_Init 2 */
/* USER CODE END ADC2_Init 2 */
}
/**
* @brief DAC1 Initialization Function
* @param None
* @retval None
*/
static void MX_DAC1_Init(void)
{
/* USER CODE BEGIN DAC1_Init 0 */
/* USER CODE END DAC1_Init 0 */
DAC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN DAC1_Init 1 */
/* USER CODE END DAC1_Init 1 */
/** DAC Initialization
*/
hdac1.Instance = DAC1;
if (HAL_DAC_Init(&hdac1) != HAL_OK)
{
Error_Handler();
}
/** DAC channel OUT1 config
*/
sConfig.DAC_Trigger = DAC_TRIGGER_SOFTWARE;
sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_DISABLE;
if (HAL_DAC_ConfigChannel(&hdac1, &sConfig, DAC_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN DAC1_Init 2 */
/* USER CODE END DAC1_Init 2 */
}
/**
* @brief TIM1 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM1_Init(void)
{
/* USER CODE BEGIN TIM1_Init 0 */
/* USER CODE END TIM1_Init 0 */
TIM_SlaveConfigTypeDef sSlaveConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
/* USER CODE BEGIN TIM1_Init 1 */
/* USER CODE END TIM1_Init 1 */
htim1.Instance = TIM1;
htim1.Init.Prescaler = ((TIM_CLOCK_DIVIDER) - 1);
htim1.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED1;
htim1.Init.Period = ((PWM_PERIOD_CYCLES) / 2);
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV2;
htim1.Init.RepetitionCounter = (REP_COUNTER);
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
{
Error_Handler();
}
sSlaveConfig.SlaveMode = TIM_SLAVEMODE_TRIGGER;
sSlaveConfig.InputTrigger = TIM_TS_ITR1;
if (HAL_TIM_SlaveConfigSynchro(&htim1, &sSlaveConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_OC4REF;
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = ((PWM_PERIOD_CYCLES) / 4);
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM2;
sConfigOC.Pulse = (((PWM_PERIOD_CYCLES) / 2) - (HTMIN));
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
{
Error_Handler();
}
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_ENABLE;
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_ENABLE;
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_1;
sBreakDeadTimeConfig.DeadTime = 0;
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
sBreakDeadTimeConfig.BreakFilter = 0;
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_ENABLE;
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_LOW;
sBreakDeadTimeConfig.Break2Filter = 3;
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM1_Init 2 */
/* USER CODE END TIM1_Init 2 */
HAL_TIM_MspPostInit(&htim1);
}
/**
* @brief TIM4 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM4_Init(void)
{
/* USER CODE BEGIN TIM4_Init 0 */
/* USER CODE END TIM4_Init 0 */
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_IC_InitTypeDef sConfigIC = {0};
/* USER CODE BEGIN TIM4_Init 1 */
/* USER CODE END TIM4_Init 1 */
htim4.Instance = TIM4;
htim4.Init.Prescaler = 8;
htim4.Init.CounterMode = TIM_COUNTERMODE_UP;
htim4.Init.Period = 65535;
htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
if (HAL_TIM_Base_Init(&htim4) != HAL_OK)
{
Error_Handler();
}
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_IC_Init(&htim4) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
sConfigIC.ICSelection = TIM_ICSELECTION_DIRECTTI;
sConfigIC.ICPrescaler = TIM_ICPSC_DIV1;
sConfigIC.ICFilter = 0;
if (HAL_TIM_IC_ConfigChannel(&htim4, &sConfigIC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_FALLING;
if (HAL_TIM_IC_ConfigChannel(&htim4, &sConfigIC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM4_Init 2 */
//bpt
HAL_TIM_Base_Start(&htim4);
/* USER CODE END TIM4_Init 2 */
}
/**
* @brief USART2 Initialization Function
* @param None
* @retval None
*/
static void MX_USART2_UART_Init(void)
{
/* USER CODE BEGIN USART2_Init 0 */
/* USER CODE END USART2_Init 0 */
/* USER CODE BEGIN USART2_Init 1 */
/* USER CODE END USART2_Init 1 */
huart2.Instance = USART2;
huart2.Init.BaudRate = 115200;
huart2.Init.WordLength = UART_WORDLENGTH_8B;
huart2.Init.StopBits = UART_STOPBITS_1;
huart2.Init.Parity = UART_PARITY_NONE;
huart2.Init.Mode = UART_MODE_TX_RX;
huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart2.Init.OverSampling = UART_OVERSAMPLING_16;
huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART2_Init 2 */
/* USER CODE END USART2_Init 2 */
}
/**
* Enable DMA controller clock
*/
static void MX_DMA_Init(void)
{
/* DMA controller clock enable */
__HAL_RCC_DMA1_CLK_ENABLE();
/* DMA interrupt init */
/* DMA1_Channel1_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn);
/* DMA1_Channel4_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA1_Channel4_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel4_IRQn);
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(LED2_GPIO_Port, LED2_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB, M1_PWM_EN_U_Pin|M1_PWM_EN_V_Pin|M1_PWM_EN_W_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin : Start_Stop_Pin */
GPIO_InitStruct.Pin = Start_Stop_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(Start_Stop_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : LED2_Pin */
GPIO_InitStruct.Pin = LED2_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(LED2_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : M1_PWM_EN_U_Pin M1_PWM_EN_V_Pin M1_PWM_EN_W_Pin */
GPIO_InitStruct.Pin = M1_PWM_EN_U_Pin|M1_PWM_EN_V_Pin|M1_PWM_EN_W_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pin : GP_Input_Pin */
GPIO_InitStruct.Pin = GP_Input_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLUP;
HAL_GPIO_Init(GP_Input_GPIO_Port, &GPIO_InitStruct);
}
/* USER CODE BEGIN 4 */
/**
* Configure DMA //bpt
* Enable DMA controller clock
*
*/
static void DMA_Config(void)
{
/*##-2- Select the DMA functional Parameters for TIM4 chan1 & chan2 ######################*/
hdma_tim4_ch2.Init.Direction = DMA_PERIPH_TO_MEMORY; /* M2M transfer mode */
hdma_tim4_ch2.Init.PeriphInc = DMA_PINC_DISABLE; /* Peripheral increment mode Enable */
hdma_tim4_ch2.Init.MemInc = DMA_MINC_DISABLE; /* Memory increment mode Enable */
hdma_tim4_ch2.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; /* Peripheral data alignment : Word */
hdma_tim4_ch2.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; /* memory data alignment : Word */
hdma_tim4_ch2.Init.Mode = DMA_CIRCULAR; /* Circular DMA mode */
hdma_tim4_ch2.Init.Priority = DMA_PRIORITY_HIGH; /* priority level : high */
hdma_tim4_ch1.Init.Direction = DMA_PERIPH_TO_MEMORY; /* M2M transfer mode */
hdma_tim4_ch1.Init.PeriphInc = DMA_PINC_DISABLE; /* Peripheral increment mode Enable */
hdma_tim4_ch1.Init.MemInc = DMA_MINC_DISABLE; /* Memory increment mode Enable */
hdma_tim4_ch1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; /* Peripheral data alignment : Word */
hdma_tim4_ch1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; /* memory data alignment : Word */
hdma_tim4_ch1.Init.Mode = DMA_CIRCULAR; /* Normal DMA mode */
hdma_tim4_ch1.Init.Priority = DMA_PRIORITY_HIGH; /* priority level : high */
/* ##-3- Select the DMA instance to be used for the transfers # */
/* TIM4 ch1 is DMA ch 1, TIM4 ch2 is DMA ch 4 */
hdma_tim4_ch2.Instance = DMA1_Channel4;
hdma_tim4_ch1.Instance = DMA1_Channel1;
/*##-4- Initialize the DMA channel ##########################################*/
if (HAL_DMA_Init(&hdma_tim4_ch2) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
if (HAL_DMA_Init(&hdma_tim4_ch1) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
/*##-5- Select Callbacks functions called after Transfer complete and Transfer error */
HAL_DMA_RegisterCallback(&hdma_tim4_ch2, HAL_DMA_XFER_CPLT_CB_ID, TransferCompleteFb);
HAL_DMA_RegisterCallback(&hdma_tim4_ch1, HAL_DMA_XFER_CPLT_CB_ID, TransferCompleteRef);
HAL_DMA_RegisterCallback(&hdma_tim4_ch2, HAL_DMA_XFER_ERROR_CB_ID, TransferErrorFb);
HAL_DMA_RegisterCallback(&hdma_tim4_ch1, HAL_DMA_XFER_ERROR_CB_ID, TransferErrorRef);
/*##-6- Configure NVIC for DMA transfer complete/error interrupts ##########*/
/* Set Interrupt Group Priority */
HAL_NVIC_SetPriority(DMA1_Channel4_IRQn, 3, 2); /* sets intr # and priority */
HAL_NVIC_EnableIRQ(DMA1_Channel4_IRQn); /* enables intr */
HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 3, 2); /* sets intr # and priority */
HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn); /* enables intr */
/*##-7- Start the DMA transfers using the interrupt mode ####################*/
/* Configure the source, destination and buffer size DMA fields and Start DMA transfer */
/* Enable All the DMA interrupts */
if (HAL_DMA_Start_IT(&hdma_tim4_ch2, (uint32_t)&TIM4->CCR2, (uint32_t)&buffer1, BUFFER_SIZE) != HAL_OK)
{
/* Transfer Error */
Error_Handler();
}
if (HAL_DMA_Start_IT(&hdma_tim4_ch1, (uint32_t)&TIM4->CCR1, (uint32_t)&buffer2, BUFFER_SIZE) != HAL_OK)
{
/* Transfer Error */
Error_Handler();
}
}
static void Outer_PID_Init(void)
{
/* initialize PID for outer phase loop */
}
/**
* @brief DMA conversion complete callback
* @note This function is executed when the transfer complete interrupt
* is generated for dma channel5
* @retval None
*/
static void TransferCompleteFb(DMA_HandleTypeDef *DmaHandle)
{
/* for TIM4 chan 2, dma 4 */
}
/**
* @brief DMA conversion complete callback
* @note This function is executed when the transfer complete interrupt
* is generated for dma channel1
* @retval None
*/
static void TransferCompleteRef(DMA_HandleTypeDef *DmaHandle)
{
/* For TIM4 chan 1, dma 1 */
}
/**
* @brief DMA conversion error callback
* @note This function is executed when the transfer error interrupt
* is generated during DMA transfer
* @retval None
*/
static void TransferErrorFb(DMA_HandleTypeDef *DmaHandle)
{
transferError1Detected = 1;
}
static void TransferErrorRef(DMA_HandleTypeDef *DmaHandle)
{
transferError3Detected = 1;
}
void phase_detect(struct DmaCntDef volatile * temp)
{
/** phase detector logic
* arrive here only if count > 1
* check if error: count > 2
* compute phase error from buffer1 and buffer2
* results in *ph_error
* reset count to zero.
*/
uint16_t count = temp->fbkCnt + temp->refCnt;
g_ref = *buffer1;
g_fbk = *buffer2;
int32_t TWO_PI = htim4.Init.Period ;
if ( count > 2)
{
Error_Handler();
}
else
{
/* unravel TIM2 to range +/- PI */
g_error = g_ref - g_fbk;
if(g_error > (TWO_PI >>1) ) /* greater than pi */
{
g_error -= TWO_PI;
}
if (g_error < -(TWO_PI >>1))
{
g_error += TWO_PI;
}
/* limit magnitude of error to fref +/-PI */
if (g_error > PHASE_MAX)
*ph_error = PHASE_MAX;
else if (g_error < -PHASE_MAX)
*ph_error = -PHASE_MAX;
else *ph_error = g_error;
Updated_phase = 1; /* signal update */
}
temp->fbkCnt = 0;
temp->refCnt = 0;
}
void update_pid(struct DmaCntDef volatile * temp)
{
/* update outer loop PID */
//uint16_t hDurationms = 20; /* ? what are units ? */
//int16_t hFinalSpeed = 200; /* ? what are units ? */
//MC_ProgramSpeedRampMotor1( hFinalSpeed, hDurationms ); /* void MC_ProgramSpeedRampMotor1( int16_t hFinalSpeed, uint16_t hDurationms ); */
}
static void Toggle_LED(void)
{
/* add definition */
HAL_GPIO_TogglePin(LED2_GPIO_Port, LED2_Pin);
}
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
/* while(1) */
{
/*
Toggle_LED();
HAL_Delay(1000);
*/
Error_Count++;
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
view raw main.c hosted with ❤ by GitHub

from file stm32f3xx_it.c,

/**
* @brief This function handles DMA1 channel1 global interrupt.
*/
void DMA1_Channel1_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel1_IRQn 0 */
/* USER CODE END DMA1_Channel1_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_tim4_ch1);
/* USER CODE BEGIN DMA1_Channel1_IRQn 1 */
buffer_jit[ptr_DmaCnt->buf_pos++] = TIM4->CCR1;
if(ptr_DmaCnt->buf_pos == BUFFER_SZ_JIT)
{
ptr_DmaCnt->buf_pos = 0;
ptr_DmaCnt->full = true;
}
(ptr_DmaCnt->refCnt)++;
if ((ptr_DmaCnt->fbkCnt + ptr_DmaCnt->refCnt) > 1)
{
/* call phase detect */
phase_detect(ptr_DmaCnt);
}
/* USER CODE END DMA1_Channel1_IRQn 1 */
}
/**
* @brief This function handles DMA1 channel4 global interrupt.
*/
void DMA1_Channel4_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel4_IRQn 0 */
/* USER CODE END DMA1_Channel4_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_tim4_ch2);
/* USER CODE BEGIN DMA1_Channel4_IRQn 1 */
(ptr_DmaCnt->fbkCnt)++;
if ((ptr_DmaCnt->fbkCnt + ptr_DmaCnt->refCnt) > 1)
{
/* call phase detect */
phase_detect(ptr_DmaCnt);
}
/* USER CODE END DMA1_Channel4_IRQn 1 */
}
view raw stm32f3xx_it.c hosted with ❤ by GitHub

Test Results

As a test the two inputs were connected together and driven with a pulse generator at 200Hz with a 50% duty cycle. The inputs are setup to both trigger on rising edges. In this mode it represents the two phase inputs being perfectly in phase. The result was the phase error (ph_error) reported on every sample was zero (0).

The second test was the same setup but changes the polarity of the fbk channel to trigger on the negative edge. The figure below shows the setup. Normally Ch1 and Ch2 inputs would be the two waveforms in panel (a) with the timer triggering on the rising edges. For this test we setup panel (b) with one waveform going to both channels. One channel triggers on the rising edge and the other channel on the falling edge. The red arrows indicate the resulting phase error magnitude.

Figure 2 - Test setup waveforms

In this setup changing the duty cycle directly adjusts the phase. I used the pulse generator set to a period of 1/200Hz and varied the pulse width. The table below is the pulse width (dt) and the measured phase error in clock counts. In this case the phase error was negative and it increased linearly to the maximum limit, PHASE_MAX, of 20000 counts. The resolution is 125ns.

Leave a Comment

Your email address will not be published. Required fields are marked *

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Scroll to Top