3 #if defined(ARDUINO_ARCH_SAMD)
7 #include "../hardware_api.h"
8 #include "wiring_private.h"
13 #define SIMPLEFOC_SAMD_DEBUG
17 #ifndef SIMPLEFOC_SAMD_ALLOW_DIFFERENT_TCCS
18 #define SIMPLEFOC_SAMD_ALLOW_DIFFERENT_TCCS false
21 #ifndef SIMPLEFOC_SAMD_PWM_RESOLUTION
22 #define SIMPLEFOC_SAMD_PWM_RESOLUTION 1000
23 #define SIMPLEFOC_SAMD_PWM_TC_RESOLUTION 250
26 #ifndef SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS
27 #define SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS 12
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);
40 struct tccConfiguration {
53 #ifdef SIMPLEFOC_SAMD_DEBUG
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];
73 void configureSAMDClock() {
74 if (!SAMDClockConfigured) {
75 SAMDClockConfigured =
true;
76 for (
int i=0;i<TCC_INST_NUM;i++)
77 tccConfigured[i] =
false;
78 REG_GCLK_GENDIV = GCLK_GENDIV_DIV(1) |
80 while (GCLK->STATUS.bit.SYNCBUSY);
82 REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC |
84 GCLK_GENCTRL_SRC_DFLL48M |
86 while (GCLK->STATUS.bit.SYNCBUSY);
88 #ifdef SIMPLEFOC_SAMD_DEBUG
89 Serial.println(
"Configured clock...");
102 void configureTCC(tccConfiguration& tccConfig,
long pwm_frequency,
bool negate=
false,
float hw6pwm=-1) {
104 if (!tccConfigured[tccConfig.tcc.tccn]) {
105 uint32_t GCLK_CLKCTRL_ID_ofthistcc = -1;
106 switch (tccConfig.tcc.tccn>>1) {
108 GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC0_TCC1);
111 GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC2_TC3);
114 GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC4_TC5);
117 GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC6_TC7);
124 REG_GCLK_CLKCTRL = (uint16_t) GCLK_CLKCTRL_CLKEN |
125 GCLK_CLKCTRL_GEN_GCLK4 |
126 GCLK_CLKCTRL_ID_ofthistcc;
127 while (GCLK->STATUS.bit.SYNCBUSY);
129 tccConfigured[tccConfig.tcc.tccn] =
true;
131 if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
132 Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
135 tc->COUNT8.CTRLA.bit.ENABLE = 0;
136 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
138 tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
139 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
141 tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
142 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
144 tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
145 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
147 tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
148 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
150 tc->COUNT8.CTRLA.bit.ENABLE = 1;
151 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
153 #ifdef SIMPLEFOC_SAMD_DEBUG
154 Serial.print(
"Initialized TC ");
155 Serial.println(tccConfig.tcc.tccn);
159 Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
161 uint8_t invenMask = ~(1<<tccConfig.tcc.chan);
162 uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
163 tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
166 tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVEB_WAVEGENB_DSBOTH;
167 while ( tcc->SYNCBUSY.bit.WAVE == 1 );
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);
176 tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1;
177 while ( tcc->SYNCBUSY.bit.PER == 1 );
180 uint8_t chanCount = (tccConfig.tcc.tccn==1||tccConfig.tcc.tccn==2)?2:4;
181 for (
int i=0;i<chanCount;i++) {
183 uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
184 while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
192 tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1;
193 while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
195 #ifdef SIMPLEFOC_SAMD_DEBUG
196 Serial.print(
" Initialized TCC ");
197 Serial.print(tccConfig.tcc.tccn);
199 Serial.print(tccConfig.tcc.chan);
201 Serial.print(tccConfig.wo);
206 else if (tccConfig.tcc.tccn<TCC_INST_NUM) {
208 Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
210 tcc->CTRLA.bit.ENABLE = 0;
211 while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
213 uint8_t invenMask = ~(1<<tccConfig.tcc.chan);
214 uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
215 tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
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);
225 tcc->CTRLA.bit.ENABLE = 1;
226 while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
228 #ifdef SIMPLEFOC_SAMD_DEBUG
229 Serial.print(
"(Re-)Initialized TCC ");
230 Serial.print(tccConfig.tcc.tccn);
232 Serial.print(tccConfig.tcc.chan);
234 Serial.print(tccConfig.wo);
249 bool attachTCC(tccConfiguration& tccConfig) {
250 if (numTccPinConfigurations>=SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS)
252 pinMode(tccConfig.pin, OUTPUT);
253 pinPeripheral(tccConfig.pin, (tccConfig.alternate==1)?EPioType::PIO_TIMER_ALT:EPioType::PIO_TIMER);
254 tccPinConfigurations[numTccPinConfigurations++] = tccConfig;
266 bool inUse(tccConfiguration& tccConfig) {
267 for (
int i=0;i<numTccPinConfigurations;i++) {
268 if (tccPinConfigurations[i].tcc.chaninfo==tccConfig.tcc.chaninfo)
275 tccConfiguration* getTccPinConfiguration(uint8_t pin) {
276 for (
int i=0;i<numTccPinConfigurations;i++)
277 if (tccPinConfigurations[i].pin==pin)
278 return &tccPinConfigurations[i];
289 tccConfiguration getTCCChannelNr(
int pin,
bool alternate) {
290 tccConfiguration result;
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)
300 result.tcc.chaninfo = association.
tccE;
301 result.wo = association.
woE;
304 result.tcc.chaninfo = association.
tccF;
305 result.wo = association.
woF;
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))
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)
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)
324 if (pinBh.tcc.chan==pinCh.tcc.chan || pinBh.tcc.chan==pinCl.tcc.chan)
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)
328 if (pinBl.tcc.chan==pinCh.tcc.chan || pinBl.tcc.chan==pinCl.tcc.chan)
331 if (pinAh.tcc.chan!=pinAl.tcc.chan || pinBh.tcc.chan!=pinBl.tcc.chan || pinCh.tcc.chan!=pinCl.tcc.chan)
333 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo!=pinCl.wo)
342 bool checkPeripheralPermutationCompatible(tccConfiguration pins[], uint8_t num) {
343 for (
int i=0;i<num;i++)
344 if (pins[i].tcc.tccn<0)
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)
350 for (
int i=0;i<num;i++)
360 bool checkPeripheralPermutationCompatible6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
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)
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)
370 if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
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)
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)
378 if (pinBh.tcc.chaninfo==pinCh.tcc.chaninfo || pinBh.tcc.chaninfo==pinCl.tcc.chaninfo)
380 if (pinBl.tcc.chaninfo==pinCh.tcc.chaninfo || pinBl.tcc.chaninfo==pinCl.tcc.chaninfo)
384 if (pinAh.tcc.tccn!=pinAl.tcc.tccn || pinBh.tcc.tccn!=pinBl.tcc.tccn || pinCh.tcc.tccn!=pinCl.tcc.tccn)
388 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo==pinCl.wo)
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))
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))
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);
436 for (
int i=0;i<TCC_INST_NUM;i++){
439 usedtccs = usedtccs>>1;
441 for (
int i=0;i<TC_INST_NUM;i++){
444 usedtccs = usedtccs>>1;
453 int checkPermutations(uint8_t num,
int pins[],
bool (*checkFunc)(tccConfiguration[], uint8_t) ) {
454 tccConfiguration tccConfs[num];
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) {
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);
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 );
491 Tc* tc = (Tc*)GetTC(chaninfo);
493 tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);;
494 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
513 void _configure2PWM(
long pwm_frequency,
const int pinA,
const int pinB) {
514 #ifdef SIMPLEFOC_SAMD_DEBUG
517 int pins[2] = { pinA, pinB };
518 int compatibility = checkPermutations(2, pins, checkPeripheralPermutationCompatible);
519 if (compatibility<0) {
521 #ifdef SIMPLEFOC_SAMD_DEBUG
522 Serial.println(
"Bad combination!");
527 tccConfiguration tccConfs[2] = { getTCCChannelNr(pinA, (compatibility>>0&0x01)==0x1),
528 getTCCChannelNr(pinB, (compatibility>>1&0x01)==0x1) };
531 #ifdef SIMPLEFOC_SAMD_DEBUG
532 Serial.print(
"Found configuration: (score=");
533 Serial.print(scorePermutation(tccConfs, 2));
540 attachTCC(tccConfs[0]);
541 attachTCC(tccConfs[1]);
542 #ifdef SIMPLEFOC_SAMD_DEBUG
543 Serial.println(
"Attached pins...");
548 configureSAMDClock();
551 configureTCC(tccConfs[0], pwm_frequency);
552 configureTCC(tccConfs[1], pwm_frequency);
553 #ifdef SIMPLEFOC_SAMD_DEBUG
554 Serial.println(
"Configured TCCs...");
603 void _configure3PWM(
long pwm_frequency,
const int pinA,
const int pinB,
const int pinC) {
604 #ifdef SIMPLEFOC_SAMD_DEBUG
607 int pins[3] = { pinA, pinB, pinC };
608 int compatibility = checkPermutations(3, pins, checkPeripheralPermutationCompatible);
609 if (compatibility<0) {
611 #ifdef SIMPLEFOC_SAMD_DEBUG
612 Serial.println(
"Bad combination!");
617 tccConfiguration tccConfs[3] = { getTCCChannelNr(pinA, (compatibility>>0&0x01)==0x1),
618 getTCCChannelNr(pinB, (compatibility>>1&0x01)==0x1),
619 getTCCChannelNr(pinC, (compatibility>>2&0x01)==0x1) };
622 #ifdef SIMPLEFOC_SAMD_DEBUG
623 Serial.print(
"Found configuration: (score=");
624 Serial.print(scorePermutation(tccConfs, 3));
632 attachTCC(tccConfs[0]);
633 attachTCC(tccConfs[1]);
634 attachTCC(tccConfs[2]);
635 #ifdef SIMPLEFOC_SAMD_DEBUG
636 Serial.println(
"Attached pins...");
641 configureSAMDClock();
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...");
671 void _configure4PWM(
long pwm_frequency,
const int pin1A,
const int pin1B,
const int pin2A,
const int pin2B) {
672 #ifdef SIMPLEFOC_SAMD_DEBUG
675 int pins[4] = { pin1A, pin1B, pin2A, pin2B };
676 int compatibility = checkPermutations(4, pins, checkPeripheralPermutationCompatible);
677 if (compatibility<0) {
679 #ifdef SIMPLEFOC_SAMD_DEBUG
680 Serial.println(
"Bad combination!");
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) };
691 #ifdef SIMPLEFOC_SAMD_DEBUG
692 Serial.print(
"Found configuration: (score=");
693 Serial.print(scorePermutation(tccConfs, 4));
702 attachTCC(tccConfs[0]);
703 attachTCC(tccConfs[1]);
704 attachTCC(tccConfs[2]);
705 attachTCC(tccConfs[3]);
706 #ifdef SIMPLEFOC_SAMD_DEBUG
707 Serial.println(
"Attached pins...");
712 configureSAMDClock();
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...");
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) {
765 #ifdef SIMPLEFOC_SAMD_DEBUG
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) {
773 #ifdef SIMPLEFOC_SAMD_DEBUG
774 Serial.println(
"Bad combination!");
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);
787 #ifdef SIMPLEFOC_SAMD_DEBUG
788 Serial.println(
"Found configuration: ");
798 bool allAttached =
true;
799 allAttached |= attachTCC(pinAh);
800 allAttached |= attachTCC(pinAl);
801 allAttached |= attachTCC(pinBh);
802 allAttached |= attachTCC(pinBl);
803 allAttached |= attachTCC(pinCh);
804 allAttached |= attachTCC(pinCl);
807 #ifdef SIMPLEFOC_SAMD_DEBUG
808 Serial.println(
"Attached pins...");
812 configureSAMDClock();
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...");
843 tccConfiguration* tccI = getTccPinConfiguration(pinA);
844 writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_a);
845 tccI = getTccPinConfiguration(pinB);
846 writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_b);
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);
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);
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) {
927 float ls = dc_a+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
928 if (ls>1.0) ls = 1.0;
929 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a);
930 writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
933 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a);
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;
940 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
941 writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
944 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
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;
951 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);
952 writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
955 writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);