STM32 Center-Aligned and 6PWM

@robin2906 - it’s great that you are experienced in stm32. I’m in the process of trying to get 6PWM working with stm32. My plan is to use complementary timer (CH1 CH1N) with optional deadtime using countermode_center_up_down. I suspect our current 3PWM implementation is not center aligned either. If you can offer me help that would be appreciated!

Yep your right in simplefoc the default configuration is left aligned, it’s not optimized concerning the commutation loose and motor noise but it’s not so bad.

If you use left aligned PWM you need almost 20 kHz PWM in order to keep motor noise inaudible by a human. But you switch transistor 20 000 time per seconds.

If you use center aligned pwm 10 kHz is enough in order to keep motor noise inaudible by an human but you switch transistor only 10 000 times per second so your commutation loss are lowered.

Maybe can you open a post for the 6PWM question please? It will be simpler for the community to find about this if we open a dedicated thread no? I will post a timer initialization code for 6 pwm with dead time. Also you can give me the MCU reference you use in the thread it will be useful :slight_smile:

@robin2906 I’ve moved the above two message to this new thread.

The aim of this thread is:

  1. To investigate/improve stm32 PWM for 3PWM - as you point out our current implementation is left aligned
  2. To investigate/implement 6PWM for stm32. i.e. 3 phase each having a LIN and HIN. This may cover some of the following:
    a) Driver deadtime protection - e.g. l6387 driver found in my drone kit (link below))
    b) Software deatime protection - e.g. for circuits with no driver IC - just mosfets
  3. To investigate/implement what STM32 notched center align. This is where all 3 phases are pullled low for a short period at same time to allow BEMF current sensing, see section 4.2 of stm32-crossseries-timer-overview-stmicroelectronics application note.

I’ll primarily be using my stm32g431 drone kit for 6pwm and can also test 3pwm on my stm32f107 (storm32 gimbal board).

1 Like

I’ve found an example project specifically for this board provided by stm as part of their x-cube-mcsdk. I can generate LL or HAL code from it using CubeMX (so I’ve chosen LL as this is likely compatible with stm32duino). @robin2906 - I’m looking at how the timers are setup - e.g. countermode/repititioncounters/deadtime. I suspect this will be very similar to the timer initialization code you offered to provide!
Update: Switching to the HAL generated code - seems to be more compatible with stm32duino

1 Like

Hey @Owen_Williams,

I have dug into the stm32duino library today and I’ve found a way to center the PWM and invert it with some dead time. I will be implementing it to the library in next days.
Basically we will no longer use the analogWrite() function.

The only big downside of this code, the only limit really is that each pair of low-high side of pwm pins has to belong to the same timer. Basically just make sure your INx_H and INx_L are the channels from the same timer. This should be easy to find in the datasheet. The rest should work fine.

Here is an example for my ST32Nucleo stm32f401re.

With this code I plan to replace all the code both for 3pwm and 6pwm in the library :smiley:

Here is the example code I’ve been using to test:

//
// Slow and precise BLDC motor driver using SPWM and SVPWM modulation
// Part of code used from http://elabz.com/
// (c) 2015 Ignas Gramba www.berryjam.eu
//
 

const int EN1 = 13;

const int IN1_H = 7;
const int IN1_L = PB13;
const int IN2_H = 8;
const int IN2_L = PB14;
const int IN3_H = 6;
const int IN3_L = 3;


// SPWM (Sine Wave)
const int pwmSin[] = {127, 138, 149, 160, 170, 181, 191, 200, 209, 217, 224, 231, 237, 242, 246, 250, 252, 254, 254, 254, 252, 250, 246, 242, 237, 231, 224, 217, 209, 200, 191, 181, 170, 160, 149, 138, 127, 116, 105, 94, 84, 73, 64, 54, 45, 37, 30, 23, 17, 12, 8, 4, 2, 0, 0, 0, 2, 4, 8, 12, 17, 23, 30, 37, 45, 54, 64, 73, 84, 94, 105, 116 };

int currentStepA;
int currentStepB;
int currentStepC;
int sineArraySize;
int increment = 0;
boolean direct = 1; // direction true=forward, false=backward

//////////////////////////////////////////////////////////////////////////////


HardwareTimer *MyTim1, *MyTim2, *MyTim3,*MyTim4;
uint32_t channel1,channel2,channel3; 
void setup() {
  Serial.begin(115200);
        
  pinMode(EN1, OUTPUT); 
  digitalWrite(EN1, HIGH);

  MyTim1 = pwm_init_high(IN1_H,50000);
  //MyTim1 = pwm_init_low(IN1_L,50000);
  MyTim1 = pwm_init_high(IN1_L,50000);
  MyTim2 = pwm_init_high(IN2_H,50000);
  //MyTim2 = pwm_init_low(IN2_L,50000);
  MyTim2 = pwm_init_high(IN2_L,50000);
  MyTim3 = pwm_init_high(IN3_H,50000);
  MyTim3 = pwm_init_low(IN3_L,50000);
  pwm_align(MyTim1,MyTim2,MyTim3);


  // sine table init
  sineArraySize = sizeof(pwmSin)/sizeof(int); // Find lookup table size
  int phaseShift = sineArraySize / 3;         // Find phase shift and initial A, B C phase values
  currentStepA = 0;
  currentStepB = currentStepA + phaseShift;
  currentStepC = currentStepB + phaseShift;

  sineArraySize--; // Convert from array Size to last PWM array number
}

//////////////////////////////////////////////////////////////////////////////

void loop() {

  pwm_set(IN1_H, pwmSin[currentStepA], 8);
  pwm_set(IN1_L, constrain(pwmSin[currentStepA]+10,0,255), 8);
  pwm_set(IN2_H, pwmSin[currentStepB], 8);
  pwm_set(IN2_L, constrain(pwmSin[currentStepB]+10,0,255), 8);
  pwm_set(IN3_H, pwmSin[currentStepC], 8);
  pwm_set(IN3_L, constrain(pwmSin[currentStepC]+10,0,255), 8);


  // sine table for next loop
  currentStepA = currentStepA == sineArraySize ? 0: currentStepA+1;
  currentStepB = currentStepB == sineArraySize ? 0: currentStepB+1;
  currentStepC = currentStepC == sineArraySize ? 0: currentStepC+1;
  
  /// Control speed by this delay
  delay(1);
  Serial.println(currentStepA);
}


// init high side pin
HardwareTimer* pwm_init_high(int ulPin, uint32_t PWM_freq)
{
  PinName pin = digitalPinToPinName(ulPin);
  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
  
  uint32_t index = get_timer_index(Instance);
  if (HardwareTimer_Handle[index] == NULL) {
    HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
    HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
    HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
  }
  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
  HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin);
  HT->setOverflow(PWM_freq, HERTZ_FORMAT);
  HT->pause();
  HT->refresh();
  return HT;
}

// init low side pin
HardwareTimer* pwm_init_low(int ulPin, uint32_t PWM_freq)
{
  PinName pin = digitalPinToPinName(ulPin);
  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
  uint32_t index = get_timer_index(Instance);
    
  if (HardwareTimer_Handle[index] == NULL) {
    HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
    HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
    HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
    TIM_OC_InitTypeDef sConfigOC = {0};
    sConfigOC.OCMode = TIM_OCMODE_PWM2;
    sConfigOC.Pulse = 100;
    sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
    sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW;
    sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
    sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
    sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
    uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
    HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
  }
  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
  HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin);
  HT->setOverflow(PWM_freq, HERTZ_FORMAT);
  HT->pause();
  HT->refresh();
  return HT;
}

// align the timers to end the init
void pwm_align(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3)
{
  HT1->pause();
  HT1->refresh();
  HT2->pause();
  HT2->refresh();
  HT3->pause();
  HT3->refresh();
  HT1->resume();
  HT2->resume();
  HT3->resume();
}


// setting pwm to hardware pin - instead analogWrite()
void pwm_set(int ulPin, uint32_t value, int resolution)
{
  PinName pin = digitalPinToPinName(ulPin);
  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
  uint32_t index = get_timer_index(Instance);
  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);

  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
  HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution);
}

The code is still not bulletproof, but I’ve spent on it some time and check the results on the scope so I am pretty confident. :smiley:
As long as the timers are good the rest should be fine.

Let me know if you can test it with your setup. And I’ll let you know once I have a library version using it.

1 Like

Antun. I got your code working on my board after a little brain surgery!

#include <Arduino.h>
//
// Slow and precise BLDC motor driver using SPWM and SVPWM modulation
// Part of code used from http://elabz.com/
// (c) 2015 Ignas Gramba www.berryjam.eu
//
 
#define TX PB3
#define RX PB4
HardwareSerial Serial1(RX, TX);


const int EN1 = PC6;

const int IN1_H = PHASE_UH;
const int IN1_L = PHASE_UL;
const int IN2_H = PHASE_VH;
const int IN2_L = PHASE_VL;
const int IN3_H = PHASE_WH;
const int IN3_L = PHASE_WL;


// SPWM (Sine Wave)
const int pwmSin[] = {127, 138, 149, 160, 170, 181, 191, 200, 209, 217, 224, 231, 237, 242, 246, 250, 252, 254, 254, 254, 252, 250, 246, 242, 237, 231, 224, 217, 209, 200, 191, 181, 170, 160, 149, 138, 127, 116, 105, 94, 84, 73, 64, 54, 45, 37, 30, 23, 17, 12, 8, 4, 2, 0, 0, 0, 2, 4, 8, 12, 17, 23, 30, 37, 45, 54, 64, 73, 84, 94, 105, 116 };

int currentStepA;
int currentStepB;
int currentStepC;
int sineArraySize;
int increment = 0;
boolean direct = 1; // direction true=forward, false=backward

//////////////////////////////////////////////////////////////////////////////


HardwareTimer *MyTim1, *MyTim2, *MyTim3,*MyTim4;
uint32_t channel1,channel2,channel3; 



// init high side pin
// HardwareTimer* pwm_init_high(int ulPin, uint32_t PWM_freq)
// {
//   PinName pin = digitalPinToPinName(ulPin);
//   TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
 
//   uint32_t index = get_timer_index(Instance);
//   Serial1.println("timer: "); Serial1.println(index);


//   if (HardwareTimer_Handle[index] == NULL) {
//     HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
//     HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
//     HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
//   }
//   HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
//   uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
//   HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin);
//   HT->setOverflow(PWM_freq, HERTZ_FORMAT);
//   HT->pause();
//   HT->refresh();
//   return HT;
// }


HardwareTimer* pwm_init_high_and_low(int uhPin, int ulPin, int vhPin, int vlPin, int whPin, int wlPin,uint32_t PWM_freq)
{
  PinName uhPinName = digitalPinToPinName(uhPin);
  PinName ulPinName = digitalPinToPinName(ulPin);
  PinName vhPinName = digitalPinToPinName(vhPin);
  PinName vlPinName = digitalPinToPinName(vlPin);
  PinName whPinName = digitalPinToPinName(whPin);
  PinName wlPinName = digitalPinToPinName(wlPin);

  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM);
 
  uint32_t index = get_timer_index(Instance);
  Serial1.println("timer: "); Serial1.println(index);


  if (HardwareTimer_Handle[index] == NULL) {
    HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM));
    HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
    HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
    ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT);
  }
  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
  uint32_t channelU = STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM));
  uint32_t channelV = STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM));
  uint32_t channelW = STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM));

  
  HT->setMode(channelU, TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
  HT->setMode(channelU, TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
  HT->setMode(channelV, TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
  HT->setMode(channelV, TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
  HT->setMode(channelW, TIMER_OUTPUT_COMPARE_PWM1, whPinName);
  HT->setMode(channelW, TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
  
  LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, 100); // deadtime is non linear!
  LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N);
  HT->pause();
  HT->refresh();
  return HT;
}


// init low side pin
// HardwareTimer* pwm_init_low(int ulPin, uint32_t PWM_freq)
// {
//   PinName pin = digitalPinToPinName(ulPin);
//   TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
//   uint32_t index = get_timer_index(Instance);

//   Serial1.println("timer: "); Serial1.println(index);

//   if (HardwareTimer_Handle[index] == NULL) {
//     HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
//     HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
//     HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
//     TIM_OC_InitTypeDef sConfigOC = {0};
//     sConfigOC.OCMode = TIM_OCMODE_PWM2;
//     sConfigOC.Pulse = 100;
//     sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
//     sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW;
//     sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
//     sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
//     sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
//     uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
//     HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
//   }
//   HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
//   uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
//   HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin);
//   HT->setOverflow(PWM_freq, HERTZ_FORMAT);
//   HT->pause();
//   HT->refresh();
//   return HT;
// }

// align the timers to end the init
void pwm_align(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3)
{
  // HT1->pause();
  // HT1->refresh();
  // HT2->pause();
  // HT2->refresh();
  // HT3->pause();
  // HT3->refresh();
  HT1->resume();
  // HT2->resume();
  // HT3->resume();
}


// setting pwm to hardware pin - instead analogWrite()
void pwm_set(int ulPin, uint32_t value, int resolution)
{
  PinName pin = digitalPinToPinName(ulPin);
  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
  uint32_t index = get_timer_index(Instance);
  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);

  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
  Serial1.print(value); Serial1.print(" ");
  HT->setCaptureCompare(channel, value/6, (TimerCompareFormat_t)resolution);
}

#define constrain2(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(0):(amt)))

void setup() {
  Serial1.begin(115200);
  delay(2000);

  Serial1.println("setup");

  // uint32_t ch = 
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_UH)));
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_UL)));
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_VH)));
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_VL)));
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_WH)));
  Serial1.println(get_pwm_channel(digitalPinToPinName(PHASE_WL)));
  

        
  pinMode(EN1, OUTPUT); 
  digitalWrite(EN1, HIGH);

  MyTim1 = pwm_init_high_and_low(IN1_H, IN1_L, IN2_H, IN2_L, IN3_H, IN3_L, 50000);
  // MyTim1 = pwm_init_low(IN1_L,50000);
  // MyTim2 = pwm_init_high_and_low(IN2_H,IN2_L, 50000);
  // MyTim2 = pwm_init_low(IN2_L,50000);
  // MyTim3 = pwm_init_high_and_low(IN3_H, IN2_L, 50000);
  // MyTim3 = pwm_init_low(IN3_L,50000);
  pwm_align(MyTim1,MyTim2,MyTim3);
  delay(1000);

  // sine table init
  sineArraySize = sizeof(pwmSin)/sizeof(int); // Find lookup table size
  int phaseShift = sineArraySize / 3;         // Find phase shift and initial A, B C phase values
  currentStepA = 0;
  currentStepB = currentStepA + phaseShift;
  currentStepC = currentStepB + phaseShift;

  Serial1.print(currentStepA); Serial1.print(" ");
  Serial1.print(currentStepB); Serial1.print(" ");
  Serial1.print(currentStepC); Serial1.print(" ");

  sineArraySize--; // Convert from array Size to last PWM array number
}

//////////////////////////////////////////////////////////////////////////////

void loop() {
    Serial1.print(currentStepA); Serial1.print(" ");
    Serial1.print(currentStepB); Serial1.print(" ");
    Serial1.print(currentStepC); Serial1.print(" ");

  pwm_set(IN1_H, pwmSin[currentStepA], 8);
  // pwm_set(IN1_L, constrain(pwmSin[currentStepA]+10,0,255), 8);
  pwm_set(IN2_H, pwmSin[currentStepB], 8);
  // pwm_set(IN2_L, constrain(pwmSin[currentStepB]+10,0,255), 8);
  pwm_set(IN3_H, pwmSin[currentStepC], 8);
  // pwm_set(IN3_L, constrain(pwmSin[currentStepC]+10,0,255), 8);
    Serial1.println();

  // sine table for next loop
  currentStepA = constrain2(currentStepA + 1,0,sineArraySize);
  currentStepB = constrain2(currentStepB + 1,0,sineArraySize);
  currentStepC = constrain2(currentStepC + 1,0,sineArraySize);
  
  /// Control speed by this delay
  delay(1);
}

My board pretty much limits me to a complementary timer approach CH1 CH1N CH2 CH2N CH3 CH3N. This meant that I had to take a quite different approach. Deadtime for example is handled by the stm32 timer. It is super hacky and doesn’t deserve to work!

Hello,
Is it really mandatory to provide a 6 PWM (inverted signal between INxH and INxL ) with a DRV8323, or DRV8302, and so on…

If we only use the center-aligned INxH and then in linking between them the INxL pins, to do a enable ? It would be the simplest, no ? it save pin outputs…

Your thoughts ?

We have tested a bunch of drivers in 3pwm mode e.g some drv83xx drivers. Some of these also support 3pwn and 6pwm modes.

My board only supports 6pwm. Also this 6pwm work might allow control of 6 logic level mosfets directly connected to mcu!

Ok, I understand quite.
It is good idea