SimpleFOClibrary  2.1
samd21_mcu.cpp
Go to the documentation of this file.
1 
2 
3 #if defined(ARDUINO_ARCH_SAMD)
4 //#if defined(_SAMD21_)
5 
6 
7 #include "../hardware_api.h"
8 #include "wiring_private.h"
9 
11 
12 
13 #define SIMPLEFOC_SAMD_DEBUG
14 
15 
16 
17 #ifndef SIMPLEFOC_SAMD_ALLOW_DIFFERENT_TCCS
18 #define SIMPLEFOC_SAMD_ALLOW_DIFFERENT_TCCS false
19 #endif
20 
21 #ifndef SIMPLEFOC_SAMD_PWM_RESOLUTION
22 #define SIMPLEFOC_SAMD_PWM_RESOLUTION 1000
23 #define SIMPLEFOC_SAMD_PWM_TC_RESOLUTION 250
24 #endif
25 
26 #ifndef SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS
27 #define SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS 12
28 #endif
29 
30 
31 
32 // Wait for synchronization of registers between the clock domains
33 static __inline__ void syncTCC(Tcc* TCCx) __attribute__((always_inline, unused));
34 static void syncTCC(Tcc* TCCx) {
35  while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK);
36 }
37 
38 
39 
40 struct tccConfiguration {
41  uint8_t pin;
42  uint8_t alternate; // 1=true, 0=false
43  uint8_t wo;
44  union tccChanInfo {
45  struct {
46  int8_t chan;
47  int8_t tccn;
48  };
49  uint16_t chaninfo;
50  } tcc;
51 };
52 
53 #ifdef SIMPLEFOC_SAMD_DEBUG
54 #include "./samd_debug.h"
55 #endif
56 
57 
58 
59 
63 tccConfiguration tccPinConfigurations[SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS];
64 uint8_t numTccPinConfigurations = 0;
65 bool SAMDClockConfigured = false;
66 bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
67 
73 void configureSAMDClock() {
74  if (!SAMDClockConfigured) {
75  SAMDClockConfigured = true; // mark clock as configured
76  for (int i=0;i<TCC_INST_NUM;i++) // mark all the TCCs as not yet configured
77  tccConfigured[i] = false;
78  REG_GCLK_GENDIV = GCLK_GENDIV_DIV(1) | // Divide the 48MHz clock source by divisor N=1: 48MHz/1=48MHz
79  GCLK_GENDIV_ID(4); // Select Generic Clock (GCLK) 4
80  while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
81 
82  REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
83  GCLK_GENCTRL_GENEN | // Enable GCLK4
84  GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
85  GCLK_GENCTRL_ID(4); // Select GCLK4
86  while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
87 
88 #ifdef SIMPLEFOC_SAMD_DEBUG
89  Serial.println("Configured clock...");
90 #endif
91  }
92 }
93 
94 
95 
96 
102 void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate=false, float hw6pwm=-1) {
103  // TODO for the moment we ignore the frequency...
104  if (!tccConfigured[tccConfig.tcc.tccn]) {
105  uint32_t GCLK_CLKCTRL_ID_ofthistcc = -1;
106  switch (tccConfig.tcc.tccn>>1) {
107  case 0:
108  GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC0_TCC1);//GCLK_CLKCTRL_ID_TCC0_TCC1;
109  break;
110  case 1:
111  GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC2_TC3);//GCLK_CLKCTRL_ID_TCC2_TC3;
112  break;
113  case 2:
114  GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC4_TC5);//GCLK_CLKCTRL_ID_TC4_TC5;
115  break;
116  case 3:
117  GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC6_TC7);
118  break;
119  default:
120  return;
121  }
122 
123  // Feed GCLK4 to TCC
124  REG_GCLK_CLKCTRL = (uint16_t) GCLK_CLKCTRL_CLKEN | // Enable GCLK4
125  GCLK_CLKCTRL_GEN_GCLK4 | // Select GCLK4
126  GCLK_CLKCTRL_ID_ofthistcc; // Feed GCLK4 to tcc
127  while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
128 
129  tccConfigured[tccConfig.tcc.tccn] = true;
130 
131  if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
132  Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
133 
134  // disable
135  tc->COUNT8.CTRLA.bit.ENABLE = 0;
136  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
137  // unfortunately we need the 8-bit counter mode to use the PER register...
138  tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
139  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
140  // meaning prescaler of 8, since TC-Unit has no up/down mode, and has resolution of 250 rather than 1000...
141  tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
142  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
143  // period is 250, period cannot be higher than 256!
144  tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
145  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
146  // initial duty cycle is 0
147  tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
148  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
149  // enable
150  tc->COUNT8.CTRLA.bit.ENABLE = 1;
151  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
152 
153 #ifdef SIMPLEFOC_SAMD_DEBUG
154  Serial.print("Initialized TC ");
155  Serial.println(tccConfig.tcc.tccn);
156 #endif
157  }
158  else {
159  Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
160 
161  uint8_t invenMask = ~(1<<tccConfig.tcc.chan); // negate (invert) the signal if needed
162  uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
163  tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
164  syncTCC(tcc); // wait for sync
165 
166  tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVEB_WAVEGENB_DSBOTH; // Set wave form configuration
167  while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
168 
169  if (hw6pwm>0.0) {
170  tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
171  tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
172  tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
173  syncTCC(tcc); // wait for sync
174  }
175 
176  tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1; // Set counter Top using the PER register
177  while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
178 
179  // set all channels to 0%
180  uint8_t chanCount = (tccConfig.tcc.tccn==1||tccConfig.tcc.tccn==2)?2:4;
181  for (int i=0;i<chanCount;i++) {
182  tcc->CC[i].reg = 0; // start off at 0% duty cycle
183  uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
184  while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
185  }
186 
187  // enable double buffering
188  //tcc->CTRLBCLR.bit.LUPD = 1;
189  //while ( tcc->SYNCBUSY.bit.CTRLB == 1 );
190 
191  // Enable TC
192  tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1; //48Mhz/1=48Mhz/2(up/down)=24MHz/1024=24KHz
193  while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
194 
195 #ifdef SIMPLEFOC_SAMD_DEBUG
196  Serial.print(" Initialized TCC ");
197  Serial.print(tccConfig.tcc.tccn);
198  Serial.print("-");
199  Serial.print(tccConfig.tcc.chan);
200  Serial.print("[");
201  Serial.print(tccConfig.wo);
202  Serial.println("]");
203 #endif
204  }
205  }
206  else if (tccConfig.tcc.tccn<TCC_INST_NUM) {
207  // set invert bit for TCC channels in SW 6-PWM...
208  Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
209 
210  tcc->CTRLA.bit.ENABLE = 0;
211  while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
212 
213  uint8_t invenMask = ~(1<<tccConfig.tcc.chan); // negate (invert) the signal if needed
214  uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
215  tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
216  syncTCC(tcc); // wait for sync
217 
218  if (hw6pwm>0.0) {
219  tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
220  tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
221  tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
222  syncTCC(tcc); // wait for sync
223  }
224 
225  tcc->CTRLA.bit.ENABLE = 1;
226  while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
227 
228 #ifdef SIMPLEFOC_SAMD_DEBUG
229  Serial.print("(Re-)Initialized TCC ");
230  Serial.print(tccConfig.tcc.tccn);
231  Serial.print("-");
232  Serial.print(tccConfig.tcc.chan);
233  Serial.print("[");
234  Serial.print(tccConfig.wo);
235  Serial.println("]");
236 #endif
237  }
238 
239 
240 }
241 
242 
243 
244 
245 
249 bool attachTCC(tccConfiguration& tccConfig) {
250  if (numTccPinConfigurations>=SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS)
251  return false;
252  pinMode(tccConfig.pin, OUTPUT);
253  pinPeripheral(tccConfig.pin, (tccConfig.alternate==1)?EPioType::PIO_TIMER_ALT:EPioType::PIO_TIMER);
254  tccPinConfigurations[numTccPinConfigurations++] = tccConfig;
255  return true;
256 }
257 
258 
259 
260 
261 
262 
266 bool inUse(tccConfiguration& tccConfig) {
267  for (int i=0;i<numTccPinConfigurations;i++) {
268  if (tccPinConfigurations[i].tcc.chaninfo==tccConfig.tcc.chaninfo)
269  return true;
270  }
271  return false;
272 }
273 
274 
275 tccConfiguration* getTccPinConfiguration(uint8_t pin) {
276  for (int i=0;i<numTccPinConfigurations;i++)
277  if (tccPinConfigurations[i].pin==pin)
278  return &tccPinConfigurations[i];
279  return NULL;
280 }
281 
282 
283 
284 
285 
289 tccConfiguration getTCCChannelNr(int pin, bool alternate) {
290  tccConfiguration result;
291  result.pin = pin;
292  result.alternate = alternate?1:0;
293  result.tcc.tccn = -2;
294  result.tcc.chan = -2;
295  const PinDescription& pinDesc = g_APinDescription[pin];
296  struct wo_association& association = getWOAssociation(pinDesc.ulPort, pinDesc.ulPin);
297  if (association.port==NOT_A_PORT)
298  return result; // could not find the port/pin
299  if (!alternate) { // && (attr & PIN_ATTR_PWM) == PIN_ATTR_PWM) {
300  result.tcc.chaninfo = association.tccE;
301  result.wo = association.woE;
302  }
303  else { // && (attr & PIN_ATTR_TIMER_ALT) == PIN_ATTR_TIMER_ALT) {
304  result.tcc.chaninfo = association.tccF;
305  result.wo = association.woF;
306  }
307  return result;
308 }
309 
310 
311 
312 
313 
314 bool checkPeripheralPermutationSameTCC6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
315  if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
316  return false;
317 
318  if (pinAh.tcc.tccn<0 || pinAh.tcc.tccn!=pinAl.tcc.tccn || pinAh.tcc.tccn!=pinBh.tcc.tccn || pinAh.tcc.tccn!=pinBl.tcc.tccn
319  || pinAh.tcc.tccn!=pinCh.tcc.tccn || pinAh.tcc.tccn!=pinCl.tcc.tccn || pinAh.tcc.tccn>=TCC_INST_NUM)
320  return false;
321 
322  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)
323  return false;
324  if (pinBh.tcc.chan==pinCh.tcc.chan || pinBh.tcc.chan==pinCl.tcc.chan)
325  return false;
326  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)
327  return false;
328  if (pinBl.tcc.chan==pinCh.tcc.chan || pinBl.tcc.chan==pinCl.tcc.chan)
329  return false;
330 
331  if (pinAh.tcc.chan!=pinAl.tcc.chan || pinBh.tcc.chan!=pinBl.tcc.chan || pinCh.tcc.chan!=pinCl.tcc.chan)
332  return false;
333  if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo!=pinCl.wo)
334  return false;
335 
336  return true;
337 }
338 
339 
340 
341 
342 bool checkPeripheralPermutationCompatible(tccConfiguration pins[], uint8_t num) {
343  for (int i=0;i<num;i++)
344  if (pins[i].tcc.tccn<0)
345  return false;
346  for (int i=0;i<num-1;i++)
347  for (int j=i+1;j<num;j++)
348  if (pins[i].tcc.chaninfo==pins[j].tcc.chaninfo)
349  return false;
350  for (int i=0;i<num;i++)
351  if (inUse(pins[i]))
352  return false;
353  return true;
354 }
355 
356 
357 
358 
359 
360 bool checkPeripheralPermutationCompatible6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
361  // check we're valid PWM pins
362  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)
363  return false;
364  // only TCC units for 6-PWM
365  if (pinAh.tcc.tccn>=TCC_INST_NUM || pinAl.tcc.tccn>=TCC_INST_NUM || pinBh.tcc.tccn>=TCC_INST_NUM
366  || pinBl.tcc.tccn>=TCC_INST_NUM || pinCh.tcc.tccn>=TCC_INST_NUM || pinCl.tcc.tccn>=TCC_INST_NUM)
367  return false;
368 
369  // check we're not in use
370  if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
371  return false;
372 
373  // check pins are all different tccs/channels
374  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)
375  return false;
376  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)
377  return false;
378  if (pinBh.tcc.chaninfo==pinCh.tcc.chaninfo || pinBh.tcc.chaninfo==pinCl.tcc.chaninfo)
379  return false;
380  if (pinBl.tcc.chaninfo==pinCh.tcc.chaninfo || pinBl.tcc.chaninfo==pinCl.tcc.chaninfo)
381  return false;
382 
383  // check H/L pins are on same timer
384  if (pinAh.tcc.tccn!=pinAl.tcc.tccn || pinBh.tcc.tccn!=pinBl.tcc.tccn || pinCh.tcc.tccn!=pinCl.tcc.tccn)
385  return false;
386 
387  // check H/L pins aren't on both the same timer and wo
388  if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo==pinCl.wo)
389  return false;
390 
391  return true;
392 }
393 
394 
395 
396 
397 
398 int 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) {
399  for (int i=0;i<64;i++) {
400  tccConfiguration pinAh = getTCCChannelNr(pinA_h, (i>>0&0x01)==0x1);
401  tccConfiguration pinAl = getTCCChannelNr(pinA_l, (i>>1&0x01)==0x1);
402  tccConfiguration pinBh = getTCCChannelNr(pinB_h, (i>>2&0x01)==0x1);
403  tccConfiguration pinBl = getTCCChannelNr(pinB_l, (i>>3&0x01)==0x1);
404  tccConfiguration pinCh = getTCCChannelNr(pinC_h, (i>>4&0x01)==0x1);
405  tccConfiguration pinCl = getTCCChannelNr(pinC_l, (i>>5&0x01)==0x1);
406  if (checkPeripheralPermutationSameTCC6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
407  return i;
408  }
409  return -1;
410 }
411 
412 
413 
414 
415 int 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) {
416  for (int i=0;i<64;i++) {
417  tccConfiguration pinAh = getTCCChannelNr(pinA_h, (i>>0&0x01)==0x1);
418  tccConfiguration pinAl = getTCCChannelNr(pinA_l, (i>>1&0x01)==0x1);
419  tccConfiguration pinBh = getTCCChannelNr(pinB_h, (i>>2&0x01)==0x1);
420  tccConfiguration pinBl = getTCCChannelNr(pinB_l, (i>>3&0x01)==0x1);
421  tccConfiguration pinCh = getTCCChannelNr(pinC_h, (i>>4&0x01)==0x1);
422  tccConfiguration pinCl = getTCCChannelNr(pinC_l, (i>>5&0x01)==0x1);
423  if (checkPeripheralPermutationCompatible6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
424  return i;
425  }
426  return -1;
427 }
428 
429 
430 
431 int scorePermutation(tccConfiguration pins[], uint8_t num) {
432  uint32_t usedtccs = 0;
433  for (int i=0;i<num;i++)
434  usedtccs |= (1<<pins[i].tcc.tccn);
435  int score = 0;
436  for (int i=0;i<TCC_INST_NUM;i++){
437  if (usedtccs&0x1)
438  score+=1;
439  usedtccs = usedtccs>>1;
440  }
441  for (int i=0;i<TC_INST_NUM;i++){
442  if (usedtccs&0x1)
443  score+=(num+1);
444  usedtccs = usedtccs>>1;
445  }
446  return score;
447 }
448 
449 
450 
451 
452 
453 int checkPermutations(uint8_t num, int pins[], bool (*checkFunc)(tccConfiguration[], uint8_t) ) {
454  tccConfiguration tccConfs[num];
455  int best = -1;
456  int bestscore = 1000000;
457  for (int i=0;i<(0x1<<num);i++) {
458  for (int j=0;j<num;j++)
459  tccConfs[j] = getTCCChannelNr(pins[j], ((i>>j)&0x01)==0x1);
460  if (checkFunc(tccConfs, num)) {
461  int score = scorePermutation(tccConfs, num);
462  if (score<bestscore) {
463  bestscore = score;
464  best = i;
465  }
466  }
467  }
468  return best;
469 }
470 
471 
472 
473 
474 void writeSAMDDutyCycle(int chaninfo, float dc) {
475  uint8_t tccn = GetTCNumber(chaninfo);
476  uint8_t chan = GetTCChannelNumber(chaninfo);
477  if (tccn<TCC_INST_NUM) {
478  Tcc* tcc = (Tcc*)GetTC(chaninfo);
479  // set via CC
480  tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
481  uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
482  while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
483  // set via CCB
484 // tcc->CCB[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
485 // tcc->STATUS.vec.CCBV = tcc->STATUS.vec.CCBV | (1<<chan);
486  // TODO do we need to wait for sync?
487 // uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CCB0_Pos+chan);
488 // while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
489  }
490  else {
491  Tc* tc = (Tc*)GetTC(chaninfo);
492  //tc->COUNT16.CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
493  tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);;
494  while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
495  }
496 }
497 
498 
499 
500 
501 
502 
503 
513 void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
514 #ifdef SIMPLEFOC_SAMD_DEBUG
516 #endif
517  int pins[2] = { pinA, pinB };
518  int compatibility = checkPermutations(2, pins, checkPeripheralPermutationCompatible);
519  if (compatibility<0) {
520  // no result!
521 #ifdef SIMPLEFOC_SAMD_DEBUG
522  Serial.println("Bad combination!");
523 #endif
524  return;
525  }
526 
527  tccConfiguration tccConfs[2] = { getTCCChannelNr(pinA, (compatibility>>0&0x01)==0x1),
528  getTCCChannelNr(pinB, (compatibility>>1&0x01)==0x1) };
529 
530 
531 #ifdef SIMPLEFOC_SAMD_DEBUG
532  Serial.print("Found configuration: (score=");
533  Serial.print(scorePermutation(tccConfs, 2));
534  Serial.println(")");
535  printTCCConfiguration(tccConfs[0]);
536  printTCCConfiguration(tccConfs[1]);
537 #endif
538 
539  // attach pins to timer peripherals
540  attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
541  attachTCC(tccConfs[1]);
542 #ifdef SIMPLEFOC_SAMD_DEBUG
543  Serial.println("Attached pins...");
544 #endif
545 
546  // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
547  // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
548  configureSAMDClock();
549 
550  // configure the TCC (waveform, top-value, pre-scaler = frequency)
551  configureTCC(tccConfs[0], pwm_frequency);
552  configureTCC(tccConfs[1], pwm_frequency);
553 #ifdef SIMPLEFOC_SAMD_DEBUG
554  Serial.println("Configured TCCs...");
555 #endif
556 
557  return; // Someone with a stepper-setup who can test it?
558 }
559 
560 
561 
562 
563 
564 
565 
566 
567 
568 
569 
570 
603 void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
604 #ifdef SIMPLEFOC_SAMD_DEBUG
606 #endif
607  int pins[3] = { pinA, pinB, pinC };
608  int compatibility = checkPermutations(3, pins, checkPeripheralPermutationCompatible);
609  if (compatibility<0) {
610  // no result!
611 #ifdef SIMPLEFOC_SAMD_DEBUG
612  Serial.println("Bad combination!");
613 #endif
614  return;
615  }
616 
617  tccConfiguration tccConfs[3] = { getTCCChannelNr(pinA, (compatibility>>0&0x01)==0x1),
618  getTCCChannelNr(pinB, (compatibility>>1&0x01)==0x1),
619  getTCCChannelNr(pinC, (compatibility>>2&0x01)==0x1) };
620 
621 
622 #ifdef SIMPLEFOC_SAMD_DEBUG
623  Serial.print("Found configuration: (score=");
624  Serial.print(scorePermutation(tccConfs, 3));
625  Serial.println(")");
626  printTCCConfiguration(tccConfs[0]);
627  printTCCConfiguration(tccConfs[1]);
628  printTCCConfiguration(tccConfs[2]);
629 #endif
630 
631  // attach pins to timer peripherals
632  attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
633  attachTCC(tccConfs[1]);
634  attachTCC(tccConfs[2]);
635 #ifdef SIMPLEFOC_SAMD_DEBUG
636  Serial.println("Attached pins...");
637 #endif
638 
639  // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
640  // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
641  configureSAMDClock();
642 
643  // configure the TCC (waveform, top-value, pre-scaler = frequency)
644  configureTCC(tccConfs[0], pwm_frequency);
645  configureTCC(tccConfs[1], pwm_frequency);
646  configureTCC(tccConfs[2], pwm_frequency);
647 #ifdef SIMPLEFOC_SAMD_DEBUG
648  Serial.println("Configured TCCs...");
649 #endif
650 
651 }
652 
653 
654 
655 
656 
657 
658 
659 
671 void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
672 #ifdef SIMPLEFOC_SAMD_DEBUG
674 #endif
675  int pins[4] = { pin1A, pin1B, pin2A, pin2B };
676  int compatibility = checkPermutations(4, pins, checkPeripheralPermutationCompatible);
677  if (compatibility<0) {
678  // no result!
679 #ifdef SIMPLEFOC_SAMD_DEBUG
680  Serial.println("Bad combination!");
681 #endif
682  return;
683  }
684 
685  tccConfiguration tccConfs[4] = { getTCCChannelNr(pin1A, (compatibility>>0&0x01)==0x1),
686  getTCCChannelNr(pin1B, (compatibility>>1&0x01)==0x1),
687  getTCCChannelNr(pin2A, (compatibility>>2&0x01)==0x1),
688  getTCCChannelNr(pin2B, (compatibility>>3&0x01)==0x1) };
689 
690 
691 #ifdef SIMPLEFOC_SAMD_DEBUG
692  Serial.print("Found configuration: (score=");
693  Serial.print(scorePermutation(tccConfs, 4));
694  Serial.println(")");
695  printTCCConfiguration(tccConfs[0]);
696  printTCCConfiguration(tccConfs[1]);
697  printTCCConfiguration(tccConfs[2]);
698  printTCCConfiguration(tccConfs[3]);
699 #endif
700 
701  // attach pins to timer peripherals
702  attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
703  attachTCC(tccConfs[1]);
704  attachTCC(tccConfs[2]);
705  attachTCC(tccConfs[3]);
706 #ifdef SIMPLEFOC_SAMD_DEBUG
707  Serial.println("Attached pins...");
708 #endif
709 
710  // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
711  // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
712  configureSAMDClock();
713 
714  // configure the TCC (waveform, top-value, pre-scaler = frequency)
715  configureTCC(tccConfs[0], pwm_frequency);
716  configureTCC(tccConfs[1], pwm_frequency);
717  configureTCC(tccConfs[2], pwm_frequency);
718  configureTCC(tccConfs[3], pwm_frequency);
719 #ifdef SIMPLEFOC_SAMD_DEBUG
720  Serial.println("Configured TCCs...");
721 #endif
722 
723  return; // Someone with a stepper-setup who can test it?
724 }
725 
726 
727 
728 
729 
730 
731 
732 
733 
763 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) {
764  // we want to use a TCC channel with 1 non-inverted and 1 inverted output for each phase, with dead-time insertion
765 #ifdef SIMPLEFOC_SAMD_DEBUG
767 #endif
768  int compatibility = checkHardware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
769  if (compatibility<0) {
770  compatibility = checkSoftware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
771  if (compatibility<0) {
772  // no result!
773 #ifdef SIMPLEFOC_SAMD_DEBUG
774  Serial.println("Bad combination!");
775 #endif
776  return -1;
777  }
778  }
779 
780  tccConfiguration pinAh = getTCCChannelNr(pinA_h, (compatibility>>0&0x01)==0x1);
781  tccConfiguration pinAl = getTCCChannelNr(pinA_l, (compatibility>>1&0x01)==0x1);
782  tccConfiguration pinBh = getTCCChannelNr(pinB_h, (compatibility>>2&0x01)==0x1);
783  tccConfiguration pinBl = getTCCChannelNr(pinB_l, (compatibility>>3&0x01)==0x1);
784  tccConfiguration pinCh = getTCCChannelNr(pinC_h, (compatibility>>4&0x01)==0x1);
785  tccConfiguration pinCl = getTCCChannelNr(pinC_l, (compatibility>>5&0x01)==0x1);
786 
787 #ifdef SIMPLEFOC_SAMD_DEBUG
788  Serial.println("Found configuration: ");
789  printTCCConfiguration(pinAh);
790  printTCCConfiguration(pinAl);
791  printTCCConfiguration(pinBh);
792  printTCCConfiguration(pinBl);
793  printTCCConfiguration(pinCh);
794  printTCCConfiguration(pinCl);
795 #endif
796 
797  // attach pins to timer peripherals
798  bool allAttached = true;
799  allAttached |= attachTCC(pinAh); // in theory this can fail, but there is no way to signal it...
800  allAttached |= attachTCC(pinAl);
801  allAttached |= attachTCC(pinBh);
802  allAttached |= attachTCC(pinBl);
803  allAttached |= attachTCC(pinCh);
804  allAttached |= attachTCC(pinCl);
805  if (!allAttached)
806  return -1;
807 #ifdef SIMPLEFOC_SAMD_DEBUG
808  Serial.println("Attached pins...");
809 #endif
810  // set up clock - if we did this right it should be possible to get all TCC units synchronized?
811  // e.g. attach all the timers, start them, and then start the clock... but this would require API changes in SimpleFOC driver API
812  configureSAMDClock();
813 
814  // configure the TCC(s)
815  configureTCC(pinAh, pwm_frequency, false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?dead_zone:-1);
816  if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo))
817  configureTCC(pinAl, pwm_frequency, true, -1.0);
818  configureTCC(pinBh, pwm_frequency, false, (pinBh.tcc.chaninfo==pinBl.tcc.chaninfo)?dead_zone:-1);
819  if ((pinBh.tcc.chaninfo!=pinBl.tcc.chaninfo))
820  configureTCC(pinBl, pwm_frequency, true, -1.0);
821  configureTCC(pinCh, pwm_frequency, false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?dead_zone:-1);
822  if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo))
823  configureTCC(pinCl, pwm_frequency, true, -1.0);
824 #ifdef SIMPLEFOC_SAMD_DEBUG
825  Serial.println("Configured TCCs...");
826 #endif
827 
828  return 0;
829 }
830 
831 
842 void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB) {
843  tccConfiguration* tccI = getTccPinConfiguration(pinA);
844  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_a);
845  tccI = getTccPinConfiguration(pinB);
846  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_b);
847  return;
848 }
849 
862 void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC) {
863  tccConfiguration* tccI = getTccPinConfiguration(pinA);
864  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_a);
865  tccI = getTccPinConfiguration(pinB);
866  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_b);
867  tccI = getTccPinConfiguration(pinC);
868  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_c);
869  return;
870 }
871 
872 
887 void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
888  tccConfiguration* tccI = getTccPinConfiguration(pin1A);
889  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_1a);
890  tccI = getTccPinConfiguration(pin2A);
891  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_2a);
892  tccI = getTccPinConfiguration(pin1B);
893  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_1b);
894  tccI = getTccPinConfiguration(pin2B);
895  writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_2b);
896  return;
897 }
898 
922 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){
923  tccConfiguration* tcc1 = getTccPinConfiguration(pinA_h);
924  tccConfiguration* tcc2 = getTccPinConfiguration(pinA_l);
925  if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
926  // low-side on a different pin of same TCC - do dead-time in software...
927  float ls = dc_a+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
928  if (ls>1.0) ls = 1.0; // no off-time is better than too-short dead-time
929  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a);
930  writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
931  }
932  else
933  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a); // dead-time is done is hardware, no need to set low side pin explicitly
934 
935  tcc1 = getTccPinConfiguration(pinB_h);
936  tcc2 = getTccPinConfiguration(pinB_l);
937  if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
938  float ls = dc_b+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
939  if (ls>1.0) ls = 1.0; // no off-time is better than too-short dead-time
940  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
941  writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
942  }
943  else
944  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
945 
946  tcc1 = getTccPinConfiguration(pinC_h);
947  tcc2 = getTccPinConfiguration(pinC_l);
948  if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
949  float ls = dc_c+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
950  if (ls>1.0) ls = 1.0; // no off-time is better than too-short dead-time
951  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);
952  writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
953  }
954  else
955  writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);
956  return;
957 }
958 
959 
960 
961 
962 
963 
964 
965 #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
printAllPinInfos
void printAllPinInfos()
Definition: samd_debug.h:18
wo_association::woE
uint8_t woE
Definition: samd21_wo_associations.h:7
wo_association
Definition: samd21_wo_associations.h:3
_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
printTCCConfiguration
void printTCCConfiguration(tccConfiguration &info)
Definition: samd_debug.h:91
_writeDutyCycle2PWM
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:55
wo_association::tccE
ETCChannel tccE
Definition: samd21_wo_associations.h:6
wo_association::tccF
ETCChannel tccF
Definition: samd21_wo_associations.h:8
wo_association::woF
uint8_t woF
Definition: samd21_wo_associations.h:9
_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
samd21_wo_associations.h
wo_association::port
EPortType port
Definition: samd21_wo_associations.h:4
samd_debug.h
_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