8
8
9
9
// empty motor slot
10
10
#define _EMPTY_SLOT -20
11
+ #define _TAKEN_SLOT -21
11
12
12
13
// structure containing motor slot configuration
13
14
// this library supports up to 4 motors
@@ -19,7 +20,7 @@ typedef struct {
19
20
mcpwm_io_signals_t mcpwm_a;
20
21
mcpwm_io_signals_t mcpwm_b;
21
22
mcpwm_io_signals_t mcpwm_c;
22
- } bldc_motor_slots_t ;
23
+ } bldc_3pwm_motor_slots_t ;
23
24
typedef struct {
24
25
int pin1A;
25
26
mcpwm_dev_t * mcpwm_num;
@@ -32,8 +33,22 @@ typedef struct {
32
33
mcpwm_io_signals_t mcpwm_2b;
33
34
} stepper_motor_slots_t ;
34
35
36
+ typedef struct {
37
+ int pinAH;
38
+ mcpwm_dev_t * mcpwm_num;
39
+ mcpwm_unit_t mcpwm_unit;
40
+ mcpwm_operator_t mcpwm_operator1;
41
+ mcpwm_operator_t mcpwm_operator2;
42
+ mcpwm_io_signals_t mcpwm_ah;
43
+ mcpwm_io_signals_t mcpwm_bh;
44
+ mcpwm_io_signals_t mcpwm_ch;
45
+ mcpwm_io_signals_t mcpwm_al;
46
+ mcpwm_io_signals_t mcpwm_bl;
47
+ mcpwm_io_signals_t mcpwm_cl;
48
+ } bldc_6pwm_motor_slots_t ;
49
+
35
50
// define bldc motor slots array
36
- bldc_motor_slots_t esp32_bldc_motor_slots [4 ] = {
51
+ bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots [4 ] = {
37
52
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A
38
53
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B
39
54
{_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A
@@ -42,8 +57,14 @@ bldc_motor_slots_t esp32_bldc_motor_slots[4] = {
42
57
43
58
// define stepper motor slots array
44
59
stepper_motor_slots_t esp32_stepper_motor_slots[2 ] = {
45
- {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1
46
60
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0
61
+ {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1
62
+ };
63
+
64
+ // define stepper motor slots array
65
+ bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2 ] = {
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 MCPWM0
47
68
};
48
69
49
70
// configuring high frequency pwm timer
@@ -102,18 +123,30 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
102
123
if (!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000 ; // default frequency 20khz - centered pwm has twice lower frequency
103
124
else pwm_frequency = _constrain (2 *pwm_frequency, 0 , 60000 ); // constrain to 30kHz max - centered pwm has twice lower frequency
104
125
105
- bldc_motor_slots_t m_slot = {};
126
+ bldc_3pwm_motor_slots_t m_slot = {};
106
127
107
128
// determine which motor are we connecting
108
129
// and set the appropriate configuration parameters
109
- for (int i = 0 ; i < 4 ; i++){
110
- if (esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot
111
- esp32_bldc_motor_slots[i].pinA = pinA;
112
- m_slot = esp32_bldc_motor_slots[i];
130
+ int slot_num;
131
+ for (slot_num = 0 ; slot_num < 4 ; slot_num++){
132
+ if (esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot
133
+ esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA;
134
+ m_slot = esp32_bldc_3pwm_motor_slots[slot_num];
113
135
break ;
114
136
}
115
137
}
116
-
138
+ // disable all the slots with the same MCPWM
139
+ if ( slot_num < 2 ){
140
+ // slot 0 of the stepper
141
+ esp32_stepper_motor_slots[0 ].pin1A = _TAKEN_SLOT;
142
+ // slot 0 of the 6pwm bldc
143
+ esp32_bldc_6pwm_motor_slots[0 ].pinAH = _TAKEN_SLOT;
144
+ }else {
145
+ // slot 1 of the stepper
146
+ esp32_stepper_motor_slots[1 ].pin1A = _TAKEN_SLOT;
147
+ // slot 1 of the 6pwm bldc
148
+ esp32_bldc_6pwm_motor_slots[1 ].pinAH = _TAKEN_SLOT;
149
+ }
117
150
// configure pins
118
151
mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_a , pinA);
119
152
mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_b , pinB);
@@ -135,14 +168,29 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
135
168
stepper_motor_slots_t m_slot = {};
136
169
// determine which motor are we connecting
137
170
// and set the appropriate configuration parameters
138
- for (int i = 0 ; i < 2 ; i++){
139
- if (esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot
140
- esp32_stepper_motor_slots[i].pin1A = pinA;
141
- m_slot = esp32_stepper_motor_slots[i];
171
+ int slot_num;
172
+ for (slot_num = 0 ; slot_num < 2 ; slot_num++){
173
+ if (esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot
174
+ esp32_stepper_motor_slots[slot_num].pin1A = pinA;
175
+ m_slot = esp32_stepper_motor_slots[slot_num];
142
176
break ;
143
177
}
144
178
}
145
-
179
+ // disable all the slots with the same MCPWM
180
+ if ( slot_num == 0 ){
181
+ // slots 0 and 1 of the 3pwm bldc
182
+ esp32_bldc_3pwm_motor_slots[0 ].pinA = _TAKEN_SLOT;
183
+ esp32_bldc_3pwm_motor_slots[1 ].pinA = _TAKEN_SLOT;
184
+ // slot 0 of the 6pwm bldc
185
+ esp32_bldc_6pwm_motor_slots[0 ].pinAH = _TAKEN_SLOT;
186
+ }else {
187
+ // slots 2 and 3 of the 3pwm bldc
188
+ esp32_bldc_3pwm_motor_slots[2 ].pinA = _TAKEN_SLOT;
189
+ esp32_bldc_3pwm_motor_slots[3 ].pinA = _TAKEN_SLOT;
190
+ // slot 1 of the 6pwm bldc
191
+ esp32_bldc_6pwm_motor_slots[1 ].pinAH = _TAKEN_SLOT;
192
+ }
193
+
146
194
// configure pins
147
195
mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_1a , pinA);
148
196
mcpwm_gpio_init (m_slot.mcpwm_unit , m_slot.mcpwm_1b , pinB);
@@ -153,20 +201,19 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
153
201
_configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit );
154
202
}
155
203
156
-
157
204
// function setting the pwm duty cycle to the hardware
158
205
// - BLDC motor - 3PWM setting
159
206
// - hardware speciffic
160
207
// ESP32 uses MCPWM
161
208
void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
162
209
// determine which motor slot is the motor connected to
163
210
for (int i = 0 ; i < 4 ; i++){
164
- if (esp32_bldc_motor_slots [i].pinA == pinA){ // if motor slot found
211
+ if (esp32_bldc_3pwm_motor_slots [i].pinA == pinA){ // if motor slot found
165
212
// se the PWM on the slot timers
166
213
// transform duty cycle from [0,1] to [0,2047]
167
- esp32_bldc_motor_slots [i].mcpwm_num ->channel [0 ].cmpr_value [esp32_bldc_motor_slots [i].mcpwm_operator ].cmpr_val = dc_a*2047 ;
168
- esp32_bldc_motor_slots [i].mcpwm_num ->channel [1 ].cmpr_value [esp32_bldc_motor_slots [i].mcpwm_operator ].cmpr_val = dc_b*2047 ;
169
- esp32_bldc_motor_slots [i].mcpwm_num ->channel [2 ].cmpr_value [esp32_bldc_motor_slots [i].mcpwm_operator ].cmpr_val = dc_c*2047 ;
214
+ esp32_bldc_3pwm_motor_slots [i].mcpwm_num ->channel [0 ].cmpr_value [esp32_bldc_3pwm_motor_slots [i].mcpwm_operator ].cmpr_val = dc_a*2047 ;
215
+ esp32_bldc_3pwm_motor_slots [i].mcpwm_num ->channel [1 ].cmpr_value [esp32_bldc_3pwm_motor_slots [i].mcpwm_operator ].cmpr_val = dc_b*2047 ;
216
+ esp32_bldc_3pwm_motor_slots [i].mcpwm_num ->channel [2 ].cmpr_value [esp32_bldc_3pwm_motor_slots [i].mcpwm_operator ].cmpr_val = dc_c*2047 ;
170
217
break ;
171
218
}
172
219
}
@@ -195,13 +242,75 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
195
242
// - BLDC driver - 6PWM setting
196
243
// - hardware specific
197
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){
198
- return -1 ;
245
+
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
+
285
+ // configure the timer
286
+ _configureTimerFrequency (pwm_frequency, m_slot.mcpwm_num , m_slot.mcpwm_unit );
287
+ // return
288
+ return 0 ;
199
289
}
200
290
201
291
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
202
292
// - BLDC driver - 6PWM setting
203
293
// - hardware specific
204
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){
205
- return ;
295
+ // determine which motor slot is the motor connected to
296
+ for (int i = 0 ; i < 2 ; i++){
297
+ if (esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found
298
+ // se the PWM on the slot timers
299
+ // transform duty cycle from [0,1] to [0,100.0]
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
+ }
206
315
}
207
316
#endif
0 commit comments