Skip to content

Commit fba8876

Browse files
author
Richard Unger
committed
STM32 refactored (but untested)
1 parent a149896 commit fba8876

File tree

1 file changed

+128
-51
lines changed

1 file changed

+128
-51
lines changed

src/drivers/hardware_specific/stm32_mcu.cpp

Lines changed: 128 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -14,15 +14,28 @@
1414
#define _ERROR_6PWM -1
1515

1616

17+
18+
typedef struct STM32DriverParams {
19+
HardwareTimer* timers[6];
20+
uint32_t channels[6];
21+
long pwm_frequency;
22+
float dead_zone;
23+
uint8_t interface_type;
24+
} STM32DriverParams;
25+
26+
27+
28+
29+
1730
// setting pwm to hardware pin - instead analogWrite()
18-
void _setPwm(int ulPin, uint32_t value, int resolution)
31+
void _setPwm(HardwareTimer *HT, uint32_t channel, uint32_t value, int resolution)
1932
{
20-
PinName pin = digitalPinToPinName(ulPin);
21-
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
22-
uint32_t index = get_timer_index(Instance);
23-
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
33+
// PinName pin = digitalPinToPinName(ulPin);
34+
// TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
35+
// uint32_t index = get_timer_index(Instance);
36+
// HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
2437

25-
uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
38+
//uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
2639
HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution);
2740
}
2841

@@ -129,7 +142,7 @@ void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,Ha
129142
}
130143

131144
// configure hardware 6pwm interface only one timer with inverted channels
132-
HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
145+
STM32DriverParams* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
133146
{
134147

135148
#if !defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
@@ -139,6 +152,12 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
139152
PinName vlPinName = digitalPinToPinName(pinB_l);
140153
PinName whPinName = digitalPinToPinName(pinC_h);
141154
PinName wlPinName = digitalPinToPinName(pinC_l);
155+
uint32_t channel1 = STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM));
156+
uint32_t channel2 = STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM));
157+
uint32_t channel3 = STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM));
158+
uint32_t channel4 = STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM));
159+
uint32_t channel5 = STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM));
160+
uint32_t channel6 = STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM));
142161

143162
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM);
144163

@@ -153,12 +172,12 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
153172
}
154173
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
155174

156-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
157-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
158-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
159-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
160-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName);
161-
HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
175+
HT->setMode(channel1, TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
176+
HT->setMode(channel2, TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
177+
HT->setMode(channel3, TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
178+
HT->setMode(channel4, TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
179+
HT->setMode(channel5, TIMER_OUTPUT_COMPARE_PWM1, whPinName);
180+
HT->setMode(channel6, TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
162181

163182
// dead time is set in nanoseconds
164183
uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
@@ -177,9 +196,18 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
177196
HT->getHandle()->Instance->CNT = TIM1->ARR;
178197

179198
HT->resume();
180-
return HT;
199+
200+
STM32DriverParams* params = new STM32DriverParams {
201+
.timers = { HT },
202+
.channels = { channel1, channel3, channel5 },
203+
.pwm_frequency = PWM_freq,
204+
.dead_zone = dead_zone,
205+
.interface_type = _HARDWARE_6PWM
206+
};
207+
208+
return params;
181209
#else
182-
return nullptr; // return nothing
210+
return SIMPLEFOC_DRIVER_INIT_FAILED; // return nothing
183211
#endif
184212
}
185213

@@ -223,7 +251,7 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const
223251
// function setting the high pwm frequency to the supplied pins
224252
// - Stepper motor - 2PWM setting
225253
// - hardware speciffic
226-
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
254+
void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
227255
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
228256
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
229257
// center-aligned frequency is uses two periods
@@ -233,13 +261,24 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
233261
HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB);
234262
// allign the timers
235263
_alignPWMTimers(HT1, HT2, HT2);
264+
265+
uint32_t channel1 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM));
266+
uint32_t channel2 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM));
267+
268+
STM32DriverParams* params = new STM32DriverParams {
269+
.timers = { HT1, HT2 },
270+
.channels = { channel1, channel2 },
271+
.pwm_frequency = pwm_frequency
272+
};
273+
return params;
236274
}
237275

238276

277+
239278
// function setting the high pwm frequency to the supplied pins
240279
// - BLDC motor - 3PWM setting
241280
// - hardware speciffic
242-
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
281+
void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
243282
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
244283
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
245284
// center-aligned frequency is uses two periods
@@ -250,12 +289,25 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
250289
HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC);
251290
// allign the timers
252291
_alignPWMTimers(HT1, HT2, HT3);
292+
293+
uint32_t channel1 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM));
294+
uint32_t channel2 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM));
295+
uint32_t channel3 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM));
296+
297+
STM32DriverParams* params = new STM32DriverParams {
298+
.timers = { HT1, HT2, HT3 },
299+
.channels = { channel1, channel2, channel3 },
300+
.pwm_frequency = pwm_frequency
301+
};
302+
return params;
253303
}
254304

305+
306+
255307
// function setting the high pwm frequency to the supplied pins
256308
// - Stepper motor - 4PWM setting
257309
// - hardware speciffic
258-
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
310+
void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
259311
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
260312
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
261313
// center-aligned frequency is uses two periods
@@ -267,37 +319,51 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
267319
HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD);
268320
// allign the timers
269321
_alignPWMTimers(HT1, HT2, HT3, HT4);
322+
323+
uint32_t channel1 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM));
324+
uint32_t channel2 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM));
325+
uint32_t channel3 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM));
326+
uint32_t channel4 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinD), PinMap_PWM));
327+
328+
STM32DriverParams* params = new STM32DriverParams {
329+
.timers = { HT1, HT2, HT3, HT4 },
330+
.channels = { channel1, channel2, channel3, channel4 },
331+
.pwm_frequency = pwm_frequency
332+
};
333+
return params;
270334
}
271335

336+
337+
272338
// function setting the pwm duty cycle to the hardware
273339
// - Stepper motor - 2PWM setting
274340
//- hardware speciffic
275-
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
341+
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
276342
// transform duty cycle from [0,1] to [0,4095]
277-
_setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
278-
_setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
343+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
344+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
279345
}
280346

281347
// function setting the pwm duty cycle to the hardware
282348
// - BLDC motor - 3PWM setting
283349
//- hardware speciffic
284-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
350+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
285351
// transform duty cycle from [0,1] to [0,4095]
286-
_setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
287-
_setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
288-
_setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
352+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
353+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
354+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
289355
}
290356

291357

292358
// function setting the pwm duty cycle to the hardware
293359
// - Stepper motor - 4PWM setting
294360
//- hardware speciffic
295-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
361+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
296362
// transform duty cycle from [0,1] to [0,4095]
297-
_setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
298-
_setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
299-
_setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
300-
_setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
363+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
364+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
365+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
366+
_setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
301367
}
302368

303369

@@ -306,55 +372,66 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
306372
// Configuring PWM frequency, resolution and alignment
307373
// - BLDC driver - 6PWM setting
308374
// - hardware specific
309-
int _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){
375+
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){
310376
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
311377
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
312378
// center-aligned frequency is uses two periods
313379
pwm_frequency *=2;
314380

315381
// find configuration
316382
int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
383+
STM32DriverParams* params;
317384
// configure accordingly
318385
switch(config){
319386
case _ERROR_6PWM:
320-
return -1; // fail
321-
break;
387+
return SIMPLEFOC_DRIVER_INIT_FAILED;
322388
case _HARDWARE_6PWM:
323-
_initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
389+
params = _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
324390
break;
325391
case _SOFTWARE_6PWM:
326392
HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h);
327393
_initPinPWMLow(pwm_frequency, pinA_l);
328-
HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h);
394+
HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency, pinB_h);
329395
_initPinPWMLow(pwm_frequency, pinB_l);
330-
HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h);
396+
HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency, pinC_h);
331397
_initPinPWMLow(pwm_frequency, pinC_l);
332398
_alignPWMTimers(HT1, HT2, HT3);
399+
uint32_t channel1 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA_h), PinMap_PWM));
400+
uint32_t channel2 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA_l), PinMap_PWM));
401+
uint32_t channel3 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB_h), PinMap_PWM));
402+
uint32_t channel4 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB_l), PinMap_PWM));
403+
uint32_t channel5 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC_h), PinMap_PWM));
404+
uint32_t channel6 = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC_l), PinMap_PWM));
405+
params = new STM32DriverParams {
406+
.timers = { HT1, HT2, HT3 },
407+
.channels = { channel1, channel2, channel3, channel4, channel5, channel6 },
408+
.pwm_frequency = pwm_frequency,
409+
.dead_zone = dead_zone,
410+
.interface_type = _SOFTWARE_6PWM
411+
};
333412
break;
334413
}
335-
return 0; // success
414+
return params; // success
336415
}
337416

338417
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
339418
// - BLDC driver - 6PWM setting
340419
// - hardware specific
341-
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
342-
// find configuration
343-
int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
344-
// set pwm accordingly
345-
switch(config){
420+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
421+
switch(((STM32DriverParams*)params)->interface_type){
346422
case _HARDWARE_6PWM:
347-
_setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
348-
_setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
349-
_setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
423+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
424+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
425+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
350426
break;
351427
case _SOFTWARE_6PWM:
352-
_setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
353-
_setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
354-
_setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
355-
_setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
356-
_setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
357-
_setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
428+
float dead_zone = ((STM32DriverParams*)params)->dead_zone;
429+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
430+
_setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[1], _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
431+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[2], _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
432+
_setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[3], _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
433+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[4], _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
434+
_setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[5], _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
358435
break;
359436
}
360437
}

0 commit comments

Comments
 (0)