@@ -46,17 +46,19 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
46
46
if (timer==NP)
47
47
return NP;
48
48
uint32_t index = get_timer_index ((TIM_TypeDef*)timer->peripheral );
49
+ bool init = false ;
49
50
if (HardwareTimer_Handle[index] == NULL ) {
50
51
HardwareTimer_Handle[index]->__this = new HardwareTimer ((TIM_TypeDef*)timer->peripheral );
51
52
HardwareTimer_Handle[index]->handle .Init .CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
52
53
HAL_TIM_Base_Init (&(HardwareTimer_Handle[index]->handle ));
54
+ init = true ;
53
55
}
54
56
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this );
55
57
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);
58
58
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 );
60
62
return HT;
61
63
}
62
64
@@ -67,8 +69,7 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
67
69
68
70
69
71
// init high side pin
70
- HardwareTimer* _initPinPWMHigh (uint32_t PWM_freq, PinMap* timer)
71
- {
72
+ HardwareTimer* _initPinPWMHigh (uint32_t PWM_freq, PinMap* timer) {
72
73
return _initPinPWM (PWM_freq, timer);
73
74
}
74
75
@@ -77,31 +78,39 @@ HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, PinMap* timer)
77
78
{
78
79
uint32_t index = get_timer_index ((TIM_TypeDef*)timer->peripheral );
79
80
81
+ bool init = false ;
80
82
if (HardwareTimer_Handle[index] == NULL ) {
81
83
HardwareTimer_Handle[index]->__this = new HardwareTimer ((TIM_TypeDef*)timer->peripheral );
82
84
HardwareTimer_Handle[index]->handle .Init .CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
83
85
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 ;
98
87
}
99
88
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this );
100
89
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
+
103
94
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);
105
114
return HT;
106
115
}
107
116
@@ -168,8 +177,10 @@ void _alignTimersNew() {
168
177
timers[i]->refresh ();
169
178
}
170
179
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 )));
172
182
timers[i]->resume ();
183
+ }
173
184
174
185
}
175
186
@@ -303,6 +314,9 @@ int scoreCombination(int numPins, PinMap* pinTimers[]) {
303
314
&& STM_PIN_CHANNEL (pinTimers[i]->function ) == STM_PIN_CHANNEL (timerPinsUsed[i]->function ))
304
315
return -2 ; // bad combination - timer channel already used
305
316
}
317
+
318
+ // TODO LPTIM and HRTIM should be ignored for now
319
+
306
320
// check for inverted channels
307
321
if (numPins < 6 ) {
308
322
for (int i=0 ; i<numPins; i++) {
@@ -345,6 +359,21 @@ int scoreCombination(int numPins, PinMap* pinTimers[]) {
345
359
&& STM_PIN_CHANNEL (pinTimers[4 ]->function ) == STM_PIN_CHANNEL (pinTimers[5 ]->function )
346
360
&& STM_PIN_INVERTED (pinTimers[1 ]->function ) && STM_PIN_INVERTED (pinTimers[3 ]->function ) && STM_PIN_INVERTED (pinTimers[5 ]->function )) {
347
361
// 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
348
377
}
349
378
else {
350
379
// 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
622
651
// Configuring PWM frequency, resolution and alignment
623
652
// - BLDC driver - 6PWM setting
624
653
// - 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){
626
655
if (numTimerPinsUsed+6 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
627
656
SIMPLEFOC_DEBUG (" STM32: ERR: too many pins used" );
628
657
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
@@ -650,7 +679,7 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
650
679
HardwareTimer* HT4 = _initPinPWMLow (pwm_frequency, pinTimers[3 ]);
651
680
HardwareTimer* HT5 = _initPinPWMHigh (pwm_frequency, pinTimers[4 ]);
652
681
HardwareTimer* HT6 = _initPinPWMLow (pwm_frequency, pinTimers[5 ]);
653
- _alignPWMTimers (HT1, HT2, HT3);
682
+ // _alignPWMTimers(HT1, HT2, HT3);
654
683
uint32_t channel1 = STM_PIN_CHANNEL (pinTimers[0 ]->function );
655
684
uint32_t channel2 = STM_PIN_CHANNEL (pinTimers[1 ]->function );
656
685
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
665
694
.interface_type = _SOFTWARE_6PWM
666
695
};
667
696
}
668
- if (params >=0 ) {
697
+ if (score >=0 ) {
669
698
for (int i=0 ; i<6 ; i++)
670
699
timerPinsUsed[numTimerPinsUsed++] = pinTimers[i];
700
+ _alignTimersNew ();
671
701
}
672
702
return params; // success
673
703
}
@@ -679,21 +709,21 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
679
709
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
680
710
// - BLDC driver - 6PWM setting
681
711
// - 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){
683
713
switch (((STM32DriverParams*)params)->interface_type ){
684
714
case _HARDWARE_6PWM:
685
715
_setPwm (((STM32DriverParams*)params)->timers [0 ], ((STM32DriverParams*)params)->channels [0 ], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
686
716
_setPwm (((STM32DriverParams*)params)->timers [2 ], ((STM32DriverParams*)params)->channels [2 ], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
687
717
_setPwm (((STM32DriverParams*)params)->timers [4 ], ((STM32DriverParams*)params)->channels [4 ], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
688
718
break ;
689
719
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);
697
727
break ;
698
728
}
699
729
}
0 commit comments