Skip to content

Commit 494ced5

Browse files
committed
SAMD driver improvements
1 parent 4555f91 commit 494ced5

File tree

4 files changed

+108
-50
lines changed

4 files changed

+108
-50
lines changed

src/drivers/hardware_specific/samd21_mcu.cpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -159,6 +159,7 @@ void configureSAMDClock() {
159159
REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
160160
GCLK_GENCTRL_GENEN | // Enable GCLK4
161161
GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
162+
// GCLK_GENCTRL_SRC_FDPLL | // Set the 96MHz clock source
162163
GCLK_GENCTRL_ID(4); // Select GCLK4
163164
while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
164165

@@ -305,11 +306,11 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
305306

306307

307308

308-
void writeSAMDDutyCycle(int chaninfo, float dc) {
309-
uint8_t tccn = GetTCNumber(chaninfo);
310-
uint8_t chan = GetTCChannelNumber(chaninfo);
309+
void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
310+
uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
311+
uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
311312
if (tccn<TCC_INST_NUM) {
312-
Tcc* tcc = (Tcc*)GetTC(chaninfo);
313+
Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
313314
// set via CC
314315
// tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
315316
// uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
@@ -324,7 +325,7 @@ void writeSAMDDutyCycle(int chaninfo, float dc) {
324325
// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
325326
}
326327
else {
327-
Tc* tc = (Tc*)GetTC(chaninfo);
328+
Tc* tc = (Tc*)GetTC(info->tcc.chaninfo);
328329
tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
329330
while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
330331
}

src/drivers/hardware_specific/samd51_mcu.cpp

Lines changed: 38 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,16 @@
77

88

99

10+
// expected frequency on DPLL, since we don't configure it ourselves. Typically this is the CPU frequency.
11+
// for custom boards or overclockers you can override it using this define.
12+
#ifndef SIMPLEFOC_SAMD51_DPLL_FREQ
13+
#define SIMPLEFOC_SAMD51_DPLL_FREQ 120000000
14+
#endif
15+
16+
17+
18+
19+
1020
// TCC# Channels WO_NUM Counter size Fault Dithering Output matrix DTI SWAP Pattern generation
1121
// 0 6 8 24-bit Yes Yes Yes Yes Yes Yes
1222
// 1 4 8 24-bit Yes Yes Yes Yes Yes Yes
@@ -17,7 +27,6 @@
1727

1828
#define NUM_WO_ASSOCIATIONS 72
1929

20-
2130
struct wo_association WO_associations[] = {
2231

2332
{ PORTB, 9, TC4_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
@@ -112,7 +121,7 @@ struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
112121

113122

114123
EPioType getPeripheralOfPermutation(int permutation, int pin_position) {
115-
return ((permutation>>pin_position)&0x01)==0x1?PIO_TIMER_ALT:PIO_TIMER;
124+
return ((permutation>>pin_position)&0x01)==0x1?PIO_TCC_PDEC:PIO_TIMER_ALT;
116125
}
117126

118127

@@ -124,24 +133,17 @@ void syncTCC(Tcc* TCCx) {
124133

125134

126135

127-
void writeSAMDDutyCycle(int chaninfo, float dc) {
128-
uint8_t tccn = GetTCNumber(chaninfo);
129-
uint8_t chan = GetTCChannelNumber(chaninfo);
136+
void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
137+
uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
138+
uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
130139
if (tccn<TCC_INST_NUM) {
131-
Tcc* tcc = (Tcc*)GetTC(chaninfo);
140+
Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
132141
// set via CCBUF
133-
while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
134-
tcc->CCBUF[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc); // TODO pwm frequency!
135-
// tcc->STATUS.vec.CCBUFV |= (0x1<<chan);
136-
// while ( tcc->SYNCBUSY.bit.STATUS > 0 );
137-
// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
138-
// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
142+
// while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
143+
tcc->CCBUF[chan].reg = (uint32_t)((info->pwm_res-1) * dc); // TODO pwm frequency!
139144
}
140-
else {
141-
// Tc* tc = (Tc*)GetTC(chaninfo);
142-
// //tc->COUNT16.CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
143-
// tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
144-
// while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
145+
else {
146+
// we don't support the TC channels on SAMD51, isn't worth it.
145147
}
146148
}
147149

@@ -183,8 +185,8 @@ void configureSAMDClock() {
183185
while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));
184186

185187
GCLK->GENCTRL[PWM_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1) | GCLK_GENCTRL_IDC
186-
| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
187-
//| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
188+
//| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
189+
| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
188190
while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));
189191

190192
#ifdef SIMPLEFOC_SAMD_DEBUG
@@ -221,18 +223,27 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
221223
tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
222224
syncTCC(tcc); // wait for sync
223225

226+
// work out pwm resolution for desired frequency and constrain to max/min values
227+
long pwm_resolution = (SIMPLEFOC_SAMD51_DPLL_FREQ/2) / pwm_frequency;
228+
if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
229+
pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
230+
if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
231+
pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
232+
// store for later use
233+
tccConfig.pwm_res = pwm_resolution;
234+
224235
if (hw6pwm>0.0) {
225236
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
226-
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
227-
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
237+
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
238+
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
228239
syncTCC(tcc); // wait for sync
229240
}
230241

231242
if (!tccConfigured[tccConfig.tcc.tccn]) {
232243
tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVE_WAVEGEN_DSTOP; // Set wave form configuration - TODO check this... why set like this?
233244
while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
234245

235-
tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1; // Set counter Top using the PER register
246+
tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
236247
while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
237248

238249
// set all channels to 0%
@@ -254,11 +265,12 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
254265
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
255266
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
256267
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
257-
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
268+
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
269+
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
258270
#endif
259271
}
260272
else if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
261-
Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
273+
//Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
262274

263275
// disable
264276
// tc->COUNT8.CTRLA.bit.ENABLE = 0;
@@ -280,8 +292,9 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
280292
// while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
281293

282294
#ifdef SIMPLEFOC_SAMD_DEBUG
283-
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("Initialized TC ");
295+
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("Not initialized: TC ");
284296
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(tccConfig.tcc.tccn);
297+
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("TC units not supported on SAMD51");
285298
#endif
286299
}
287300

src/drivers/hardware_specific/samd_mcu.cpp

Lines changed: 53 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -315,9 +315,16 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
315315
// e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
316316
configureSAMDClock();
317317

318+
if (pwm_frequency==NOT_SET) {
319+
// use default frequency
320+
pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
321+
}
322+
318323
// configure the TCC (waveform, top-value, pre-scaler = frequency)
319324
configureTCC(tccConfs[0], pwm_frequency);
320325
configureTCC(tccConfs[1], pwm_frequency);
326+
getTccPinConfiguration(pinA)->pwm_res = tccConfs[0].pwm_res;
327+
getTccPinConfiguration(pinB)->pwm_res = tccConfs[1].pwm_res;
321328
#ifdef SIMPLEFOC_SAMD_DEBUG
322329
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("Configured TCCs...");
323330
#endif
@@ -408,10 +415,18 @@ void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const in
408415
// e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
409416
configureSAMDClock();
410417

418+
if (pwm_frequency==NOT_SET) {
419+
// use default frequency
420+
pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
421+
}
422+
411423
// configure the TCC (waveform, top-value, pre-scaler = frequency)
412424
configureTCC(tccConfs[0], pwm_frequency);
413425
configureTCC(tccConfs[1], pwm_frequency);
414426
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;
415430
#ifdef SIMPLEFOC_SAMD_DEBUG
416431
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("Configured TCCs...");
417432
#endif
@@ -479,11 +494,20 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const
479494
// e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
480495
configureSAMDClock();
481496

497+
if (pwm_frequency==NOT_SET) {
498+
// use default frequency
499+
pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
500+
}
501+
482502
// configure the TCC (waveform, top-value, pre-scaler = frequency)
483503
configureTCC(tccConfs[0], pwm_frequency);
484504
configureTCC(tccConfs[1], pwm_frequency);
485505
configureTCC(tccConfs[2], pwm_frequency);
486506
configureTCC(tccConfs[3], pwm_frequency);
507+
getTccPinConfiguration(pin1A)->pwm_res = tccConfs[0].pwm_res;
508+
getTccPinConfiguration(pin2A)->pwm_res = tccConfs[1].pwm_res;
509+
getTccPinConfiguration(pin1B)->pwm_res = tccConfs[2].pwm_res;
510+
getTccPinConfiguration(pin2B)->pwm_res = tccConfs[3].pwm_res;
487511
#ifdef SIMPLEFOC_SAMD_DEBUG
488512
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("Configured TCCs...");
489513
#endif
@@ -579,6 +603,11 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
579603
// e.g. attach all the timers, start them, and then start the clock... but this would require API changes in SimpleFOC driver API
580604
configureSAMDClock();
581605

606+
if (pwm_frequency==NOT_SET) {
607+
// use default frequency
608+
pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
609+
}
610+
582611
// configure the TCC(s)
583612
configureTCC(pinAh, pwm_frequency, false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?dead_zone:-1);
584613
if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo))
@@ -589,6 +618,12 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
589618
configureTCC(pinCh, pwm_frequency, false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?dead_zone:-1);
590619
if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo))
591620
configureTCC(pinCl, pwm_frequency, true, -1.0);
621+
getTccPinConfiguration(pinA_h)->pwm_res = pinAh.pwm_res;
622+
getTccPinConfiguration(pinA_l)->pwm_res = pinAh.pwm_res; // use the high phase resolution, in case we didn't set it
623+
getTccPinConfiguration(pinB_h)->pwm_res = pinBh.pwm_res;
624+
getTccPinConfiguration(pinB_l)->pwm_res = pinBh.pwm_res;
625+
getTccPinConfiguration(pinC_h)->pwm_res = pinCh.pwm_res;
626+
getTccPinConfiguration(pinC_l)->pwm_res = pinCh.pwm_res;
592627
#ifdef SIMPLEFOC_SAMD_DEBUG
593628
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("Configured TCCs...");
594629
#endif
@@ -611,9 +646,9 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
611646
*/
612647
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB) {
613648
tccConfiguration* tccI = getTccPinConfiguration(pinA);
614-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_a);
649+
writeSAMDDutyCycle(tccI, dc_a);
615650
tccI = getTccPinConfiguration(pinB);
616-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_b);
651+
writeSAMDDutyCycle(tccI, dc_b);
617652
return;
618653
}
619654

@@ -635,11 +670,11 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB) {
635670
*/
636671
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC) {
637672
tccConfiguration* tccI = getTccPinConfiguration(pinA);
638-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_a);
673+
writeSAMDDutyCycle(tccI, dc_a);
639674
tccI = getTccPinConfiguration(pinB);
640-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_b);
675+
writeSAMDDutyCycle(tccI, dc_b);
641676
tccI = getTccPinConfiguration(pinC);
642-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_c);
677+
writeSAMDDutyCycle(tccI, dc_c);
643678
return;
644679
}
645680

@@ -662,13 +697,13 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB
662697
*/
663698
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
664699
tccConfiguration* tccI = getTccPinConfiguration(pin1A);
665-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_1a);
700+
writeSAMDDutyCycle(tccI, dc_1a);
666701
tccI = getTccPinConfiguration(pin2A);
667-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_2a);
702+
writeSAMDDutyCycle(tccI, dc_2a);
668703
tccI = getTccPinConfiguration(pin1B);
669-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_1b);
704+
writeSAMDDutyCycle(tccI, dc_1b);
670705
tccI = getTccPinConfiguration(pin2B);
671-
writeSAMDDutyCycle(tccI->tcc.chaninfo, dc_2b);
706+
writeSAMDDutyCycle(tccI, dc_2b);
672707
return;
673708
}
674709

@@ -705,33 +740,33 @@ void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, i
705740
// low-side on a different pin of same TCC - do dead-time in software...
706741
float ls = dc_a+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
707742
if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
708-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a);
709-
writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
743+
writeSAMDDutyCycle(tcc1, dc_a);
744+
writeSAMDDutyCycle(tcc2, ls);
710745
}
711746
else
712-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_a); // dead-time is done is hardware, no need to set low side pin explicitly
747+
writeSAMDDutyCycle(tcc1, dc_a); // dead-time is done is hardware, no need to set low side pin explicitly
713748

714749
tcc1 = getTccPinConfiguration(pinB_h);
715750
tcc2 = getTccPinConfiguration(pinB_l);
716751
if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
717752
float ls = dc_b+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
718753
if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
719-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
720-
writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
754+
writeSAMDDutyCycle(tcc1, dc_b);
755+
writeSAMDDutyCycle(tcc2, ls);
721756
}
722757
else
723-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_b);
758+
writeSAMDDutyCycle(tcc1, dc_b);
724759

725760
tcc1 = getTccPinConfiguration(pinC_h);
726761
tcc2 = getTccPinConfiguration(pinC_l);
727762
if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
728763
float ls = dc_c+(dead_zone*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1));
729764
if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
730-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);
731-
writeSAMDDutyCycle(tcc2->tcc.chaninfo, ls);
765+
writeSAMDDutyCycle(tcc1, dc_c);
766+
writeSAMDDutyCycle(tcc2, ls);
732767
}
733768
else
734-
writeSAMDDutyCycle(tcc1->tcc.chaninfo, dc_c);
769+
writeSAMDDutyCycle(tcc1, dc_c);
735770
return;
736771
}
737772

src/drivers/hardware_specific/samd_mcu.h

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,9 +29,17 @@
2929

3030
#ifndef SIMPLEFOC_SAMD_PWM_RESOLUTION
3131
#define SIMPLEFOC_SAMD_PWM_RESOLUTION 1000
32-
#define SIMPLEFOC_SAMD_PWM_TC_RESOLUTION 250
3332
#endif
3433

34+
#define SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ 24000
35+
// arbitrary maximum. On SAMD51 with 120MHz clock this means 2kHz minimum pwm frequency
36+
#define SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION 30000
37+
// lets not go too low - 400 with clock speed of 120MHz on SAMD51 means 150kHz maximum PWM frequency...
38+
// 400 with 48MHz clock on SAMD21 means 60kHz maximum PWM frequency...
39+
#define SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION 400
40+
// this is the most we can support on the TC units
41+
#define SIMPLEFOC_SAMD_PWM_TC_RESOLUTION 250
42+
3543
#ifndef SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS
3644
#define SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS 24
3745
#endif
@@ -49,6 +57,7 @@ struct tccConfiguration {
4957
};
5058
uint16_t chaninfo;
5159
} tcc;
60+
uint16_t pwm_res;
5261
};
5362

5463

@@ -92,7 +101,7 @@ extern bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
92101

93102

94103
struct wo_association& getWOAssociation(EPortType port, uint32_t pin);
95-
void writeSAMDDutyCycle(int chaninfo, float dc);
104+
void writeSAMDDutyCycle(tccConfiguration* info, float dc);
96105
void configureSAMDClock();
97106
void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate=false, float hw6pwm=-1);
98107
__inline__ void syncTCC(Tcc* TCCx) __attribute__((always_inline, unused));

0 commit comments

Comments
 (0)