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 ![]()
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. ![]()
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.