SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
drivers/hardware_specific/samd/samd_mcu.cpp
Go to the documentation of this file.
1
2
3
4#include "./samd_mcu.h"
5
6#if defined(_SAMD21_)||defined(_SAMD51_)||defined(_SAME51_)
7
8
9
10/**
11 * Global state
12 */
13tccConfiguration tccPinConfigurations[SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS];
14uint8_t numTccPinConfigurations = 0;
15bool SAMDClockConfigured = false;
16bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
17
18
19
20
21
22/**
23 * Attach the TCC to the pin
24 */
25bool attachTCC(tccConfiguration& tccConfig) {
26 if (numTccPinConfigurations>=SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS)
27 return false;
28 pinMode(tccConfig.pin, OUTPUT);
29
30 pinPeripheral(tccConfig.pin, tccConfig.peripheral);
31 tccPinConfigurations[numTccPinConfigurations++] = tccConfig;
32 return true;
33}
34
35
36
37
38
39int getPermutationNumber(int pins) {
40 int num = 1;
41 for (int i=0;i<pins;i++)
42 num *= NUM_PIO_TIMER_PERIPHERALS;
43 return num;
44}
45
46
47
48
49/**
50 * Check if the configuration is in use already.
51 */
52bool inUse(tccConfiguration& tccConfig) {
53 for (int i=0;i<numTccPinConfigurations;i++) {
54 if (tccPinConfigurations[i].tcc.chaninfo==tccConfig.tcc.chaninfo)
55 return true;
56 }
57 return false;
58}
59
60
61tccConfiguration* getTccPinConfiguration(uint8_t pin) {
62 for (int i=0;i<numTccPinConfigurations;i++)
63 if (tccPinConfigurations[i].pin==pin)
64 return &tccPinConfigurations[i];
65 return NULL;
66}
67
68
69
70
71
72/**
73 * Get the TCC channel associated with that pin
74 */
75tccConfiguration getTCCChannelNr(int pin, EPioType peripheral) {
76 tccConfiguration result;
77 result.pin = pin;
78 result.peripheral = peripheral;
79 result.tcc.tccn = -2;
80 result.tcc.chan = -2;
81 const PinDescription& pinDesc = g_APinDescription[pin];
82 struct wo_association& association = getWOAssociation(pinDesc.ulPort, pinDesc.ulPin);
83 if (association.port==NOT_A_PORT)
84 return result; // could not find the port/pin
85 if (peripheral==PIO_TIMER) {
86 result.tcc.chaninfo = association.tccE;
87 result.wo = association.woE;
88 }
89 else if (peripheral==PIO_TIMER_ALT) {
90 result.tcc.chaninfo = association.tccF;
91 result.wo = association.woF;
92 }
93#if defined(_SAMD51_)||defined(_SAME51_)
94 else if (peripheral==PIO_TCC_PDEC) {
95 result.tcc.chaninfo = association.tccG;
96 result.wo = association.woG;
97 }
98#endif
99 return result;
100}
101
102
103
104
105
106bool checkPeripheralPermutationSameTCC6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
107 if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
108 return false;
109
110 if (pinAh.tcc.tccn<0 || pinAh.tcc.tccn!=pinAl.tcc.tccn || pinAh.tcc.tccn!=pinBh.tcc.tccn || pinAh.tcc.tccn!=pinBl.tcc.tccn
111 || pinAh.tcc.tccn!=pinCh.tcc.tccn || pinAh.tcc.tccn!=pinCl.tcc.tccn || pinAh.tcc.tccn>=TCC_INST_NUM)
112 return false;
113
114 if (pinAh.tcc.chan==pinBh.tcc.chan || pinAh.tcc.chan==pinBl.tcc.chan || pinAh.tcc.chan==pinCh.tcc.chan || pinAh.tcc.chan==pinCl.tcc.chan)
115 return false;
116 if (pinBh.tcc.chan==pinCh.tcc.chan || pinBh.tcc.chan==pinCl.tcc.chan)
117 return false;
118 if (pinAl.tcc.chan==pinBh.tcc.chan || pinAl.tcc.chan==pinBl.tcc.chan || pinAl.tcc.chan==pinCh.tcc.chan || pinAl.tcc.chan==pinCl.tcc.chan)
119 return false;
120 if (pinBl.tcc.chan==pinCh.tcc.chan || pinBl.tcc.chan==pinCl.tcc.chan)
121 return false;
122
123 if (pinAh.tcc.chan!=pinAl.tcc.chan || pinBh.tcc.chan!=pinBl.tcc.chan || pinCh.tcc.chan!=pinCl.tcc.chan)
124 return false;
125 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo!=pinCl.wo)
126 return false;
127
128 return true;
129}
130
131
132
133
134bool checkPeripheralPermutationCompatible(tccConfiguration pins[], uint8_t num) {
135 for (int i=0;i<num;i++)
136 if (pins[i].tcc.tccn<0)
137 return false;
138 for (int i=0;i<num-1;i++)
139 for (int j=i+1;j<num;j++)
140 if (pins[i].tcc.chaninfo==pins[j].tcc.chaninfo)
141 return false;
142 for (int i=0;i<num;i++)
143 if (inUse(pins[i]))
144 return false;
145 return true;
146}
147
148
149
150
151
152bool checkPeripheralPermutationCompatible6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
153 // check we're valid PWM pins
154 if (pinAh.tcc.tccn<0 || pinAl.tcc.tccn<0 || pinBh.tcc.tccn<0 || pinBl.tcc.tccn<0 || pinCh.tcc.tccn<0 || pinCl.tcc.tccn<0)
155 return false;
156 // only TCC units for 6-PWM
157 if (pinAh.tcc.tccn>=TCC_INST_NUM || pinAl.tcc.tccn>=TCC_INST_NUM || pinBh.tcc.tccn>=TCC_INST_NUM
158 || pinBl.tcc.tccn>=TCC_INST_NUM || pinCh.tcc.tccn>=TCC_INST_NUM || pinCl.tcc.tccn>=TCC_INST_NUM)
159 return false;
160
161 // check we're not in use
162 if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
163 return false;
164
165 // check pins are all different tccs/channels
166 if (pinAh.tcc.chaninfo==pinBh.tcc.chaninfo || pinAh.tcc.chaninfo==pinBl.tcc.chaninfo || pinAh.tcc.chaninfo==pinCh.tcc.chaninfo || pinAh.tcc.chaninfo==pinCl.tcc.chaninfo)
167 return false;
168 if (pinAl.tcc.chaninfo==pinBh.tcc.chaninfo || pinAl.tcc.chaninfo==pinBl.tcc.chaninfo || pinAl.tcc.chaninfo==pinCh.tcc.chaninfo || pinAl.tcc.chaninfo==pinCl.tcc.chaninfo)
169 return false;
170 if (pinBh.tcc.chaninfo==pinCh.tcc.chaninfo || pinBh.tcc.chaninfo==pinCl.tcc.chaninfo)
171 return false;
172 if (pinBl.tcc.chaninfo==pinCh.tcc.chaninfo || pinBl.tcc.chaninfo==pinCl.tcc.chaninfo)
173 return false;
174
175 // check H/L pins are on same timer
176 if (pinAh.tcc.tccn!=pinAl.tcc.tccn || pinBh.tcc.tccn!=pinBl.tcc.tccn || pinCh.tcc.tccn!=pinCl.tcc.tccn)
177 return false;
178
179 // check H/L pins aren't on both the same timer and wo
180 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo==pinCl.wo)
181 return false;
182
183 return true;
184}
185
186
187
188
189
190int checkHardware6PWM(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
191 for (int i=0;i<64;i++) {
192 tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(i, 0));
193 tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(i, 1));
194 tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(i, 2));
195 tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(i, 3));
196 tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(i, 4));
197 tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(i, 5));
198 if (checkPeripheralPermutationSameTCC6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
199 return i;
200 }
201 return -1;
202}
203
204
205
206
207int checkSoftware6PWM(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
208 for (int i=0;i<64;i++) {
209 tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(i, 0));
210 tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(i, 1));
211 tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(i, 2));
212 tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(i, 3));
213 tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(i, 4));
214 tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(i, 5));
215 if (checkPeripheralPermutationCompatible6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
216 return i;
217 }
218 return -1;
219}
220
221
222
223int scorePermutation(tccConfiguration pins[], uint8_t num) {
224 uint32_t usedtccs = 0;
225 for (int i=0;i<num;i++)
226 usedtccs |= (1<<pins[i].tcc.tccn);
227 int score = 0;
228 for (int i=0;i<TCC_INST_NUM;i++){
229 if (usedtccs&0x1)
230 score+=1;
231 usedtccs = usedtccs>>1;
232 }
233 for (int i=0;i<TC_INST_NUM;i++){
234 if (usedtccs&0x1)
235 score+=(num+1);
236 usedtccs = usedtccs>>1;
237 }
238 return score;
239}
240
241
242
243
244
245
246
247
248int checkPermutations(uint8_t num, int pins[], bool (*checkFunc)(tccConfiguration[], uint8_t) ) {
249 tccConfiguration tccConfs[num];
250 int best = -1;
251 int bestscore = 1000000;
252 for (int i=0;i<(0x1<<num);i++) {
253 for (int j=0;j<num;j++)
254 tccConfs[j] = getTCCChannelNr(pins[j], getPeripheralOfPermutation(i, j));
255 if (checkFunc(tccConfs, num)) {
256 int score = scorePermutation(tccConfs, num);
257 if (score<bestscore) {
258 bestscore = score;
259 best = i;
260 }
261 }
262 }
263 return best;
264}
265
266
267
268
269
270
271
272/**
273 * Configuring PWM frequency, resolution and alignment
274 * - Stepper driver - 2PWM setting
275 * - hardware specific
276 *
277 * @param pwm_frequency - frequency in hertz - if applicable
278 * @param pinA pinA bldc driver
279 * @param pinB pinB bldc driver
280 */
281void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
282#ifdef SIMPLEFOC_SAMD_DEBUG
283 printAllPinInfos();
284#endif
285 int pins[2] = { pinA, pinB };
286 int compatibility = checkPermutations(2, pins, checkPeripheralPermutationCompatible);
287 if (compatibility<0) {
288 // no result!
289#ifdef SIMPLEFOC_SAMD_DEBUG
290 SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
291#endif
293 }
294
295 tccConfiguration tccConfs[2] = { getTCCChannelNr(pinA, getPeripheralOfPermutation(compatibility, 0)),
296 getTCCChannelNr(pinB, getPeripheralOfPermutation(compatibility, 1)) };
297
298
299#ifdef SIMPLEFOC_SAMD_DEBUG
300 SIMPLEFOC_DEBUG("SAMD: Found configuration: score=", scorePermutation(tccConfs, 2));
301 printTCCConfiguration(tccConfs[0]);
302 printTCCConfiguration(tccConfs[1]);
303#endif
304
305 // attach pins to timer peripherals
306 attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
307 attachTCC(tccConfs[1]);
308#ifdef SIMPLEFOC_SAMD_DEBUG
309 SIMPLEFOC_DEBUG("SAMD: Attached pins...");
310#endif
311
312 // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
313 // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
314 configureSAMDClock();
315
316 if (pwm_frequency==NOT_SET) {
317 // use default frequency
318 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
319 }
320
321 // configure the TCC (waveform, top-value, pre-scaler = frequency)
322 configureTCC(tccConfs[0], pwm_frequency);
323 configureTCC(tccConfs[1], pwm_frequency);
324 getTccPinConfiguration(pinA)->pwm_res = tccConfs[0].pwm_res;
325 getTccPinConfiguration(pinB)->pwm_res = tccConfs[1].pwm_res;
326#ifdef SIMPLEFOC_SAMD_DEBUG
327 SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
328#endif
329
330 SAMDHardwareDriverParams* params = new SAMDHardwareDriverParams {
331 .tccPinConfigurations = { getTccPinConfiguration(pinA), getTccPinConfiguration(pinB) },
332 .pwm_frequency = (uint32_t)pwm_frequency
333 }; // Someone with a stepper-setup who can test it?
334 return params;
335}
336
337
338
339
340
341
342
343
344
345
346
347
348/**
349 * Configuring PWM frequency, resolution and alignment
350 * - BLDC driver - 3PWM setting
351 * - hardware specific
352 *
353 * SAMD21 will support up to 2 BLDC motors in 3-PWM:
354 * one on TCC0 using 3 of the channels 0,1,2 or 3
355 * one on TCC3 using 3 of the channels 0,1,2 or 3
356 * i.e. 8 different pins can be used, but only 4 different signals (WO[x]) on those 8 pins
357 * WO[0] and WO[4] are the same
358 * WO[1] and WO[5] are the same
359 * WO[2] and WO[6] are the same
360 * WO[3] and WO[7] are the same
361 *
362 * If you're on the Arduino Nano33 IoT, please see the Nano33 IoT pinout diagram to see which TCC0/WO[x]
363 * signal is on which pin of the Nano. You can drive one motor on TCC0. For other boards, consult their documentation.
364 *
365 * Note:
366 * That's if we want to keep the signals strictly in sync.
367 *
368 * If we can accept out-of-sync PWMs on the different phases, we could drive up to 4 BLDCs in 3-PWM mode,
369 * using all the TCC channels. (TCC0 & TCC3 - 4 channels each, TCC1 & TCC2 - 2 channels each)
370 *
371 * All channels will use the same resolution, prescaler and clock, but they will have different start-times leading
372 * to misaligned signals.
373 *
374 *
375 * @param pwm_frequency - frequency in hertz - if applicable
376 * @param pinA pinA bldc driver
377 * @param pinB pinB bldc driver
378 * @param pinC pinC bldc driver
379 */
380void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
381#ifdef SIMPLEFOC_SAMD_DEBUG
382 printAllPinInfos();
383#endif
384 int pins[3] = { pinA, pinB, pinC };
385 int compatibility = checkPermutations(3, pins, checkPeripheralPermutationCompatible);
386 if (compatibility<0) {
387 // no result!
388#ifdef SIMPLEFOC_SAMD_DEBUG
389 SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
390#endif
392 }
393
394 tccConfiguration tccConfs[3] = { getTCCChannelNr(pinA, getPeripheralOfPermutation(compatibility, 0)),
395 getTCCChannelNr(pinB, getPeripheralOfPermutation(compatibility, 1)),
396 getTCCChannelNr(pinC, getPeripheralOfPermutation(compatibility, 2)) };
397
398
399#ifdef SIMPLEFOC_SAMD_DEBUG
400 SIMPLEFOC_DEBUG("SAMD: Found configuration: score=", scorePermutation(tccConfs, 3));
401 printTCCConfiguration(tccConfs[0]);
402 printTCCConfiguration(tccConfs[1]);
403 printTCCConfiguration(tccConfs[2]);
404#endif
405
406 // attach pins to timer peripherals
407 attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
408 attachTCC(tccConfs[1]);
409 attachTCC(tccConfs[2]);
410#ifdef SIMPLEFOC_SAMD_DEBUG
411 SIMPLEFOC_DEBUG("SAMD: Attached pins...");
412#endif
413
414 // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
415 // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
416 configureSAMDClock();
417
418 if (pwm_frequency==NOT_SET) {
419 // use default frequency
420 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
421 }
422
423 // configure the TCC (waveform, top-value, pre-scaler = frequency)
424 configureTCC(tccConfs[0], pwm_frequency);
425 configureTCC(tccConfs[1], pwm_frequency);
426 configureTCC(tccConfs[2], pwm_frequency);
427 getTccPinConfiguration(pinA)->pwm_res = tccConfs[0].pwm_res;
428 getTccPinConfiguration(pinB)->pwm_res = tccConfs[1].pwm_res;
429 getTccPinConfiguration(pinC)->pwm_res = tccConfs[2].pwm_res;
430#ifdef SIMPLEFOC_SAMD_DEBUG
431 SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
432#endif
433
434 return new SAMDHardwareDriverParams {
435 .tccPinConfigurations = { getTccPinConfiguration(pinA), getTccPinConfiguration(pinB), getTccPinConfiguration(pinC) },
436 .pwm_frequency = (uint32_t)pwm_frequency
437 };
438
439}
440
441
442
443
444
445
446
447
448/**
449 * Configuring PWM frequency, resolution and alignment
450 * - Stepper driver - 4PWM setting
451 * - hardware specific
452 *
453 * @param pwm_frequency - frequency in hertz - if applicable
454 * @param pin1A pin1A stepper driver
455 * @param pin1B pin1B stepper driver
456 * @param pin2A pin2A stepper driver
457 * @param pin2B pin2B stepper driver
458 */
459void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
460#ifdef SIMPLEFOC_SAMD_DEBUG
461 printAllPinInfos();
462#endif
463 int pins[4] = { pin1A, pin1B, pin2A, pin2B };
464 int compatibility = checkPermutations(4, pins, checkPeripheralPermutationCompatible);
465 if (compatibility<0) {
466 // no result!
467#ifdef SIMPLEFOC_SAMD_DEBUG
468 SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
469#endif
471 }
472
473 tccConfiguration tccConfs[4] = { getTCCChannelNr(pin1A, getPeripheralOfPermutation(compatibility, 0)),
474 getTCCChannelNr(pin1B, getPeripheralOfPermutation(compatibility, 1)),
475 getTCCChannelNr(pin2A, getPeripheralOfPermutation(compatibility, 2)),
476 getTCCChannelNr(pin2B, getPeripheralOfPermutation(compatibility, 3)) };
477
478
479#ifdef SIMPLEFOC_SAMD_DEBUG
480 SIMPLEFOC_DEBUG("SAMD: Found configuration: score=", scorePermutation(tccConfs, 4));
481 printTCCConfiguration(tccConfs[0]);
482 printTCCConfiguration(tccConfs[1]);
483 printTCCConfiguration(tccConfs[2]);
484 printTCCConfiguration(tccConfs[3]);
485#endif
486
487 // attach pins to timer peripherals
488 attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
489 attachTCC(tccConfs[1]);
490 attachTCC(tccConfs[2]);
491 attachTCC(tccConfs[3]);
492#ifdef SIMPLEFOC_SAMD_DEBUG
493 SIMPLEFOC_DEBUG("SAMD: Attached pins...");
494#endif
495
496 // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
497 // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
498 configureSAMDClock();
499
500 if (pwm_frequency==NOT_SET) {
501 // use default frequency
502 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
503 }
504
505 // configure the TCC (waveform, top-value, pre-scaler = frequency)
506 configureTCC(tccConfs[0], pwm_frequency);
507 configureTCC(tccConfs[1], pwm_frequency);
508 configureTCC(tccConfs[2], pwm_frequency);
509 configureTCC(tccConfs[3], pwm_frequency);
510 getTccPinConfiguration(pin1A)->pwm_res = tccConfs[0].pwm_res;
511 getTccPinConfiguration(pin2A)->pwm_res = tccConfs[1].pwm_res;
512 getTccPinConfiguration(pin1B)->pwm_res = tccConfs[2].pwm_res;
513 getTccPinConfiguration(pin2B)->pwm_res = tccConfs[3].pwm_res;
514#ifdef SIMPLEFOC_SAMD_DEBUG
515 SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
516#endif
517
518 return new SAMDHardwareDriverParams {
519 .tccPinConfigurations = { getTccPinConfiguration(pin1A), getTccPinConfiguration(pin1B), getTccPinConfiguration(pin2A), getTccPinConfiguration(pin2B) },
520 .pwm_frequency = (uint32_t)pwm_frequency
521 };
522}
523
524
525
526
527
528
529
530
531
532/**
533 * Configuring PWM frequency, resolution and alignment
534 * - BLDC driver - 6PWM setting
535 * - hardware specific
536 *
537 * SAMD21 will support up to 2 BLDC motors in 6-PWM:
538 * one on TCC0 using 3 of the channels 0,1,2 or 3
539 * one on TCC3 using 3 of the channels 0,1,2 or 3
540 * i.e. 6 out of 8 pins must be used, in the following high/low side pairs:
541 * WO[0] & WO[4] (high side & low side)
542 * WO[1] & WO[5]
543 * WO[2] & WO[6]
544 * WO[3] & WO[7]
545 *
546 * If you're on the Arduino Nano33 IoT, please see the Nano33 IoT pinout diagram to see which TCC0/WO[x]
547 * signal is on which pin of the Nano. You can drive 1 BLDC on TCC0. For other boards, consult their documentation.
548 *
549 *
550 * @param pwm_frequency - frequency in hertz - if applicable
551 * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable
552 * @param pinA_h pinA high-side bldc driver
553 * @param pinA_l pinA low-side bldc driver
554 * @param pinB_h pinA high-side bldc driver
555 * @param pinB_l pinA low-side bldc driver
556 * @param pinC_h pinA high-side bldc driver
557 * @param pinC_l pinA low-side bldc driver
558 *
559 * @return 0 if config good, -1 if failed
560 */
561void* _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) {
562 // we want to use a TCC channel with 1 non-inverted and 1 inverted output for each phase, with dead-time insertion
563#ifdef SIMPLEFOC_SAMD_DEBUG
564 printAllPinInfos();
565#endif
566 int compatibility = checkHardware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
567 if (compatibility<0) {
568 compatibility = checkSoftware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
569 if (compatibility<0) {
570 // no result!
571#ifdef SIMPLEFOC_SAMD_DEBUG
572 SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
573#endif
575 }
576 }
577
578 tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(compatibility, 0));
579 tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(compatibility, 1));
580 tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(compatibility, 2));
581 tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(compatibility, 3));
582 tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(compatibility, 4));
583 tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(compatibility, 5));
584
585#ifdef SIMPLEFOC_SAMD_DEBUG
586 SIMPLEFOC_DEBUG("SAMD: Found configuration: ");
587 printTCCConfiguration(pinAh);
588 printTCCConfiguration(pinAl);
589 printTCCConfiguration(pinBh);
590 printTCCConfiguration(pinBl);
591 printTCCConfiguration(pinCh);
592 printTCCConfiguration(pinCl);
593#endif
594
595 // attach pins to timer peripherals
596 bool allAttached = true;
597 allAttached |= attachTCC(pinAh); // in theory this can fail, but there is no way to signal it...
598 allAttached |= attachTCC(pinAl);
599 allAttached |= attachTCC(pinBh);
600 allAttached |= attachTCC(pinBl);
601 allAttached |= attachTCC(pinCh);
602 allAttached |= attachTCC(pinCl);
603 if (!allAttached)
605#ifdef SIMPLEFOC_SAMD_DEBUG
606 SIMPLEFOC_DEBUG("SAMD: Attached pins...");
607#endif
608 // set up clock - if we did this right it should be possible to get all TCC units synchronized?
609 // e.g. attach all the timers, start them, and then start the clock... but this would require API changes in SimpleFOC driver API
610 configureSAMDClock();
611
612 if (pwm_frequency==NOT_SET) {
613 // use default frequency
614 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
615 }
616
617 // configure the TCC(s)
618 configureTCC(pinAh, pwm_frequency, false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?dead_zone:-1);
619 if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo))
620 configureTCC(pinAl, pwm_frequency, true, -1.0);
621 configureTCC(pinBh, pwm_frequency, false, (pinBh.tcc.chaninfo==pinBl.tcc.chaninfo)?dead_zone:-1);
622 if ((pinBh.tcc.chaninfo!=pinBl.tcc.chaninfo))
623 configureTCC(pinBl, pwm_frequency, true, -1.0);
624 configureTCC(pinCh, pwm_frequency, false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?dead_zone:-1);
625 if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo))
626 configureTCC(pinCl, pwm_frequency, true, -1.0);
627 getTccPinConfiguration(pinA_h)->pwm_res = pinAh.pwm_res;
628 getTccPinConfiguration(pinA_l)->pwm_res = pinAh.pwm_res; // use the high phase resolution, in case we didn't set it
629 getTccPinConfiguration(pinB_h)->pwm_res = pinBh.pwm_res;
630 getTccPinConfiguration(pinB_l)->pwm_res = pinBh.pwm_res;
631 getTccPinConfiguration(pinC_h)->pwm_res = pinCh.pwm_res;
632 getTccPinConfiguration(pinC_l)->pwm_res = pinCh.pwm_res;
633#ifdef SIMPLEFOC_SAMD_DEBUG
634 SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
635#endif
636
637 return new SAMDHardwareDriverParams {
638 .tccPinConfigurations = { getTccPinConfiguration(pinA_h), getTccPinConfiguration(pinA_l), getTccPinConfiguration(pinB_h), getTccPinConfiguration(pinB_l), getTccPinConfiguration(pinC_h), getTccPinConfiguration(pinC_l) },
639 .pwm_frequency = (uint32_t)pwm_frequency,
641 };
642}
643
644
645
646
647/**
648 * Function setting the duty cycle to the pwm pin (ex. analogWrite())
649 * - Stepper driver - 2PWM setting
650 * - hardware specific
651 *
652 * @param dc_a duty cycle phase A [0, 1]
653 * @param dc_b duty cycle phase B [0, 1]
654 * @param pinA phase A hardware pin number
655 * @param pinB phase B hardware pin number
656 */
657void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
658 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_a);
659 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_b);
660 return;
661}
662
663
664
665
666
667/**
668 * Function setting the duty cycle to the pwm pin (ex. analogWrite())
669 * - BLDC driver - 3PWM setting
670 * - hardware specific
671 *
672 * @param dc_a duty cycle phase A [0, 1]
673 * @param dc_b duty cycle phase B [0, 1]
674 * @param dc_c duty cycle phase C [0, 1]
675 * @param pinA phase A hardware pin number
676 * @param pinB phase B hardware pin number
677 * @param pinC phase C hardware pin number
678 */
679void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params) {
680 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_a);
681 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_b);
682 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[2], dc_c);
683 return;
684}
685
686
687
688
689/**
690 * Function setting the duty cycle to the pwm pin (ex. analogWrite())
691 * - Stepper driver - 4PWM setting
692 * - hardware specific
693 *
694 * @param dc_1a duty cycle phase 1A [0, 1]
695 * @param dc_1b duty cycle phase 1B [0, 1]
696 * @param dc_2a duty cycle phase 2A [0, 1]
697 * @param dc_2b duty cycle phase 2B [0, 1]
698 * @param pin1A phase 1A hardware pin number
699 * @param pin1B phase 1B hardware pin number
700 * @param pin2A phase 2A hardware pin number
701 * @param pin2B phase 2B hardware pin number
702 */
703void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
704 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_1a);
705 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_1b);
706 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[2], dc_2a);
707 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[3], dc_2b);
708 return;
709}
710
711
712
713
714/**
715 * Function setting the duty cycle to the pwm pin (ex. analogWrite())
716 * - BLDC driver - 6PWM setting
717 * - hardware specific
718 *
719 * Note: dead-time must be setup in advance, so parameter "dead_zone" is ignored
720 * the low side pins are automatically driven by the SAMD DTI module, so it is enough to set the high-side
721 * duty cycle.
722 * No sanity checks are perfomed to ensure the pinA, pinB, pinC are the same pins you used in configure method...
723 * so use appropriately.
724 *
725 * @param dc_a duty cycle phase A [0, 1]
726 * @param dc_b duty cycle phase B [0, 1]
727 * @param dc_c duty cycle phase C [0, 1]
728 * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low
729 * @param pinA_h phase A high-side hardware pin number
730 * @param pinA_l phase A low-side hardware pin number
731 * @param pinB_h phase B high-side hardware pin number
732 * @param pinB_l phase B low-side hardware pin number
733 * @param pinC_h phase C high-side hardware pin number
734 * @param pinC_l phase C low-side hardware pin number
735 *
736 */
737void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
738 SAMDHardwareDriverParams* p = (SAMDHardwareDriverParams*)params;
739 tccConfiguration* tcc1 = p->tccPinConfigurations[0];
740 tccConfiguration* tcc2 = p->tccPinConfigurations[1];
741 uint32_t pwm_res =p->tccPinConfigurations[0]->pwm_res;
742 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
743 // low-side on a different pin of same TCC - do dead-time in software...
744 float ls = dc_a+(p->dead_zone * (pwm_res-1)); // TODO resolution!!!
745 if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
746 writeSAMDDutyCycle(tcc1, dc_a);
747 writeSAMDDutyCycle(tcc2, ls);
748 }
749 else
750 writeSAMDDutyCycle(tcc1, dc_a); // dead-time is done is hardware, no need to set low side pin explicitly
751
752 tcc1 = p->tccPinConfigurations[2];
753 tcc2 = p->tccPinConfigurations[3];
754 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
755 float ls = dc_b+(p->dead_zone * (pwm_res-1));
756 if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
757 writeSAMDDutyCycle(tcc1, dc_b);
758 writeSAMDDutyCycle(tcc2, ls);
759 }
760 else
761 writeSAMDDutyCycle(tcc1, dc_b);
762
763 tcc1 = p->tccPinConfigurations[4];
764 tcc2 = p->tccPinConfigurations[5];
765 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
766 float ls = dc_c+(p->dead_zone * (pwm_res-1));
767 if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
768 writeSAMDDutyCycle(tcc1, dc_c);
769 writeSAMDDutyCycle(tcc2, ls);
770 }
771 else
772 writeSAMDDutyCycle(tcc1, dc_c);
773 return;
774
776}
777
778
779
780
781#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
782
783/**
784 * Prints a table of pin assignments for your SAMD MCU. Very useful since the
785 * board pinout descriptions and variant.cpp are usually quite wrong, and this
786 * saves you hours of cross-referencing with the datasheet.
787 */
788void printAllPinInfos() {
790 for (uint8_t pin=0;pin<PINS_COUNT;pin++) {
791 const PinDescription& pinDesc = g_APinDescription[pin];
792 wo_association& association = getWOAssociation(pinDesc.ulPort, pinDesc.ulPin);
793 SimpleFOCDebug::print("Pin ");
794 if (pin<10) SimpleFOCDebug::print("0");
796 switch (pinDesc.ulPort) {
797 case NOT_A_PORT: SimpleFOCDebug::print(" "); break;
798 case PORTA: SimpleFOCDebug::print(" PA"); break;
799 case PORTB: SimpleFOCDebug::print(" PB"); break;
800 case PORTC: SimpleFOCDebug::print(" PC"); break;
801#if defined(_SAMD51_)||defined(_SAME51_)
802 case PORTD: SimpleFOCDebug::print(" PD"); break;
803#endif
804 }
805 if (pinDesc.ulPin <10) SimpleFOCDebug::print("0");
806 SimpleFOCDebug::print((int)pinDesc.ulPin);
807
809 if (association.tccE>=0) {
810 int tcn = GetTCNumber(association.tccE);
811 if (tcn>=TCC_INST_NUM){
813 SimpleFOCDebug::print(tcn-TCC_INST_NUM);
814 }
815 else {
818 }
820 SimpleFOCDebug::print(GetTCChannelNumber(association.tccE));
822 SimpleFOCDebug::print(GetTCChannelNumber(association.woE));
824 if (tcn<10)
826 }
827 else
828 SimpleFOCDebug::print(" None ");
829
831 if (association.tccF>=0) {
832 int tcn = GetTCNumber(association.tccF);
833 if (tcn>=TCC_INST_NUM){
835 SimpleFOCDebug::print(tcn-TCC_INST_NUM);
836 }
837 else {
840 }
842 SimpleFOCDebug::print(GetTCChannelNumber(association.tccF));
844 SimpleFOCDebug::print(GetTCChannelNumber(association.woF));
846 if (tcn<10)
848 }
849 else
850 SimpleFOCDebug::print(" None ");
851
852#if defined(_SAMD51_)||defined(_SAME51_)
854 if (association.tccG>=0) {
855 int tcn = GetTCNumber(association.tccG);
857 if (tcn<10)
861 SimpleFOCDebug::print(GetTCChannelNumber(association.tccG));
863 SimpleFOCDebug::print(GetTCChannelNumber(association.woG));
865 }
866 else
867 SimpleFOCDebug::println(" None ");
868#else
870#endif
871
872 }
874}
875
876
877
878
879
880void printTCCConfiguration(tccConfiguration& info) {
881 SimpleFOCDebug::print(info.pin);
882 if (info.tcc.tccn>=TCC_INST_NUM)
883 SimpleFOCDebug::print(": TC Peripheral");
884 else
885 SimpleFOCDebug::print(": TCC Peripheral");
886 switch (info.peripheral) {
887 case PIO_TIMER:
888 SimpleFOCDebug::print(" E "); break;
889 case PIO_TIMER_ALT:
890 SimpleFOCDebug::print(" F "); break;
891#if defined(_SAMD51_)||defined(_SAME51_)
892 case PIO_TCC_PDEC:
893 SimpleFOCDebug::print(" G "); break;
894#endif
895 default:
896 SimpleFOCDebug::print(" ? "); break;
897 }
898 if (info.tcc.tccn>=0) {
899 SimpleFOCDebug::print(info.tcc.tccn);
901 SimpleFOCDebug::print(info.tcc.chan);
903 SimpleFOCDebug::print(info.wo);
905 }
906 else
908}
909
910
911
912#endif
913
914#endif
PhaseState
Definition FOCDriver.h:7
#define SIMPLEFOC_DEBUG(msg,...)
static void print(const char *msg)
static void println()
const int const int const int pinC
GenericCurrentSenseParams * params
void * _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
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)
void * _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
void _writeDutyCycle2PWM(float dc_a, float dc_b, void *params)
#define SIMPLEFOC_DRIVER_INIT_FAILED
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void *params)
void * _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void *params)
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void *params)
float const int const int const int pinB_h
float const int const int const int const int pinB_l
const int const int pin1B
const int const int const int pin2A
float const int const int const int const int const int pinC_h
float float float dc_2b
float float PhaseState * phase_state
float const int const int const int const int const int const int pinC_l
float const int const int pinA_l
const int const int const int const int pin2B
#define NOT_SET
Definition foc_utils.h:34
#define _UNUSED(v)
Definition foc_utils.h:14