Skip to content

Commit ddc5ec3

Browse files
Merge pull request #134 from runger1101001/dev
SAMD code improvements
2 parents ffd2c5d + 64de2e4 commit ddc5ec3

File tree

4 files changed

+128
-59
lines changed

4 files changed

+128
-59
lines changed

src/drivers/hardware_specific/samd21_mcu.cpp

Lines changed: 26 additions & 14 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

@@ -177,6 +178,15 @@ void configureSAMDClock() {
177178
* faster won't be possible without sacrificing resolution.
178179
*/
179180
void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, float hw6pwm) {
181+
182+
long pwm_resolution = (24000000) / pwm_frequency;
183+
if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
184+
pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
185+
if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
186+
pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
187+
// store for later use
188+
tccConfig.pwm_res = pwm_resolution;
189+
180190
// TODO for the moment we ignore the frequency...
181191
if (!tccConfigured[tccConfig.tcc.tccn]) {
182192
uint32_t GCLK_CLKCTRL_ID_ofthistcc = -1;
@@ -234,12 +244,12 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
234244

235245
if (hw6pwm>0.0) {
236246
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
237-
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
238-
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
247+
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
248+
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
239249
syncTCC(tcc); // wait for sync
240250
}
241251

242-
tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1; // Set counter Top using the PER register
252+
tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
243253
while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
244254

245255
// set all channels to 0%
@@ -261,7 +271,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
261271
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
262272
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
263273
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
264-
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
274+
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
275+
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
265276
#endif
266277
}
267278
}
@@ -279,8 +290,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
279290

280291
if (hw6pwm>0.0) {
281292
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
282-
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
283-
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
293+
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
294+
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
284295
syncTCC(tcc); // wait for sync
285296
}
286297

@@ -294,7 +305,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
294305
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
295306
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
296307
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
297-
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
308+
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
309+
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
298310
#endif
299311
}
300312

@@ -305,26 +317,26 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
305317

306318

307319

308-
void writeSAMDDutyCycle(int chaninfo, float dc) {
309-
uint8_t tccn = GetTCNumber(chaninfo);
310-
uint8_t chan = GetTCChannelNumber(chaninfo);
320+
void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
321+
uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
322+
uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
311323
if (tccn<TCC_INST_NUM) {
312-
Tcc* tcc = (Tcc*)GetTC(chaninfo);
324+
Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
313325
// set via CC
314326
// tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
315327
// uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
316328
// while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
317329
// set via CCB
318-
while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
319-
tcc->CCB[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
330+
//while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
331+
tcc->CCB[chan].reg = (uint32_t)((info->pwm_res-1) * dc);
320332
// while ( (tcc->SYNCBUSY.vec.CCB & (0x1<<chan)) > 0 );
321333
// tcc->STATUS.vec.CCBV |= (0x1<<chan);
322334
// while ( tcc->SYNCBUSY.bit.STATUS > 0 );
323335
// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
324336
// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
325337
}
326338
else {
327-
Tc* tc = (Tc*)GetTC(chaninfo);
339+
Tc* tc = (Tc*)GetTC(info->tcc.chaninfo);
328340
tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
329341
while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
330342
}

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

0 commit comments

Comments
 (0)