@@ -64,7 +64,7 @@ stepper_motor_slots_t esp32_stepper_motor_slots[2] = {
64
64
// define stepper motor slots array
65
65
bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2 ] = {
66
66
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0
67
- {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM1
67
+ {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0
68
68
};
69
69
70
70
// configuring high frequency pwm timer
@@ -238,126 +238,79 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
238
238
}
239
239
}
240
240
241
- // configuring high frequency pwm timer
242
- // https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller/log/184464-mcpwm-with-deadband
243
- void _configureTimerFrequency6PWM (long pwm_frequency, mcpwm_dev_t * mcpwm_num, mcpwm_unit_t mcpwm_unit){
244
-
245
- mcpwm_config_t pwm_config;
246
- pwm_config.frequency = 4000 ; // frequency = 20000Hz
247
- pwm_config.cmpr_a = 50.0 ; // duty cycle of PWMxA = 50.0%
248
- pwm_config.cmpr_b = 50.0 ; // duty cycle of PWMxB = 50.0%
249
- pwm_config.counter_mode = MCPWM_UP_COUNTER; // Up-down counter (triangle wave)
250
- pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH
251
- mcpwm_init (MCPWM_UNIT_0, MCPWM_TIMER_0, &pwm_config); // Configure PWM0A & PWM0B with above settings
252
- mcpwm_init (MCPWM_UNIT_0, MCPWM_TIMER_1, &pwm_config); // Configure PWM0A & PWM0B with above settings
253
- mcpwm_init (MCPWM_UNIT_0, MCPWM_TIMER_2, &pwm_config); // Configure PWM0A & PWM0B with above settings
254
-
255
- mcpwm_deadtime_enable (MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, 40 , 40 );
256
- mcpwm_deadtime_enable (MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, 40 , 40 );
257
- mcpwm_deadtime_enable (MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, 40 , 40 );
258
-
259
- mcpwm_sync_enable (MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0 );
260
- mcpwm_sync_enable (MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0 );
261
- mcpwm_sync_enable (MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0 );
262
-
263
- MCPWM0.timer [0 ].sync .out_sel = 1 ;
264
- delayMicroseconds (1000 );
265
- MCPWM0.timer [0 ].sync .out_sel = 0 ;
266
-
267
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, 50 );
268
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, 50 );
269
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_OPR_A, 50 );
270
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_OPR_B, 50 );
271
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_OPR_A, 50 );
272
- mcpwm_set_duty (MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_OPR_B, 50 );
273
- }
274
-
275
-
276
241
// Configuring PWM frequency, resolution and alignment
277
242
// - BLDC driver - 6PWM setting
278
243
// - hardware specific
279
244
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){
280
245
281
- // if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency
282
- // else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency
283
- // bldc_6pwm_motor_slots_t m_slot = {};
284
- // // determine which motor are we connecting
285
- // // and set the appropriate configuration parameters
286
- // int slot_num;
287
- // for(slot_num = 0; slot_num < 2; slot_num++){
288
- // if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot
289
- // esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h;
290
- // m_slot = esp32_bldc_6pwm_motor_slots[slot_num];
291
- // break;
292
- // }
293
- // }
294
- // // if no slots available
295
- // if(!m_slot.mcpwm_unit) return -1;
296
-
297
- // // disable all the slots with the same MCPWM
298
- // if( slot_num == 0 ){
299
- // // slots 0 and 1 of the 3pwm bldc
300
- // esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT;
301
- // esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT;
302
- // // slot 0 of the 6pwm bldc
303
- // esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT;
304
- // }else{
305
- // // slots 2 and 3 of the 3pwm bldc
306
- // esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT;
307
- // esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT;
308
- // // slot 1 of the 6pwm bldc
309
- // esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT;
310
- // }
311
-
312
- // // configure pins
313
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h);
314
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l);
315
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h);
316
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l);
317
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h);
318
- // mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l);
319
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM0A, pinA_h);
320
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM0B, pinA_l);
321
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM1A, pinB_h);
322
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM1B, pinB_l);
323
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM2A, pinC_h);
324
- mcpwm_gpio_init (MCPWM_UNIT_0, MCPWM2B, pinC_l);
246
+ if (!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000 ; // default frequency 20khz - centered pwm has twice lower frequency
247
+ else pwm_frequency = _constrain (2 *pwm_frequency, 0 , 60000 ); // constrain to 30kHz max - centered pwm has twice lower frequency
248
+ bldc_6pwm_motor_slots_t m_slot = {};
249
+ // determine which motor are we connecting
250
+ // and set the appropriate configuration parameters
251
+ int slot_num;
252
+ for (slot_num = 0 ; slot_num < 2 ; slot_num++){
253
+ if (esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot
254
+ esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h;
255
+ m_slot = esp32_bldc_6pwm_motor_slots[slot_num];
256
+ break ;
257
+ }
258
+ }
259
+ // if no slots available
260
+ if (!m_slot.mcpwm_unit ) return -1 ;
261
+
262
+ // disable all the slots with the same MCPWM
263
+ if ( slot_num == 0 ){
264
+ // slots 0 and 1 of the 3pwm bldc
265
+ esp32_bldc_3pwm_motor_slots[0 ].pinA = _TAKEN_SLOT;
266
+ esp32_bldc_3pwm_motor_slots[1 ].pinA = _TAKEN_SLOT;
267
+ // slot 0 of the 6pwm bldc
268
+ esp32_stepper_motor_slots[0 ].pin1A = _TAKEN_SLOT;
269
+ }else {
270
+ // slots 2 and 3 of the 3pwm bldc
271
+ esp32_bldc_3pwm_motor_slots[2 ].pinA = _TAKEN_SLOT;
272
+ esp32_bldc_3pwm_motor_slots[3 ].pinA = _TAKEN_SLOT;
273
+ // slot 1 of the 6pwm bldc
274
+ esp32_stepper_motor_slots[1 ].pin1A = _TAKEN_SLOT;
275
+ }
276
+
277
+ // configure pins
278
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_ah , pinA_h);
279
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_al , pinA_l);
280
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_bh , pinB_h);
281
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_bl , pinB_l);
282
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_ch , pinC_h);
283
+ mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_cl , pinC_l);
284
+
325
285
// configure the timer
326
- _configureTimerFrequency6PWM (pwm_frequency, 0 , 0 );
286
+ _configureTimerFrequency (pwm_frequency, m_slot. mcpwm_num , m_slot. mcpwm_unit );
327
287
// return
328
288
return 0 ;
329
289
}
330
290
331
-
332
291
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
333
292
// - BLDC driver - 6PWM setting
334
293
// - hardware specific
335
294
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){
336
295
// determine which motor slot is the motor connected to
337
- // for(int i = 0; i < 2; i++){
338
- // if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found
296
+ for (int i = 0 ; i < 2 ; i++){
297
+ if (esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found
339
298
// se the PWM on the slot timers
340
299
// transform duty cycle from [0,1] to [0,100.0]
341
- // float dc_ah = _constrain(dc_a - dead_zone/2.0 , 0, 1)*100.0;
342
- // float dc_bh = _constrain(dc_b - dead_zone/2.0 , 0, 1)*100.0;
343
- // float dc_ch = _constrain(dc_c - dead_zone/2.0 , 0, 1)*100.0;
344
- // float dc_al = _constrain(dc_a + dead_zone/2.0 , 0, 1)*100.0;
345
- // float dc_bl = _constrain(dc_b + dead_zone/2.0 , 0, 1)*100.0;
346
- // float dc_cl = _constrain(dc_c + dead_zone/2.0 , 0, 1)*100.0;
347
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0);
348
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0);
349
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0);
350
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0);
351
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0);
352
- // mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0);
353
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, 50);
354
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, 50);
355
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_OPR_A, 50);
356
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_1, MCPWM_OPR_B, 50);
357
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_OPR_A, 50);
358
- // mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_2, MCPWM_OPR_B, 50);
359
- // break;
360
- // }
361
- // }
300
+ float dc_ah = _constrain (dc_a - dead_zone/2.0 , 0 , 1 )*100.0 ;
301
+ float dc_bh = _constrain (dc_b - dead_zone/2.0 , 0 , 1 )*100.0 ;
302
+ float dc_ch = _constrain (dc_c - dead_zone/2.0 , 0 , 1 )*100.0 ;
303
+ float dc_al = _constrain (dc_a + dead_zone/2.0 , 0 , 1 )*100.0 ;
304
+ float dc_bl = _constrain (dc_b + dead_zone/2.0 , 0 , 1 )*100.0 ;
305
+ float dc_cl = _constrain (dc_c + dead_zone/2.0 , 0 , 1 )*100.0 ;
306
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_A, dc_ah);
307
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_0, MCPWM_OPR_B, dc_al);
308
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_A, dc_bh);
309
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_1, MCPWM_OPR_B, dc_bl);
310
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_A, dc_ch);
311
+ mcpwm_set_duty (esp32_bldc_6pwm_motor_slots[i].mcpwm_unit , MCPWM_TIMER_2, MCPWM_OPR_B, dc_cl);
312
+ break ;
313
+ }
314
+ }
362
315
}
363
316
#endif
0 commit comments