SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
drivers/hardware_specific/samd/samd21_mcu.cpp
Go to the documentation of this file.
1
2
3
4#include "./samd_mcu.h"
5
6
7#ifdef _SAMD21_
8
9
10#pragma message("")
11#pragma message("SimpleFOC: compiling for SAMD21")
12#pragma message("")
13
14
15#ifndef TCC3_CH0
16#define TCC3_CH0 NOT_ON_TIMER
17#endif
18#ifndef TCC3_CH1
19#define TCC3_CH1 NOT_ON_TIMER
20#endif
21#ifndef TCC3_CH2
22#define TCC3_CH2 NOT_ON_TIMER
23#endif
24#ifndef TCC3_CH3
25#define TCC3_CH3 NOT_ON_TIMER
26#endif
27#ifndef TCC3_CH4
28#define TCC3_CH4 NOT_ON_TIMER
29#endif
30#ifndef TCC3_CH5
31#define TCC3_CH5 NOT_ON_TIMER
32#endif
33#ifndef TCC3_CH6
34#define TCC3_CH6 NOT_ON_TIMER
35#endif
36#ifndef TCC3_CH7
37#define TCC3_CH7 NOT_ON_TIMER
38#endif
39#ifndef TC6_CH0
40#define TC6_CH0 NOT_ON_TIMER
41#endif
42#ifndef TC6_CH1
43#define TC6_CH1 NOT_ON_TIMER
44#endif
45#ifndef TC7_CH0
46#define TC7_CH0 NOT_ON_TIMER
47#endif
48#ifndef TC7_CH1
49#define TC7_CH1 NOT_ON_TIMER
50#endif
51
52
53
54#define NUM_WO_ASSOCIATIONS 48
55
56/*
57 * For SAM D21 A/B/C/D Variant Devices and SAM DA1 A/B Variant Devices
58 * Good for SAMD2xE, SAMD2xG and SAMD2xJ devices. Other SAMD21s currently not supported in arduino anyway?
59 *
60 * Note: only the pins which have timers associated are listed in this table.
61 * You can use the values from g_APinDescription.ulPort and g_APinDescription.ulPin to find the correct row in the table.
62 *
63 * See Microchip Technology datasheet DS40001882F-page 30
64 */
65struct wo_association WO_associations[] = {
66
67 { PORTA, 0, TCC2_CH0, 0, NOT_ON_TIMER, 0},
68 { PORTA, 1, TCC2_CH1, 1, NOT_ON_TIMER, 0},
69 { PORTA, 2, NOT_ON_TIMER, 0, TCC3_CH0, 0},
70 { PORTA, 3, NOT_ON_TIMER, 0, TCC3_CH1, 1},
71 // PB04, PB05, PB06, PB07 - no timers
72 { PORTB, 8, TC4_CH0, 0, TCC3_CH6, 6},
73 { PORTB, 9, TC4_CH1, 1, TCC3_CH7, 7},
74 { PORTA, 4, TCC0_CH0, 0, TCC3_CH2, 2},
75 { PORTA, 5, TCC0_CH1, 1, TCC3_CH3, 3},
76 { PORTA, 6, TCC1_CH0, 0, TCC3_CH4, 4},
77 { PORTA, 7, TCC1_CH1, 1, TCC3_CH5, 5},
78 { PORTA, 8, TCC0_CH0, 0, TCC1_CH2, 2},
79 { PORTA, 9, TCC0_CH1, 1, TCC1_CH3, 3},
80 { PORTA, 10, TCC1_CH0, 0, TCC0_CH2, 2},
81 { PORTA, 11, TCC1_CH1, 1, TCC0_CH3, 3},
82 { PORTB, 10, TC5_CH0, 0, TCC0_CH4, 4},
83 { PORTB, 11, TC5_CH1, 1, TCC0_CH5, 5},
84 { PORTB, 12, TC4_CH0, 0, TCC0_CH6, 6},
85 { PORTB, 13, TC4_CH1, 1, TCC0_CH7, 7},
86 { PORTB, 14, TC5_CH0, 0, NOT_ON_TIMER, 0},
87 { PORTB, 15, TC5_CH1, 1, NOT_ON_TIMER, 0},
88 { PORTA, 12, TCC2_CH0, 0, TCC0_CH6, 6},
89 { PORTA, 13, TCC2_CH1, 1, TCC0_CH7, 7},
90 { PORTA, 14, TC3_CH0, 0, TCC0_CH4, 4},
91 { PORTA, 15, TC3_CH1, 1, TCC0_CH5, 5},
92 { PORTA, 16, TCC2_CH0, 0, TCC0_CH6, 6},
93 { PORTA, 17, TCC2_CH1, 1, TCC0_CH7, 7},
94 { PORTA, 18, TC3_CH0, 0, TCC0_CH2, 2},
95 { PORTA, 19, TC3_CH1, 1, TCC0_CH3, 3},
96 { PORTB, 16, TC6_CH0, 0, TCC0_CH4, 4},
97 { PORTB, 17, TC6_CH1, 1, TCC0_CH5, 5},
98 { PORTA, 20, TC7_CH0, 0, TCC0_CH6, 6},
99 { PORTA, 21, TC7_CH1, 1, TCC0_CH7, 7},
100 { PORTA, 22, TC4_CH0, 0, TCC0_CH4, 4},
101 { PORTA, 23, TC4_CH1, 1, TCC0_CH5, 5},
102 { PORTA, 24, TC5_CH0, 0, TCC1_CH2, 2},
103 { PORTA, 25, TC5_CH1, 1, TCC1_CH3, 3},
104 { PORTB, 22, TC7_CH0, 0, TCC3_CH0, 0},
105 { PORTB, 23, TC7_CH1, 1, TCC3_CH1, 1},
106 { PORTA, 27, NOT_ON_TIMER, 0, TCC3_CH6, 6},
107 { PORTA, 28, NOT_ON_TIMER, 0, TCC3_CH7, 7},
108 { PORTA, 30, TCC1_CH0, 0, TCC3_CH4, 4},
109 { PORTA, 31, TCC1_CH1, 1, TCC3_CH5, 5},
110 { PORTB, 30, TCC0_CH0, 0, TCC1_CH2, 2},
111 { PORTB, 31, TCC0_CH1, 1, TCC1_CH3, 3},
112 { PORTB, 0, TC7_CH0, 0, NOT_ON_TIMER, 0},
113 { PORTB, 1, TC7_CH1, 1, NOT_ON_TIMER, 0},
114 { PORTB, 2, TC6_CH0, 0, TCC3_CH2, 2},
115 { PORTB, 3, TC6_CH1, 1, TCC3_CH3, 3}
116};
117wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};
118
119
120
121struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
122 for (int i=0;i<NUM_WO_ASSOCIATIONS;i++) {
123 if (WO_associations[i].port==port && WO_associations[i].pin==pin)
124 return WO_associations[i];
125 }
126 return ASSOCIATION_NOT_FOUND;
127};
128
129
130
131EPioType getPeripheralOfPermutation(int permutation, int pin_position) {
132 return ((permutation>>pin_position)&0x01)==0x1?PIO_TIMER_ALT:PIO_TIMER;
133}
134
135
136
137
138
139void syncTCC(Tcc* TCCx) {
140 while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK); // Wait for synchronization of registers between the clock domains
141}
142
143
144
145/**
146 * Configure Clock 4 - we want all simplefoc PWMs to use the same clock. This ensures that
147 * any compatible pin combination can be used without having to worry about configuring different
148 * clocks.
149 */
150void configureSAMDClock() {
151
152 // TODO investigate using the FDPLL96M clock to get 96MHz timer clocks... this
153 // would enable 48KHz PWM clocks, and setting the frequency between 24Khz with resolution 2000, to 48KHz with resolution 1000
154
155 if (!SAMDClockConfigured) {
156 SAMDClockConfigured = true; // mark clock as configured
157 for (int i=0;i<TCC_INST_NUM;i++) // mark all the TCCs as not yet configured
158 tccConfigured[i] = false;
159 REG_GCLK_GENDIV = GCLK_GENDIV_DIV(1) | // Divide the 48MHz clock source by divisor N=1: 48MHz/1=48MHz
160 GCLK_GENDIV_ID(4); // Select Generic Clock (GCLK) 4
161 while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
162
163 REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
164 GCLK_GENCTRL_GENEN | // Enable GCLK4
165 GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
166 // GCLK_GENCTRL_SRC_FDPLL | // Set the 96MHz clock source
167 GCLK_GENCTRL_ID(4); // Select GCLK4
168 while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
169
170#ifdef SIMPLEFOC_SAMD_DEBUG
171 SIMPLEFOC_DEBUG("SAMD: Configured clock...");
172#endif
173 }
174}
175
176
177
178
179/**
180 * Configure a TCC unit
181 * pwm_frequency is fixed at 24kHz for now. We could go slower, but going
182 * faster won't be possible without sacrificing resolution.
183 */
184void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, float hw6pwm) {
185
186 long pwm_resolution = (24000000) / pwm_frequency;
187 if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
188 pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
189 if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
190 pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
191 // store for later use
192 tccConfig.pwm_res = pwm_resolution;
193
194 // TODO for the moment we ignore the frequency...
195 if (!tccConfigured[tccConfig.tcc.tccn]) {
196 uint32_t GCLK_CLKCTRL_ID_ofthistcc = -1;
197 switch (tccConfig.tcc.tccn>>1) {
198 case 0: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC0_TCC1); break; //GCLK_CLKCTRL_ID_TCC0_TCC1;
199 case 1: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC2_TC3); break; //GCLK_CLKCTRL_ID_TCC2_TC3;
200 case 2: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC4_TC5); break; //GCLK_CLKCTRL_ID_TC4_TC5;
201 case 3: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC6_TC7); break;
202 default: return;
203 }
204
205 // Feed GCLK4 to TCC
206 REG_GCLK_CLKCTRL = (uint16_t) GCLK_CLKCTRL_CLKEN | // Enable GCLK4
207 GCLK_CLKCTRL_GEN_GCLK4 | // Select GCLK4
208 GCLK_CLKCTRL_ID_ofthistcc; // Feed GCLK4 to tcc
209 while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
210
211 tccConfigured[tccConfig.tcc.tccn] = true;
212
213 if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
214 Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
215 // disable
216 tc->COUNT8.CTRLA.bit.ENABLE = 0;
217 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
218 // unfortunately we need the 8-bit counter mode to use the PER register...
219 tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
220 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
221 // meaning prescaler of 8, since TC-Unit has no up/down mode, and has resolution of 250 rather than 1000...
222 tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
223 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
224 // period is 250, period cannot be higher than 256!
225 tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
226 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
227 // initial duty cycle is 0
228 tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
229 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
230 // enable
231 tc->COUNT8.CTRLA.bit.ENABLE = 1;
232 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
233#ifdef SIMPLEFOC_SAMD_DEBUG
234 SIMPLEFOC_DEBUG("SAMD: Initialized TC ", tccConfig.tcc.tccn);
235#endif
236 }
237 else {
238 Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
239
240 uint8_t invenMask = ~(1<<tccConfig.tcc.chan); // negate (invert) the signal if needed
241 uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
242 tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
243 syncTCC(tcc); // wait for sync
244
245 tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVEB_WAVEGENB_DSBOTH; // Set wave form configuration
246 while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
247
248 if (hw6pwm>0.0) {
249 tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
250 tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
251 tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
252 syncTCC(tcc); // wait for sync
253 }
254
255 tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
256 while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
257
258 // set all channels to 0%
259 uint8_t chanCount = (tccConfig.tcc.tccn==1||tccConfig.tcc.tccn==2)?2:4;
260 for (int i=0;i<chanCount;i++) {
261 tcc->CC[i].reg = 0; // start off at 0% duty cycle
262 uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
263 while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
264 }
265
266 // Enable TC
267 tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1; //48Mhz/1=48Mhz/2(up/down)=24MHz/1024=24KHz
268 while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
269
270#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
271 SimpleFOCDebug::print("SAMD: Initialized TCC ");
272 SimpleFOCDebug::print(tccConfig.tcc.tccn);
274 SimpleFOCDebug::print(tccConfig.tcc.chan);
276 SimpleFOCDebug::print(tccConfig.wo);
277 SimpleFOCDebug::print("] pwm res ");
278 SimpleFOCDebug::print((int)pwm_resolution);
280#endif
281 }
282 }
283 else if (tccConfig.tcc.tccn<TCC_INST_NUM) {
284 // set invert bit for TCC channels in SW 6-PWM...
285 Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
286
287 tcc->CTRLA.bit.ENABLE = 0;
288 while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
289
290 uint8_t invenMask = ~(1<<tccConfig.tcc.chan); // negate (invert) the signal if needed
291 uint8_t invenVal = negate?(1<<tccConfig.tcc.chan):0;
292 tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
293 syncTCC(tcc); // wait for sync
294
295 if (hw6pwm>0.0) {
296 tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
297 tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
298 tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
299 syncTCC(tcc); // wait for sync
300 }
301
302 tcc->CTRLA.bit.ENABLE = 1;
303 while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
304
305#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
306 SimpleFOCDebug::print("SAMD: (Re-)Initialized TCC ");
307 SimpleFOCDebug::print(tccConfig.tcc.tccn);
309 SimpleFOCDebug::print(tccConfig.tcc.chan);
311 SimpleFOCDebug::print(tccConfig.wo);
312 SimpleFOCDebug::print("] pwm res ");
313 SimpleFOCDebug::print((int)pwm_resolution);
315#endif
316 }
317
318
319}
320
321
322
323
324
325void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
326 uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
327 uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
328 if (tccn<TCC_INST_NUM) {
329 Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
330 // set via CC
331// tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
332// uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
333// while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
334 // set via CCB
335 //while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
336 tcc->CCB[chan].reg = (uint32_t)((info->pwm_res-1) * dc);
337// while ( (tcc->SYNCBUSY.vec.CCB & (0x1<<chan)) > 0 );
338// tcc->STATUS.vec.CCBV |= (0x1<<chan);
339// while ( tcc->SYNCBUSY.bit.STATUS > 0 );
340// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
341// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
342 }
343 else {
344 Tc* tc = (Tc*)GetTC(info->tcc.chaninfo);
345 tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
346 while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
347 }
348}
349
350
351
352
353#endif
#define SIMPLEFOC_DEBUG(msg,...)
static void print(const char *msg)
static void println()