@@ -35,6 +35,7 @@ typedef struct {
35
35
mcpwm_io_signals_t mcpwm_b;
36
36
mcpwm_io_signals_t mcpwm_c;
37
37
} bldc_3pwm_motor_slots_t ;
38
+
38
39
typedef struct {
39
40
int pin1A;
40
41
mcpwm_dev_t * mcpwm_num;
@@ -46,6 +47,7 @@ typedef struct {
46
47
mcpwm_io_signals_t mcpwm_2a;
47
48
mcpwm_io_signals_t mcpwm_2b;
48
49
} stepper_4pwm_motor_slots_t ;
50
+
49
51
typedef struct {
50
52
int pin1pwm;
51
53
mcpwm_dev_t * mcpwm_num;
@@ -69,6 +71,8 @@ typedef struct {
69
71
mcpwm_io_signals_t mcpwm_cl;
70
72
} bldc_6pwm_motor_slots_t ;
71
73
74
+
75
+
72
76
// define bldc motor slots array
73
77
bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4 ] = {
74
78
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A
@@ -97,6 +101,19 @@ stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4] = {
97
101
{_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B
98
102
};
99
103
104
+
105
+
106
+ typedef struct ESP32MCPWMDriverParams {
107
+ long pwm_frequency;
108
+ mcpwm_unit_t mcpwm_unit;
109
+ mcpwm_operator_t mcpwm_operator1;
110
+ mcpwm_operator_t mcpwm_operator2;
111
+ } ESP32MCPWMDriverParams;
112
+
113
+
114
+
115
+
116
+
100
117
// configuring high frequency pwm timer
101
118
// a lot of help from this post from Paul Gauld
102
119
// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller
@@ -180,7 +197,7 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm
180
197
// - Stepper motor - 2PWM setting
181
198
// - hardware speciffic
182
199
// supports Arudino/ATmega328, STM32 and ESP32
183
- void _configure2PWM (long pwm_frequency,const int pinA, const int pinB) {
200
+ void * _configure2PWM (long pwm_frequency, const int pinA, const int pinB) {
184
201
if (!pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
185
202
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 40kHz max
186
203
@@ -218,14 +235,20 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
218
235
// configure the timer
219
236
_configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit );
220
237
238
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams {
239
+ .pwm_frequency = pwm_frequency,
240
+ .mcpwm_unit = m_slot.mcpwm_unit ,
241
+ .mcpwm_operator1 = m_slot.mcpwm_operator
242
+ };
243
+ return params;
221
244
}
222
245
223
246
224
247
// function setting the high pwm frequency to the supplied pins
225
248
// - BLDC motor - 3PWM setting
226
249
// - hardware speciffic
227
250
// supports Arudino/ATmega328, STM32 and ESP32
228
- void _configure3PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC) {
251
+ void * _configure3PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC) {
229
252
if (!pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
230
253
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 40kHz max
231
254
@@ -263,13 +286,19 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
263
286
// configure the timer
264
287
_configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit );
265
288
289
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams {
290
+ .pwm_frequency = pwm_frequency,
291
+ .mcpwm_unit = m_slot.mcpwm_unit ,
292
+ .mcpwm_operator1 = m_slot.mcpwm_operator
293
+ };
294
+ return params;
266
295
}
267
296
268
297
269
298
// function setting the high pwm frequency to the supplied pins
270
299
// - Stepper motor - 4PWM setting
271
300
// - hardware speciffic
272
- void _configure4PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
301
+ void * _configure4PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
273
302
if (!pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
274
303
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 40kHz max
275
304
stepper_4pwm_motor_slots_t m_slot = {};
@@ -312,66 +341,68 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
312
341
313
342
// configure the timer
314
343
_configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit );
344
+
345
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams {
346
+ .pwm_frequency = pwm_frequency,
347
+ .mcpwm_unit = m_slot.mcpwm_unit ,
348
+ .mcpwm_operator1 = m_slot.mcpwm_operator1 ,
349
+ .mcpwm_operator2 = m_slot.mcpwm_operator2
350
+ };
351
+ return params;
315
352
}
316
353
354
+
355
+
356
+
317
357
// function setting the pwm duty cycle to the hardware
318
358
// - Stepper motor - 2PWM setting
319
359
// - hardware speciffic
320
360
// ESP32 uses MCPWM
321
- void _writeDutyCycle2PWM (float dc_a, float dc_b, int pinA, int pinB){
322
- // determine which motor slot is the motor connected to
323
- for (int i = 0 ; i < 4 ; i++){
324
- if (esp32_stepper_2pwm_motor_slots[i].pin1pwm == pinA){ // if motor slot found
325
- // se the PWM on the slot timers
326
- // transform duty cycle from [0,1] to [0,100]
327
- mcpwm_set_duty (esp32_stepper_2pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator , dc_a*100.0 );
328
- mcpwm_set_duty (esp32_stepper_2pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator , dc_b*100.0 );
329
- break ;
330
- }
331
- }
361
+ void _writeDutyCycle2PWM (float dc_a, float dc_b, void * params){
362
+ // se the PWM on the slot timers
363
+ // transform duty cycle from [0,1] to [0,100]
364
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_a*100.0 );
365
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_b*100.0 );
332
366
}
333
367
368
+
369
+
370
+
334
371
// function setting the pwm duty cycle to the hardware
335
372
// - BLDC motor - 3PWM setting
336
373
// - hardware speciffic
337
374
// ESP32 uses MCPWM
338
- void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
339
- // determine which motor slot is the motor connected to
340
- for (int i = 0 ; i < 4 ; i++){
341
- if (esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found
342
- // se the PWM on the slot timers
343
- // transform duty cycle from [0,1] to [0,100]
344
- mcpwm_set_duty (esp32_bldc_3pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator , dc_a*100.0 );
345
- mcpwm_set_duty (esp32_bldc_3pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator , dc_b*100.0 );
346
- mcpwm_set_duty (esp32_bldc_3pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_2, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator , dc_c*100.0 );
347
- break ;
348
- }
349
- }
375
+ void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, void * params){
376
+ // se the PWM on the slot timers
377
+ // transform duty cycle from [0,1] to [0,100]
378
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_a*100.0 );
379
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_b*100.0 );
380
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_2, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_c*100.0 );
350
381
}
351
382
383
+
384
+
385
+
352
386
// function setting the pwm duty cycle to the hardware
353
387
// - Stepper motor - 4PWM setting
354
388
// - hardware speciffic
355
389
// ESP32 uses MCPWM
356
- void _writeDutyCycle4PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
357
- // determine which motor slot is the motor connected to
358
- for (int i = 0 ; i < 2 ; i++){
359
- if (esp32_stepper_4pwm_motor_slots[i].pin1A == pin1A){ // if motor slot found
360
- // se the PWM on the slot timers
361
- // transform duty cycle from [0,1] to [0,100]
362
- mcpwm_set_duty (esp32_stepper_4pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1 , dc_1a*100.0 );
363
- mcpwm_set_duty (esp32_stepper_4pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1 , dc_1b*100.0 );
364
- mcpwm_set_duty (esp32_stepper_4pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2 , dc_2a*100.0 );
365
- mcpwm_set_duty (esp32_stepper_4pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2 , dc_2b*100.0 );
366
- break ;
367
- }
368
- }
390
+ void _writeDutyCycle4PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, void * params){
391
+ // se the PWM on the slot timers
392
+ // transform duty cycle from [0,1] to [0,100]
393
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_1a*100.0 );
394
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator1 , dc_1b*100.0 );
395
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator2 , dc_2a*100.0 );
396
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, ((ESP32MCPWMDriverParams*)params)->mcpwm_operator2 , dc_2b*100.0 );
369
397
}
370
398
399
+
400
+
401
+
371
402
// Configuring PWM frequency, resolution and alignment
372
403
// - BLDC driver - 6PWM setting
373
404
// - hardware specific
374
- 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){
405
+ 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){
375
406
376
407
if (!pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = 20000 ; // default frequency 20khz - centered pwm has twice lower frequency
377
408
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 40kHz max - centered pwm has twice lower frequency
@@ -387,7 +418,7 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
387
418
}
388
419
}
389
420
// if no slots available
390
- if (slot_num >= 2 ) return - 1 ;
421
+ if (slot_num >= 2 ) return SIMPLEFOC_DRIVER_INIT_FAILED ;
391
422
392
423
// disable all the slots with the same MCPWM
393
424
if ( slot_num == 0 ){
@@ -415,26 +446,28 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
415
446
// configure the timer
416
447
_configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit , dead_zone);
417
448
// return
418
- return 0 ;
449
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams {
450
+ .pwm_frequency = pwm_frequency,
451
+ .mcpwm_unit = m_slot.mcpwm_unit
452
+ };
453
+ return params;
419
454
}
420
455
456
+
457
+
458
+
421
459
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
422
460
// - BLDC driver - 6PWM setting
423
461
// - hardware specific
424
- 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){
425
- // determine which motor slot is the motor connected to
426
- for (int i = 0 ; i < 2 ; i++){
427
- if (esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found
462
+ void _writeDutyCycle6PWM (float dc_a, float dc_b, float dc_c, void * params){
428
463
// se the PWM on the slot timers
429
464
// transform duty cycle from [0,1] to [0,100.0]
430
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0 );
431
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0 );
432
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0 );
433
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0 );
434
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0 );
435
- mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0 );
436
- break ;
437
- }
438
- }
465
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0 );
466
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0 );
467
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0 );
468
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0 );
469
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0 );
470
+ mcpwm_set_duty (((ESP32MCPWMDriverParams*)params)->mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0 );
439
471
}
472
+
440
473
#endif
0 commit comments