Skip to content

Commit cc3393d

Browse files
author
Richard Unger
committed
esp32 driver refactor (untested)
1 parent 514f1c1 commit cc3393d

File tree

1 file changed

+88
-55
lines changed

1 file changed

+88
-55
lines changed

src/drivers/hardware_specific/esp32_mcu.cpp

Lines changed: 88 additions & 55 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ typedef struct {
3535
mcpwm_io_signals_t mcpwm_b;
3636
mcpwm_io_signals_t mcpwm_c;
3737
} bldc_3pwm_motor_slots_t;
38+
3839
typedef struct {
3940
int pin1A;
4041
mcpwm_dev_t* mcpwm_num;
@@ -46,6 +47,7 @@ typedef struct {
4647
mcpwm_io_signals_t mcpwm_2a;
4748
mcpwm_io_signals_t mcpwm_2b;
4849
} stepper_4pwm_motor_slots_t;
50+
4951
typedef struct {
5052
int pin1pwm;
5153
mcpwm_dev_t* mcpwm_num;
@@ -69,6 +71,8 @@ typedef struct {
6971
mcpwm_io_signals_t mcpwm_cl;
7072
} bldc_6pwm_motor_slots_t;
7173

74+
75+
7276
// define bldc motor slots array
7377
bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = {
7478
{_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] = {
97101
{_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B
98102
};
99103

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+
100117
// configuring high frequency pwm timer
101118
// a lot of help from this post from Paul Gauld
102119
// 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
180197
// - Stepper motor - 2PWM setting
181198
// - hardware speciffic
182199
// 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) {
184201
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
185202
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
186203

@@ -218,14 +235,20 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
218235
// configure the timer
219236
_configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit);
220237

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;
221244
}
222245

223246

224247
// function setting the high pwm frequency to the supplied pins
225248
// - BLDC motor - 3PWM setting
226249
// - hardware speciffic
227250
// 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) {
229252
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
230253
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
231254

@@ -263,13 +286,19 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
263286
// configure the timer
264287
_configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit);
265288

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;
266295
}
267296

268297

269298
// function setting the high pwm frequency to the supplied pins
270299
// - Stepper motor - 4PWM setting
271300
// - 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) {
273302
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
274303
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
275304
stepper_4pwm_motor_slots_t m_slot = {};
@@ -312,66 +341,68 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
312341

313342
// configure the timer
314343
_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;
315352
}
316353

354+
355+
356+
317357
// function setting the pwm duty cycle to the hardware
318358
// - Stepper motor - 2PWM setting
319359
// - hardware speciffic
320360
// 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);
332366
}
333367

368+
369+
370+
334371
// function setting the pwm duty cycle to the hardware
335372
// - BLDC motor - 3PWM setting
336373
// - hardware speciffic
337374
// 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);
350381
}
351382

383+
384+
385+
352386
// function setting the pwm duty cycle to the hardware
353387
// - Stepper motor - 4PWM setting
354388
// - hardware speciffic
355389
// 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);
369397
}
370398

399+
400+
401+
371402
// Configuring PWM frequency, resolution and alignment
372403
// - BLDC driver - 6PWM setting
373404
// - 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){
375406

376407
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
377408
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
387418
}
388419
}
389420
// if no slots available
390-
if(slot_num >= 2) return -1;
421+
if(slot_num >= 2) return SIMPLEFOC_DRIVER_INIT_FAILED;
391422

392423
// disable all the slots with the same MCPWM
393424
if( slot_num == 0 ){
@@ -415,26 +446,28 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
415446
// configure the timer
416447
_configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone);
417448
// 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;
419454
}
420455

456+
457+
458+
421459
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
422460
// - BLDC driver - 6PWM setting
423461
// - 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){
428463
// se the PWM on the slot timers
429464
// 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);
439471
}
472+
440473
#endif

0 commit comments

Comments
 (0)