SimpleFOClibrary  2.1
esp32_mcu.cpp
Go to the documentation of this file.
1 #include "../hardware_api.h"
2 
3 #if defined(ESP_H)
4 
5 #include "driver/mcpwm.h"
6 #include "soc/mcpwm_reg.h"
7 #include "soc/mcpwm_struct.h"
8 
9 // empty motor slot
10 #define _EMPTY_SLOT -20
11 #define _TAKEN_SLOT -21
12 
13 // ABI bus frequency - would be better to take it from somewhere
14 // but I did nto find a good exposed variable
15 #define _MCPWM_FREQ 160e6
16 
17 // preferred pwm resolution default
18 #define _PWM_RES_DEF 2048
19 // min resolution
20 #define _PWM_RES_MIN 1500
21 // max resolution
22 #define _PWM_RES_MAX 3000
23 
24 // structure containing motor slot configuration
25 // this library supports up to 4 motors
26 typedef struct {
27  int pinA;
28  mcpwm_dev_t* mcpwm_num;
29  mcpwm_unit_t mcpwm_unit;
30  mcpwm_operator_t mcpwm_operator;
31  mcpwm_io_signals_t mcpwm_a;
32  mcpwm_io_signals_t mcpwm_b;
33  mcpwm_io_signals_t mcpwm_c;
34 } bldc_3pwm_motor_slots_t;
35 typedef struct {
36  int pin1A;
37  mcpwm_dev_t* mcpwm_num;
38  mcpwm_unit_t mcpwm_unit;
39  mcpwm_operator_t mcpwm_operator1;
40  mcpwm_operator_t mcpwm_operator2;
41  mcpwm_io_signals_t mcpwm_1a;
42  mcpwm_io_signals_t mcpwm_1b;
43  mcpwm_io_signals_t mcpwm_2a;
44  mcpwm_io_signals_t mcpwm_2b;
45 } stepper_4pwm_motor_slots_t;
46 typedef struct {
47  int pin1pwm;
48  mcpwm_dev_t* mcpwm_num;
49  mcpwm_unit_t mcpwm_unit;
50  mcpwm_operator_t mcpwm_operator;
51  mcpwm_io_signals_t mcpwm_a;
52  mcpwm_io_signals_t mcpwm_b;
53 } stepper_2pwm_motor_slots_t;
54 
55 typedef struct {
56  int pinAH;
57  mcpwm_dev_t* mcpwm_num;
58  mcpwm_unit_t mcpwm_unit;
59  mcpwm_operator_t mcpwm_operator1;
60  mcpwm_operator_t mcpwm_operator2;
61  mcpwm_io_signals_t mcpwm_ah;
62  mcpwm_io_signals_t mcpwm_bh;
63  mcpwm_io_signals_t mcpwm_ch;
64  mcpwm_io_signals_t mcpwm_al;
65  mcpwm_io_signals_t mcpwm_bl;
66  mcpwm_io_signals_t mcpwm_cl;
67 } bldc_6pwm_motor_slots_t;
68 
69 // define bldc motor slots array
70 bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = {
71  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A
72  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B
73  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A
74  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B
75  };
76 
77 // define stepper motor slots array
78 bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = {
79  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0
80  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0
81  };
82 
83 // define 4pwm stepper motor slots array
84 stepper_4pwm_motor_slots_t esp32_stepper_4pwm_motor_slots[2] = {
85  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0
86  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1
87  };
88 
89 // define 2pwm stepper motor slots array
90 stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4] = {
91  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 1st motor will be MCPWM0 channel A
92  {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B}, // 2nd motor will be MCPWM0 channel B
93  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 3rd motor will be MCPWM1 channel A
94  {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B
95  };
96 
97 // configuring high frequency pwm timer
98 // a lot of help from this post from Paul Gauld
99 // https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller
100 void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){
101 
102  mcpwm_config_t pwm_config;
103  pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave)
104  pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH
105  mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings
106  mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings
107  mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings
108 
109  if (_isset(dead_zone)){
110  // dead zone is configured
111  float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone;
112  mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);
113  mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);
114  mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);
115  }
116  _delay(100);
117 
118  mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0);
119  mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1);
120  mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2);
121 
122  // manual configuration due to the lack of config flexibility in mcpwm_init()
123  mcpwm_num->clk_cfg.prescale = 0;
124  // calculate prescaler and period
125  // step 1: calculate the prescaler using the default pwm resolution
126  // prescaler = bus_freq / (pwm_freq * default_pwm_res) - 1
127  int prescaler = ceil((double)_MCPWM_FREQ / (double)_PWM_RES_DEF / 2.0 / (double)pwm_frequency) - 1;
128  // constrain prescaler
129  prescaler = _constrain(prescaler, 0, 128);
130  // now calculate the real resolution timer period necessary (pwm resolution)
131  // pwm_res = bus_freq / (pwm_freq * (prescaler + 1))
132  int resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(prescaler + 1);
133  // if pwm resolution too low lower the prescaler
134  if(resolution_corrected < _PWM_RES_MIN && prescaler > 0 )
135  resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(--prescaler + 1);
136  resolution_corrected = _constrain(resolution_corrected, _PWM_RES_MIN, _PWM_RES_MAX);
137 
138  // set prescaler
139  mcpwm_num->timer[0].period.prescale = prescaler;
140  mcpwm_num->timer[1].period.prescale = prescaler;
141  mcpwm_num->timer[2].period.prescale = prescaler;
142  _delay(1);
143  //set period
144  mcpwm_num->timer[0].period.period = resolution_corrected;
145  mcpwm_num->timer[1].period.period = resolution_corrected;
146  mcpwm_num->timer[2].period.period = resolution_corrected;
147  _delay(1);
148  mcpwm_num->timer[0].period.upmethod = 0;
149  mcpwm_num->timer[1].period.upmethod = 0;
150  mcpwm_num->timer[2].period.upmethod = 0;
151  _delay(1);
152  //restart the timers
153  mcpwm_start(mcpwm_unit, MCPWM_TIMER_0);
154  mcpwm_start(mcpwm_unit, MCPWM_TIMER_1);
155  mcpwm_start(mcpwm_unit, MCPWM_TIMER_2);
156  _delay(1);
157 
158  mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0);
159  mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0);
160  mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0);
161  _delay(1);
162  mcpwm_num->timer[0].sync.out_sel = 1;
163  _delay(1);
164  mcpwm_num->timer[0].sync.out_sel = 0;
165 }
166 
167 // function setting the high pwm frequency to the supplied pins
168 // - Stepper motor - 2PWM setting
169 // - hardware speciffic
170 // supports Arudino/ATmega328, STM32 and ESP32
171 void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
172 
173  if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
174  else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
175 
176  stepper_2pwm_motor_slots_t m_slot = {};
177 
178  // determine which motor are we connecting
179  // and set the appropriate configuration parameters
180  int slot_num;
181  for(slot_num = 0; slot_num < 4; slot_num++){
182  if(esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm == _EMPTY_SLOT){ // put the new motor in the first empty slot
183  esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = pinA;
184  m_slot = esp32_stepper_2pwm_motor_slots[slot_num];
185  break;
186  }
187  }
188 
189  // disable all the slots with the same MCPWM
190  // disable 3pwm bldc motor which would go in the same slot
191  esp32_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT;
192  if( slot_num < 2 ){
193  // slot 0 of the 4pwm stepper
194  esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT;
195  // slot 0 of the 6pwm bldc
196  esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT;
197  }else{
198  // slot 1 of the stepper
199  esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT;
200  // slot 1 of the 6pwm bldc
201  esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT;
202  }
203  // configure pins
204  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA);
205  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB);
206 
207  // configure the timer
208  _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit);
209 
210 }
211 
212 
213 // function setting the high pwm frequency to the supplied pins
214 // - BLDC motor - 3PWM setting
215 // - hardware speciffic
216 // supports Arudino/ATmega328, STM32 and ESP32
217 void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
218 
219  if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
220  else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
221 
222  bldc_3pwm_motor_slots_t m_slot = {};
223 
224  // determine which motor are we connecting
225  // and set the appropriate configuration parameters
226  int slot_num;
227  for(slot_num = 0; slot_num < 4; slot_num++){
228  if(esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot
229  esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA;
230  m_slot = esp32_bldc_3pwm_motor_slots[slot_num];
231  break;
232  }
233  }
234  // disable all the slots with the same MCPWM
235  // disable 2pwm steppr motor which would go in the same slot
236  esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = _TAKEN_SLOT;
237  if( slot_num < 2 ){
238  // slot 0 of the 4pwm stepper
239  esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT;
240  // slot 0 of the 6pwm bldc
241  esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT;
242  }else{
243  // slot 1 of the stepper
244  esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT;
245  // slot 1 of the 6pwm bldc
246  esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT;
247  }
248  // configure pins
249  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA);
250  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB);
251  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC);
252 
253  // configure the timer
254  _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit);
255 
256 }
257 
258 
259 // function setting the high pwm frequency to the supplied pins
260 // - Stepper motor - 4PWM setting
261 // - hardware speciffic
262 void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
263 
264  if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
265  else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 50kHz max - centered pwm has twice lower frequency
266  stepper_4pwm_motor_slots_t m_slot = {};
267  // determine which motor are we connecting
268  // and set the appropriate configuration parameters
269  int slot_num;
270  for(slot_num = 0; slot_num < 2; slot_num++){
271  if(esp32_stepper_4pwm_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot
272  esp32_stepper_4pwm_motor_slots[slot_num].pin1A = pinA;
273  m_slot = esp32_stepper_4pwm_motor_slots[slot_num];
274  break;
275  }
276  }
277  // disable all the slots with the same MCPWM
278  if( slot_num == 0 ){
279  // slots 0 and 1 of the 3pwm bldc
280  esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT;
281  esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT;
282  // slots 0 and 1 of the 2pwm stepper taken
283  esp32_stepper_2pwm_motor_slots[0].pin1pwm = _TAKEN_SLOT;
284  esp32_stepper_2pwm_motor_slots[1].pin1pwm = _TAKEN_SLOT;
285  // slot 0 of the 6pwm bldc
286  esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT;
287  }else{
288  // slots 2 and 3 of the 3pwm bldc
289  esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT;
290  esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT;
291  // slots 2 and 3 of the 2pwm stepper taken
292  esp32_stepper_2pwm_motor_slots[2].pin1pwm = _TAKEN_SLOT;
293  esp32_stepper_2pwm_motor_slots[3].pin1pwm = _TAKEN_SLOT;
294  // slot 1 of the 6pwm bldc
295  esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT;
296  }
297 
298  // configure pins
299  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA);
300  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB);
301  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC);
302  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD);
303 
304  // configure the timer
305  _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit);
306 }
307 
308 // function setting the pwm duty cycle to the hardware
309 // - Stepper motor - 2PWM setting
310 // - hardware speciffic
311 // ESP32 uses MCPWM
312 void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
313  // determine which motor slot is the motor connected to
314  for(int i = 0; i < 4; i++){
315  if(esp32_stepper_2pwm_motor_slots[i].pin1pwm == pinA){ // if motor slot found
316  // se the PWM on the slot timers
317  // transform duty cycle from [0,1] to [0,100]
318  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);
319  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);
320  break;
321  }
322  }
323 }
324 
325 // function setting the pwm duty cycle to the hardware
326 // - BLDC motor - 3PWM setting
327 // - hardware speciffic
328 // ESP32 uses MCPWM
329 void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
330  // determine which motor slot is the motor connected to
331  for(int i = 0; i < 4; i++){
332  if(esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found
333  // se the PWM on the slot timers
334  // transform duty cycle from [0,1] to [0,100]
335  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);
336  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);
337  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);
338  break;
339  }
340  }
341 }
342 
343 // function setting the pwm duty cycle to the hardware
344 // - Stepper motor - 4PWM setting
345 // - hardware speciffic
346 // ESP32 uses MCPWM
347 void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
348  // determine which motor slot is the motor connected to
349  for(int i = 0; i < 2; i++){
350  if(esp32_stepper_4pwm_motor_slots[i].pin1A == pin1A){ // if motor slot found
351  // se the PWM on the slot timers
352  // transform duty cycle from [0,1] to [0,100]
353  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);
354  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);
355  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);
356  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);
357  break;
358  }
359  }
360 }
361 
362 // Configuring PWM frequency, resolution and alignment
363 // - BLDC driver - 6PWM setting
364 // - hardware specific
365 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){
366 
367  if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
368  else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
369  bldc_6pwm_motor_slots_t m_slot = {};
370  // determine which motor are we connecting
371  // and set the appropriate configuration parameters
372  int slot_num;
373  for(slot_num = 0; slot_num < 2; slot_num++){
374  if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot
375  esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h;
376  m_slot = esp32_bldc_6pwm_motor_slots[slot_num];
377  break;
378  }
379  }
380  // if no slots available
381  if(slot_num >= 2) return -1;
382 
383  // disable all the slots with the same MCPWM
384  if( slot_num == 0 ){
385  // slots 0 and 1 of the 3pwm bldc
386  esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT;
387  esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT;
388  // slot 0 of the 6pwm bldc
389  esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT;
390  }else{
391  // slots 2 and 3 of the 3pwm bldc
392  esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT;
393  esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT;
394  // slot 1 of the 6pwm bldc
395  esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT;
396  }
397 
398  // configure pins
399  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h);
400  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l);
401  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h);
402  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l);
403  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h);
404  mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l);
405 
406  // configure the timer
407  _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone);
408  // return
409  return 0;
410 }
411 
412 // Function setting the duty cycle to the pwm pin (ex. analogWrite())
413 // - BLDC driver - 6PWM setting
414 // - hardware specific
415 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){
416  // determine which motor slot is the motor connected to
417  for(int i = 0; i < 2; i++){
418  if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found
419  // se the PWM on the slot timers
420  // transform duty cycle from [0,1] to [0,100.0]
421  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0);
422  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0);
423  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0);
424  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0);
425  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0);
426  mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0);
427  break;
428  }
429  }
430 }
431 #endif
_configure3PWM
void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
Definition: drivers/hardware_specific/generic_mcu.cpp:31
_configure4PWM
void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:40
NOT_SET
#define NOT_SET
Definition: foc_utils.h:27
_constrain
#define _constrain(amt, low, high)
Definition: foc_utils.h:9
_isset
#define _isset(a)
Definition: foc_utils.h:11
_delay
void _delay(unsigned long ms)
Definition: time_utils.cpp:5
_writeDutyCycle3PWM
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC)
Definition: drivers/hardware_specific/generic_mcu.cpp:64
_writeDutyCycle2PWM
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:55
_writeDutyCycle4PWM
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:74
_writeDutyCycle6PWM
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)
Definition: drivers/hardware_specific/generic_mcu.cpp:86
_configure6PWM
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)
Definition: drivers/hardware_specific/generic_mcu.cpp:47
_configure2PWM
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:23