SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
samd51_mcu.cpp
Go to the documentation of this file.
1
2
3#include "./samd_mcu.h"
4
5
6#if defined(_SAMD51_)||defined(_SAME51_)
7
8
9#pragma message("")
10#pragma message("SimpleFOC: compiling for SAMD51/SAME51")
11#pragma message("")
12
13
14
15// expected frequency on DPLL, since we don't configure it ourselves. Typically this is the CPU frequency.
16// for custom boards or overclockers you can override it using this define.
17#ifndef SIMPLEFOC_SAMD51_DPLL_FREQ
18#define SIMPLEFOC_SAMD51_DPLL_FREQ 120000000
19#endif
20
21
22#ifndef TCC3_CH0
23#define TCC3_CH0 NOT_ON_TIMER
24#define TCC3_CH1 NOT_ON_TIMER
25#endif
26
27#ifndef TCC4_CH0
28#define TCC4_CH0 NOT_ON_TIMER
29#define TCC4_CH1 NOT_ON_TIMER
30#endif
31
32
33#ifndef TC4_CH0
34#define TC4_CH0 NOT_ON_TIMER
35#define TC4_CH1 NOT_ON_TIMER
36#endif
37
38#ifndef TC5_CH0
39#define TC5_CH0 NOT_ON_TIMER
40#define TC5_CH1 NOT_ON_TIMER
41#endif
42
43#ifndef TC6_CH0
44#define TC6_CH0 NOT_ON_TIMER
45#define TC6_CH1 NOT_ON_TIMER
46#endif
47
48#ifndef TC7_CH0
49#define TC7_CH0 NOT_ON_TIMER
50#define TC7_CH1 NOT_ON_TIMER
51#endif
52
53
54
55// TCC# Channels WO_NUM Counter size Fault Dithering Output matrix DTI SWAP Pattern generation
56// 0 6 8 24-bit Yes Yes Yes Yes Yes Yes
57// 1 4 8 24-bit Yes Yes Yes Yes Yes Yes
58// 2 3 3 16-bit Yes - Yes - - -
59// 3 2 2 16-bit Yes - - - - -
60// 4 2 2 16-bit Yes - - - - -
61
62
63#define NUM_WO_ASSOCIATIONS 72
64
65struct wo_association WO_associations[] = {
66
67 { PORTB, 9, TC4_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
68 { PORTA, 4, TC0_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
69 { PORTA, 5, TC0_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
70 { PORTA, 6, TC1_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
71 { PORTA, 7, TC1_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
72 { PORTC, 4, NOT_ON_TIMER, 0, TCC0_CH0, 0, NOT_ON_TIMER, 0},
73 // PC05, PC06, PC07 -> no timers
74 { PORTA, 8, TC0_CH0, 0, TCC0_CH0, 0, TCC1_CH0, 4},
75 { PORTA, 9, TC0_CH1, 1, TCC0_CH1, 1, TCC1_CH1, 5},
76 { PORTA, 10, TC1_CH0, 0, TCC0_CH2, 2, TCC1_CH2, 6},
77 { PORTA, 11, TC1_CH1, 1, TCC0_CH3, 3, TCC1_CH3, 7},
78 { PORTB, 10, TC5_CH0, 0, TCC0_CH4, 4, TCC1_CH0, 0},
79 { PORTB, 11, TC5_CH1, 1, TCC0_CH5, 5, TCC1_CH1, 1},
80 { PORTB, 12, TC4_CH0, 0, TCC3_CH0, 0, TCC0_CH0, 0},
81 { PORTB, 13, TC4_CH1, 1, TCC3_CH1, 1, TCC0_CH1, 1},
82 { PORTB, 14, TC5_CH0, 0, TCC4_CH0, 0, TCC0_CH2, 2},
83 { PORTB, 15, TC5_CH1, 1, TCC4_CH1, 1, TCC0_CH3, 3},
84 { PORTD, 8, NOT_ON_TIMER, 0, TCC0_CH1, 1, NOT_ON_TIMER, 0},
85 { PORTD, 9, NOT_ON_TIMER, 0, TCC0_CH2, 2, NOT_ON_TIMER, 0},
86 { PORTD, 10, NOT_ON_TIMER, 0, TCC0_CH3, 3, NOT_ON_TIMER, 0},
87 { PORTD, 11, NOT_ON_TIMER, 0, TCC0_CH4, 4, NOT_ON_TIMER, 0},
88 { PORTD, 12, NOT_ON_TIMER, 0, TCC0_CH5, 5, NOT_ON_TIMER, 0},
89 { PORTC, 10, NOT_ON_TIMER, 0, TCC0_CH0, 0, TCC1_CH0, 4},
90 { PORTC, 11, NOT_ON_TIMER, 0, TCC0_CH1, 1, TCC1_CH1, 5},
91 { PORTC, 12, NOT_ON_TIMER, 0, TCC0_CH2, 2, TCC1_CH2, 6},
92 { PORTC, 13, NOT_ON_TIMER, 0, TCC0_CH3, 3, TCC1_CH3, 7},
93 { PORTC, 14, NOT_ON_TIMER, 0, TCC0_CH4, 4, TCC1_CH0, 0},
94 { PORTC, 15, NOT_ON_TIMER, 0, TCC0_CH5, 5, TCC1_CH1, 1},
95 { PORTA, 12, TC2_CH0, 0, TCC0_CH0, 6, TCC1_CH2, 2},
96 { PORTA, 13, TC2_CH1, 1, TCC0_CH1, 7, TCC1_CH3, 3},
97 { PORTA, 14, TC3_CH0, 0, TCC2_CH0, 0, TCC1_CH2, 2},
98 { PORTA, 15, TC3_CH1, 1, TCC2_CH1, 1, TCC1_CH3, 3},
99 { PORTA, 16, TC2_CH0, 0, TCC1_CH0, 0, TCC0_CH4, 4},
100 { PORTA, 17, TC2_CH1, 1, TCC1_CH1, 1, TCC0_CH5, 5},
101 { PORTA, 18, TC3_CH0, 0, TCC1_CH2, 2, TCC0_CH0, 6},
102 { PORTA, 19, TC3_CH1, 1, TCC1_CH3, 3, TCC0_CH1, 7},
103 { PORTC, 16, NOT_ON_TIMER, 0, TCC0_CH0, 0, NOT_ON_TIMER, 0}, // PDEC0
104 { PORTC, 17, NOT_ON_TIMER, 0, TCC0_CH1, 1, NOT_ON_TIMER, 0}, // PDEC1
105 { PORTC, 18, NOT_ON_TIMER, 0, TCC0_CH2, 2, NOT_ON_TIMER, 0}, // PDEC2
106 { PORTC, 19, NOT_ON_TIMER, 0, TCC0_CH3, 3, NOT_ON_TIMER, 0},
107 { PORTC, 20, NOT_ON_TIMER, 0, TCC0_CH4, 4, NOT_ON_TIMER, 0},
108 { PORTC, 21, NOT_ON_TIMER, 0, TCC0_CH5, 5, NOT_ON_TIMER, 0},
109 { PORTC, 22, NOT_ON_TIMER, 0, TCC0_CH0, 6, NOT_ON_TIMER, 0},
110 { PORTC, 23, NOT_ON_TIMER, 0, TCC0_CH1, 7, NOT_ON_TIMER, 0},
111 { PORTD, 20, NOT_ON_TIMER, 0, TCC1_CH0, 0, NOT_ON_TIMER, 0},
112 { PORTD, 21, NOT_ON_TIMER, 0, TCC1_CH1, 1, NOT_ON_TIMER, 0},
113 { PORTB, 16, TC6_CH0, 0, TCC3_CH0, 0, TCC0_CH4, 4},
114 { PORTB, 17, TC6_CH1, 1, TCC3_CH1, 1, TCC0_CH5, 5},
115 { PORTB, 18, NOT_ON_TIMER, 0, TCC1_CH0, 0, NOT_ON_TIMER, 0}, // PDEC0
116 { PORTB, 19, NOT_ON_TIMER, 0, TCC1_CH1, 1, NOT_ON_TIMER, 0}, // PDEC1
117 { PORTB, 20, NOT_ON_TIMER, 0, TCC1_CH2, 2, NOT_ON_TIMER, 0}, // PDEC2
118 { PORTB, 21, NOT_ON_TIMER, 0, TCC1_CH3, 3, NOT_ON_TIMER, 0},
119 { PORTA, 20, TC7_CH0, 0, TCC1_CH0, 4, TCC0_CH0, 0},
120 { PORTA, 21, TC7_CH1, 1, TCC1_CH1, 5, TCC0_CH1, 1},
121 { PORTA, 22, TC4_CH0, 0, TCC1_CH2, 6, TCC0_CH2, 2},
122 { PORTA, 23, TC4_CH1, 1, TCC1_CH3, 7, TCC0_CH3, 3},
123 { PORTA, 24, TC5_CH0, 0, TCC2_CH2, 2, NOT_ON_TIMER, 0}, // PDEC0
124 { PORTA, 25, TC5_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC1
125 { PORTB, 22, TC7_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC2
126 { PORTB, 23, TC7_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC0
127 { PORTB, 24, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC1
128 { PORTB, 25, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC2
129 { PORTB, 26, NOT_ON_TIMER, 0, TCC1_CH2, 2, NOT_ON_TIMER, 0},
130 { PORTB, 27, NOT_ON_TIMER, 0, TCC1_CH3, 3, NOT_ON_TIMER, 0},
131 { PORTB, 28, NOT_ON_TIMER, 0, TCC1_CH0, 4, NOT_ON_TIMER, 0},
132 { PORTB, 29, NOT_ON_TIMER, 0, TCC1_CH1, 5, NOT_ON_TIMER, 0},
133 // PC24-PC28, PA27, RESET -> no TC/TCC peripherals
134 { PORTA, 30, TC6_CH0, 0, TCC2_CH0, 0, NOT_ON_TIMER, 0},
135 { PORTA, 31, TC6_CH1, 1, TCC2_CH1, 1, NOT_ON_TIMER, 0},
136 { PORTB, 30, TC0_CH0, 0, TCC4_CH0, 0, TCC0_CH0, 6},
137 { PORTB, 31, TC0_CH1, 1, TCC4_CH1, 1, TCC0_CH1, 7},
138 // PC30, PC31 -> no TC/TCC peripherals
139 { PORTB, 0, TC7_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
140 { PORTB, 1, TC7_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
141 { PORTB, 2, TC6_CH0, 0, TCC2_CH2, 2, NOT_ON_TIMER, 0},
142
143};
144
145wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};
146
147#ifndef TCC3_CC_NUM
148uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM };
149#else
150uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM, TCC3_CC_NUM, TCC4_CC_NUM };
151#endif
152
153
154struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
155 for (int i=0;i<NUM_WO_ASSOCIATIONS;i++) {
156 if (WO_associations[i].port==port && WO_associations[i].pin==pin)
157 return WO_associations[i];
158 }
159 return ASSOCIATION_NOT_FOUND;
160};
161
162
163EPioType getPeripheralOfPermutation(int permutation, int pin_position) {
164 return ((permutation>>pin_position)&0x01)==0x1?PIO_TCC_PDEC:PIO_TIMER_ALT;
165}
166
167
168
169void syncTCC(Tcc* TCCx) {
170 while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK);
171}
172
173
174
175
176void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
177 uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
178 uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
179 if (tccn<TCC_INST_NUM) {
180 Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
181 // set via CCBUF
182// while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
183 tcc->CCBUF[chan].reg = (uint32_t)((info->pwm_res-1) * dc); // TODO pwm frequency!
184 }
185 else {
186 // we don't support the TC channels on SAMD51, isn't worth it.
187 }
188}
189
190
191#define DPLL_CLOCK_NUM 2 // use GCLK2
192#define PWM_CLOCK_NUM 3 // use GCLK3
193
194
195/**
196 * Configure Clock 4 - we want all simplefoc PWMs to use the same clock. This ensures that
197 * any compatible pin combination can be used without having to worry about configuring different
198 * clocks.
199 */
200void configureSAMDClock() {
201 if (!SAMDClockConfigured) {
202 SAMDClockConfigured = true; // mark clock as configured
203 for (int i=0;i<TCC_INST_NUM;i++) // mark all the TCCs as not yet configured
204 tccConfigured[i] = false;
205
206 // GCLK->GENCTRL[DPLL_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1)
207 // | GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
208 // while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<DPLL_CLOCK_NUM));
209
210 // GCLK->PCHCTRL[1].reg = GCLK_PCHCTRL_GEN(DPLL_CLOCK_NUM)|GCLK_PCHCTRL_CHEN;
211 // while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<DPLL_CLOCK_NUM));
212
213 // OSCCTRL->Dpll[0].DPLLCTRLA.bit.ENABLE = 0;
214 // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
215
216 // OSCCTRL->Dpll[0].DPLLCTRLB.bit.REFCLK = OSCCTRL_DPLLCTRLB_REFCLK_GCLK_Val;
217 // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
218 // OSCCTRL->Dpll[0].DPLLRATIO.reg = 3;
219 // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
220
221 // OSCCTRL->Dpll[0].DPLLCTRLA.bit.ENABLE = 1;
222 // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
223
224 GCLK->GENCTRL[PWM_CLOCK_NUM].bit.GENEN = 0;
225 while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));
226
227 GCLK->GENCTRL[PWM_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1) | GCLK_GENCTRL_IDC
228 //| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
229 | GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
230 while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));
231
232#ifdef SIMPLEFOC_SAMD_DEBUG
233 SIMPLEFOC_DEBUG("SAMD: Configured clock...");
234#endif
235 }
236}
237
238
239
240
241
242/**
243 * Configure a TCC unit
244 * pwm_frequency is fixed at 24kHz for now. We could go slower, but going
245 * faster won't be possible without sacrificing resolution.
246 */
247void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, float hw6pwm) {
248 // TODO for the moment we ignore the frequency...
249 if (!tccConfigured[tccConfig.tcc.tccn]) {
250 uint32_t GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_IDs[tccConfig.tcc.tccn];
251 GCLK->PCHCTRL[GCLK_CLKCTRL_ID_ofthistcc].reg = GCLK_PCHCTRL_GEN(PWM_CLOCK_NUM)|GCLK_PCHCTRL_CHEN;
252 while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));
253 }
254
255 if (tccConfig.tcc.tccn<TCC_INST_NUM) {
256 Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
257
258 tcc->CTRLA.bit.ENABLE = 0; //switch off tcc
259 while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
260
261 uint8_t invenMask = ~(1<<tccConfig.tcc.chan); // negate (invert) the signal if needed
262 uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
263 tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
264 syncTCC(tcc); // wait for sync
265
266 // work out pwm resolution for desired frequency and constrain to max/min values
267 long pwm_resolution = (SIMPLEFOC_SAMD51_DPLL_FREQ/2) / pwm_frequency;
268 if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
269 pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
270 if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
271 pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
272 // store for later use
273 tccConfig.pwm_res = pwm_resolution;
274
275 if (hw6pwm>0.0) {
276 tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
277 tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
278 tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
279 syncTCC(tcc); // wait for sync
280 }
281
282 if (!tccConfigured[tccConfig.tcc.tccn]) {
283 tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVE_WAVEGEN_DSTOP; // Set wave form configuration - TODO check this... why set like this?
284 while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
285
286 tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
287 while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
288
289 // set all channels to 0%
290 for (int i=0;i<TCC_CHANNEL_COUNT[tccConfig.tcc.tccn];i++) {
291 tcc->CC[i].reg = 0; // start off at 0% duty cycle
292 uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
293 while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
294 }
295 }
296
297 // Enable TCC
298 tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1; //48Mhz/1=48Mhz/2(up/down)=24MHz/1024=24KHz
299 while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
300
301#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
302 SimpleFOCDebug::print("SAMD: (Re-)Initialized TCC ");
303 SimpleFOCDebug::print(tccConfig.tcc.tccn);
305 SimpleFOCDebug::print(tccConfig.tcc.chan);
307 SimpleFOCDebug::print(tccConfig.wo);
308 SimpleFOCDebug::print("] pwm res ");
309 SimpleFOCDebug::print((int)pwm_resolution);
311#endif
312 }
313 else if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
314 //Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
315
316 // disable
317 // tc->COUNT8.CTRLA.bit.ENABLE = 0;
318 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
319 // // unfortunately we need the 8-bit counter mode to use the PER register...
320 // tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
321 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
322 // // meaning prescaler of 8, since TC-Unit has no up/down mode, and has resolution of 250 rather than 1000...
323 // tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
324 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
325 // // period is 250, period cannot be higher than 256!
326 // tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
327 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
328 // // initial duty cycle is 0
329 // tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
330 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
331 // // enable
332 // tc->COUNT8.CTRLA.bit.ENABLE = 1;
333 // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
334
335 #ifdef SIMPLEFOC_SAMD_DEBUG
336 SIMPLEFOC_DEBUG("SAMD: Not initialized: TC ", tccConfig.tcc.tccn);
337 SIMPLEFOC_DEBUG("SAMD: TC units not supported on SAMD51");
338 #endif
339 }
340
341 // set as configured
342 tccConfigured[tccConfig.tcc.tccn] = true;
343
344
345}
346
347
348
349
350
351#endif
#define SIMPLEFOC_DEBUG(msg,...)
static void print(const char *msg)
static void println()