Skip to content

Commit 7b91728

Browse files
author
Richard Unger
committed
intermediate state - fixing problems
1 parent ebeef3b commit 7b91728

File tree

1 file changed

+64
-34
lines changed

1 file changed

+64
-34
lines changed

src/drivers/hardware_specific/stm32_mcu.cpp

Lines changed: 64 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -46,17 +46,19 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
4646
if (timer==NP)
4747
return NP;
4848
uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
49+
bool init = false;
4950
if (HardwareTimer_Handle[index] == NULL) {
5051
HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
5152
HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
5253
HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
54+
init = true;
5355
}
5456
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
5557
uint32_t channel = STM_PIN_CHANNEL(timer->function);
56-
HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, timer->pin);
57-
HT->setOverflow(PWM_freq, HERTZ_FORMAT);
5858
HT->pause();
59-
HT->refresh();
59+
if (init)
60+
HT->setOverflow(PWM_freq, HERTZ_FORMAT);
61+
HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, timer->pin);
6062
return HT;
6163
}
6264

@@ -67,8 +69,7 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
6769

6870

6971
// init high side pin
70-
HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, PinMap* timer)
71-
{
72+
HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, PinMap* timer) {
7273
return _initPinPWM(PWM_freq, timer);
7374
}
7475

@@ -77,31 +78,39 @@ HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, PinMap* timer)
7778
{
7879
uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
7980

81+
bool init = false;
8082
if (HardwareTimer_Handle[index] == NULL) {
8183
HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
8284
HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
8385
HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
84-
TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef();
85-
sConfigOC.OCMode = TIM_OCMODE_PWM2;
86-
sConfigOC.Pulse = 100;
87-
sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
88-
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
89-
#if defined(TIM_OCIDLESTATE_SET)
90-
sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
91-
#endif
92-
#if defined(TIM_OCNIDLESTATE_RESET)
93-
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
94-
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
95-
#endif
96-
uint32_t channel = STM_PIN_CHANNEL(timer->function);
97-
HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
86+
init = true;
9887
}
9988
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
10089
uint32_t channel = STM_PIN_CHANNEL(timer->function);
101-
HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, timer->pin);
102-
HT->setOverflow(PWM_freq, HERTZ_FORMAT);
90+
SIMPLEFOC_DEBUG("Configuring low timer ", (int)getTimerNumber(get_timer_index(HardwareTimer_Handle[index]->handle.Instance)));
91+
SIMPLEFOC_DEBUG("Configuring low channel ", (int)channel);
92+
93+
10394
HT->pause();
104-
HT->refresh();
95+
96+
if (init)
97+
HT->setOverflow(PWM_freq, HERTZ_FORMAT);
98+
// sets internal fields of HT, but we can't set polarity here
99+
HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, timer->pin);
100+
// set polarity, unfortunately we have to set these other fields too
101+
TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef();
102+
sConfigOC.OCMode = TIM_OCMODE_PWM2;
103+
sConfigOC.Pulse = __HAL_TIM_GET_COMPARE(&(HardwareTimer_Handle[index]->handle), HT->getChannel(channel));
104+
sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
105+
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
106+
#if defined(TIM_OCIDLESTATE_SET) // TODO check this flag, looks like G4 uses something else...
107+
sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
108+
#endif
109+
#if defined(TIM_OCNIDLESTATE_RESET) // TODO check this flag, looks like G4 uses something else...
110+
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
111+
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
112+
#endif
113+
HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
105114
return HT;
106115
}
107116

@@ -168,8 +177,10 @@ void _alignTimersNew() {
168177
timers[i]->refresh();
169178
}
170179

171-
for (int i=0; i<numTimers; i++)
180+
for (int i=0; i<numTimers; i++) {
181+
SIMPLEFOC_DEBUG("Resuming timer ", getTimerNumber(get_timer_index(timers[i]->getHandle()->Instance)));
172182
timers[i]->resume();
183+
}
173184

174185
}
175186

@@ -303,6 +314,9 @@ int scoreCombination(int numPins, PinMap* pinTimers[]) {
303314
&& STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(timerPinsUsed[i]->function))
304315
return -2; // bad combination - timer channel already used
305316
}
317+
318+
// TODO LPTIM and HRTIM should be ignored for now
319+
306320
// check for inverted channels
307321
if (numPins < 6) {
308322
for (int i=0; i<numPins; i++) {
@@ -345,6 +359,21 @@ int scoreCombination(int numPins, PinMap* pinTimers[]) {
345359
&& STM_PIN_CHANNEL(pinTimers[4]->function) == STM_PIN_CHANNEL(pinTimers[5]->function)
346360
&& STM_PIN_INVERTED(pinTimers[1]->function) && STM_PIN_INVERTED(pinTimers[3]->function) && STM_PIN_INVERTED(pinTimers[5]->function)) {
347361
// hardware 6pwm, score <10
362+
363+
// TODO F37xxx doesn't support dead-time insertion, it has no TIM1/TIM8
364+
// F301, F302 --> 6 channels, but only 1-3 have dead-time insertion
365+
// TIM2/TIM3/TIM4/TIM5 don't do dead-time insertion
366+
// TIM15/TIM16/TIM17 do dead-time insertion only on channel 1
367+
368+
// TODO check these defines
369+
#if defined(STM32F4xx_HAL_TIM_H) || defined(STM32F3xx_HAL_TIM_H) || defined(STM32F2xx_HAL_TIM_H) || defined(STM32F1xx_HAL_TIM_H) || defined(STM32F100_HAL_TIM_H) || defined(STM32FG0x1_HAL_TIM_H) || defined(STM32G0x0_HAL_TIM_H)
370+
if (STM_PIN_CHANNEL(pinTimers[0]->function)>3 || STM_PIN_CHANNEL(pinTimers[2]->function)>3 || STM_PIN_CHANNEL(pinTimers[4]->function)>3 )
371+
return -8; // channel 4 does not have dead-time insertion
372+
#endif
373+
#ifdef STM32G4xx_HAL_TIM_H
374+
if (STM_PIN_CHANNEL(pinTimers[0]->function)>4 || STM_PIN_CHANNEL(pinTimers[2]->function)>4 || STM_PIN_CHANNEL(pinTimers[4]->function)>4 )
375+
return -8; // channels 5 & 6 do not have dead-time insertion
376+
#endif
348377
}
349378
else {
350379
// check for inverted low-side channels
@@ -622,7 +651,7 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, vo
622651
// Configuring PWM frequency, resolution and alignment
623652
// - BLDC driver - 6PWM setting
624653
// - hardware specific
625-
void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
654+
void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
626655
if (numTimerPinsUsed+6 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
627656
SIMPLEFOC_DEBUG("STM32: ERR: too many pins used");
628657
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
@@ -650,7 +679,7 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
650679
HardwareTimer* HT4 = _initPinPWMLow(pwm_frequency, pinTimers[3]);
651680
HardwareTimer* HT5 = _initPinPWMHigh(pwm_frequency, pinTimers[4]);
652681
HardwareTimer* HT6 = _initPinPWMLow(pwm_frequency, pinTimers[5]);
653-
_alignPWMTimers(HT1, HT2, HT3);
682+
//_alignPWMTimers(HT1, HT2, HT3);
654683
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
655684
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
656685
uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
@@ -665,9 +694,10 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
665694
.interface_type = _SOFTWARE_6PWM
666695
};
667696
}
668-
if (params>=0) {
697+
if (score>=0) {
669698
for (int i=0; i<6; i++)
670699
timerPinsUsed[numTimerPinsUsed++] = pinTimers[i];
700+
_alignTimersNew();
671701
}
672702
return params; // success
673703
}
@@ -679,21 +709,21 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
679709
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
680710
// - BLDC driver - 6PWM setting
681711
// - hardware specific
682-
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
712+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
683713
switch(((STM32DriverParams*)params)->interface_type){
684714
case _HARDWARE_6PWM:
685715
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
686716
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
687717
_setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
688718
break;
689719
case _SOFTWARE_6PWM:
690-
float dead_zone = ((STM32DriverParams*)params)->dead_zone;
691-
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
692-
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[1], _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
693-
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[2], _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
694-
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[3], _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
695-
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[4], _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
696-
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[5], _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
720+
float dead_zone = ((STM32DriverParams*)params)->dead_zone / 2.0f;
721+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _constrain(dc_a + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
722+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[1], _constrain(dc_a - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
723+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[2], _constrain(dc_b + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
724+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[3], _constrain(dc_b - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
725+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[4], _constrain(dc_c + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
726+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[5], _constrain(dc_c - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
697727
break;
698728
}
699729
}

0 commit comments

Comments
 (0)