@@ -41,6 +41,34 @@ void _setPwm(HardwareTimer *HT, uint32_t channel, uint32_t value, int resolution
41
41
42
42
43
43
44
+ int getLLChannel (PinMap* timer) {
45
+ #if defined(TIM_CCER_CC1NE)
46
+ if (STM_PIN_INVERTED (timer->function )) {
47
+ switch (STM_PIN_CHANNEL (timer->function )) {
48
+ case 1 : return LL_TIM_CHANNEL_CH1N;
49
+ case 2 : return LL_TIM_CHANNEL_CH2N;
50
+ case 3 : return LL_TIM_CHANNEL_CH3N;
51
+ #if defined(LL_TIM_CHANNEL_CH4N)
52
+ case 4 : return LL_TIM_CHANNEL_CH4N;
53
+ #endif
54
+ default : return -1 ;
55
+ }
56
+ } else
57
+ #endif
58
+ {
59
+ switch (STM_PIN_CHANNEL (timer->function )) {
60
+ case 1 : return LL_TIM_CHANNEL_CH1;
61
+ case 2 : return LL_TIM_CHANNEL_CH2;
62
+ case 3 : return LL_TIM_CHANNEL_CH3;
63
+ case 4 : return LL_TIM_CHANNEL_CH4;
64
+ default : return -1 ;
65
+ }
66
+ }
67
+ return -1 ;
68
+ }
69
+
70
+
71
+
44
72
45
73
46
74
// init pin pwm
@@ -63,6 +91,9 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
63
91
if (init)
64
92
HT->setOverflow (PWM_freq, HERTZ_FORMAT);
65
93
HT->setMode (channel, TIMER_OUTPUT_COMPARE_PWM1, timer->pin );
94
+ #if SIMPLEFOC_PWM_ACTIVE_HIGH==false
95
+ LL_TIM_OC_SetPolarity (HT->getHandle ()->Instance , getLLChannel (timer), LL_TIM_OCPOLARITY_LOW);
96
+ #endif
66
97
#ifdef SIMPLEFOC_STM32_DEBUG
67
98
SIMPLEFOC_DEBUG (" STM32-DRV: Configuring high timer " , (int )getTimerNumber (get_timer_index (HardwareTimer_Handle[index]->handle .Instance )));
68
99
SIMPLEFOC_DEBUG (" STM32-DRV: Configuring high channel " , (int )channel);
@@ -78,7 +109,11 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
78
109
79
110
// init high side pin
80
111
HardwareTimer* _initPinPWMHigh (uint32_t PWM_freq, PinMap* timer) {
81
- return _initPinPWM (PWM_freq, timer);
112
+ HardwareTimer* HT = _initPinPWM (PWM_freq, timer);
113
+ #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false && SIMPLEFOC_PWM_ACTIVE_HIGH==true
114
+ LL_TIM_OC_SetPolarity (HT->getHandle ()->Instance , getLLChannel (timer), LL_TIM_OCPOLARITY_LOW);
115
+ #endif
116
+ return HT;
82
117
}
83
118
84
119
// init low side pin
@@ -107,6 +142,9 @@ HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, PinMap* timer)
107
142
HT->setOverflow (PWM_freq, HERTZ_FORMAT);
108
143
// sets internal fields of HT, but we can't set polarity here
109
144
HT->setMode (channel, TIMER_OUTPUT_COMPARE_PWM2, timer->pin );
145
+ #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
146
+ LL_TIM_OC_SetPolarity (HT->getHandle ()->Instance , getLLChannel (timer), LL_TIM_OCPOLARITY_LOW);
147
+ #endif
110
148
return HT;
111
149
}
112
150
@@ -213,34 +251,6 @@ void _alignTimersNew() {
213
251
214
252
215
253
216
- int getLLChannel (PinMap* timer) {
217
- #if defined(TIM_CCER_CC1NE)
218
- if (STM_PIN_INVERTED (timer->function )) {
219
- switch (STM_PIN_CHANNEL (timer->function )) {
220
- case 1 : return LL_TIM_CHANNEL_CH1N;
221
- case 2 : return LL_TIM_CHANNEL_CH2N;
222
- case 3 : return LL_TIM_CHANNEL_CH3N;
223
- #if defined(LL_TIM_CHANNEL_CH4N)
224
- case 4 : return LL_TIM_CHANNEL_CH4N;
225
- #endif
226
- default : return -1 ;
227
- }
228
- } else
229
- #endif
230
- {
231
- switch (STM_PIN_CHANNEL (timer->function )) {
232
- case 1 : return LL_TIM_CHANNEL_CH1;
233
- case 2 : return LL_TIM_CHANNEL_CH2;
234
- case 3 : return LL_TIM_CHANNEL_CH3;
235
- case 4 : return LL_TIM_CHANNEL_CH4;
236
- default : return -1 ;
237
- }
238
- }
239
- return -1 ;
240
- }
241
-
242
-
243
-
244
254
245
255
// configure hardware 6pwm for a complementary pair of channels
246
256
STM32DriverParams* _initHardware6PWMPair (long PWM_freq, float dead_zone, PinMap* pinH, PinMap* pinL, STM32DriverParams* params, int paramsPos) {
@@ -278,8 +288,13 @@ STM32DriverParams* _initHardware6PWMPair(long PWM_freq, float dead_zone, PinMap*
278
288
uint32_t dead_time_ns = (float )(1e9f/PWM_freq)*dead_zone;
279
289
uint32_t dead_time = __LL_TIM_CALC_DEADTIME (SystemCoreClock, LL_TIM_GetClockDivision (HT->getHandle ()->Instance ), dead_time_ns);
280
290
LL_TIM_OC_SetDeadTime (HT->getHandle ()->Instance , dead_time); // deadtime is non linear!
291
+ #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false
292
+ LL_TIM_OC_SetPolarity (HT->getHandle ()->Instance , getLLChannel (pinH), LL_TIM_OCPOLARITY_LOW);
293
+ #endif
294
+ #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
295
+ LL_TIM_OC_SetPolarity (HT->getHandle ()->Instance , getLLChannel (pinL), LL_TIM_OCPOLARITY_LOW);
296
+ #endif
281
297
LL_TIM_CC_EnableChannel (HT->getHandle ()->Instance , getLLChannel (pinH) | getLLChannel (pinL));
282
-
283
298
HT->pause ();
284
299
285
300
params->timers [paramsPos] = HT;
@@ -496,7 +511,36 @@ int findBestTimerCombination(int numPins, int pins[], PinMap* pinTimers[]) {
496
511
497
512
498
513
514
+ void * _configure1PWM (long pwm_frequency, const int pinA) {
515
+ if (numTimerPinsUsed+1 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
516
+ SIMPLEFOC_DEBUG (" STM32-DRV: ERR: too many pins used" );
517
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
518
+ }
499
519
520
+ if ( !pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
521
+ else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
522
+ // center-aligned frequency is uses two periods
523
+ pwm_frequency *=2 ;
524
+
525
+ int pins[1 ] = { pinA };
526
+ PinMap* pinTimers[1 ] = { NP };
527
+ if (findBestTimerCombination (1 , pins, pinTimers)<0 )
528
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
529
+
530
+ HardwareTimer* HT1 = _initPinPWM (pwm_frequency, pinTimers[0 ]);\
531
+ // allign the timers
532
+ _alignTimersNew ();
533
+
534
+ uint32_t channel1 = STM_PIN_CHANNEL (pinTimers[0 ]->function );
535
+
536
+ STM32DriverParams* params = new STM32DriverParams {
537
+ .timers = { HT1 },
538
+ .channels = { channel1 },
539
+ .pwm_frequency = pwm_frequency
540
+ };
541
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[0 ];
542
+ return params;
543
+ }
500
544
501
545
502
546
@@ -629,6 +673,16 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
629
673
630
674
631
675
676
+ // function setting the pwm duty cycle to the hardware
677
+ // - DC motor - 1PWM setting
678
+ // - hardware speciffic
679
+ void _writeDutyCycle1PWM (float dc_a, void * params){
680
+ // transform duty cycle from [0,1] to [0,255]
681
+ _setPwm (((STM32DriverParams*)params)->timers [0 ], ((STM32DriverParams*)params)->channels [0 ], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
682
+ }
683
+
684
+
685
+
632
686
// function setting the pwm duty cycle to the hardware
633
687
// - Stepper motor - 2PWM setting
634
688
// - hardware speciffic
0 commit comments