1
+ #ifdef _SAMD21_
2
+
3
+ #include " samd21_mcu.h"
4
+ #include " ../hardware_api.h"
5
+
6
+
7
+ static bool freeRunning = false ;
8
+ static int _pinA, _pinB, _pinC;
9
+ static uint16_t a = 0xFFFF , b = 0xFFFF , c = 0xFFFF ; // updated by adcStopWithDMA when configured in freerunning mode
10
+ static SAMDCurrentSenseADCDMA instance;
11
+ /* *
12
+ * function reading an ADC value and returning the read voltage
13
+ *
14
+ * @param pinA - adc pin A
15
+ * @param pinB - adc pin B
16
+ * @param pinC - adc pin C
17
+ */
18
+ void _configureADCLowSide (const int pinA,const int pinB,const int pinC)
19
+ {
20
+ _pinA = pinA;
21
+ _pinB = pinB;
22
+ _pinC = pinC;
23
+ freeRunning = true ;
24
+ instance.init (pinA, pinB, pinC);
25
+
26
+ }
27
+ void _startADC3PinConversionLowSide ()
28
+ {
29
+ instance.startADCScan ();
30
+ }
31
+ /* *
32
+ * function reading an ADC value and returning the read voltage
33
+ *
34
+ * @param pinA - the arduino pin to be read (it has to be ADC pin)
35
+ */
36
+ float _readADCVoltageLowSide (const int pinA)
37
+ {
38
+ instance.readResults (a, b, c);
39
+
40
+ if (pinA == _pinA)
41
+ return instance.toVolts (a);
42
+ if (pinA == _pinB)
43
+ return instance.toVolts (b);
44
+ if (pinA == _pinC)
45
+ return instance.toVolts (c);
46
+
47
+ return NAN;
48
+ }
49
+
50
+ /* *
51
+ * function syncing the Driver with the ADC for the LowSide Sensing
52
+ */
53
+ void _driverSyncLowSide ()
54
+ {
55
+ SIMPLEFOC_SAMD_DEBUG_SERIAL.println (F (" TODO! _driverSyncLowSide() is not implemented" ));
56
+ instance.startADCScan ();
57
+ // TODO: hook with PWM interrupts
58
+ }
59
+
60
+
61
+
62
+
63
+
64
+
65
+
66
+
67
+
68
+
69
+ // Credit: significant portions of this code were pulled from Paul Gould's git https://github.com/gouldpa/FOC-Arduino-Brushless
70
+
71
+ static void adcStopWithDMA (void );
72
+ static void adcStartWithDMA (void );
73
+
74
+ /* *
75
+ * @brief ADC sync wait
76
+ * @retval void
77
+ */
78
+ static __inline__ void ADCsync () __attribute__((always_inline, unused));
79
+ static void ADCsync () {
80
+ while (ADC->STATUS .bit .SYNCBUSY == 1 ); // Just wait till the ADC is free
81
+ }
82
+
83
+ // ADC DMA sequential free running (6) with Interrupts /////////////////
84
+
85
+ SAMDCurrentSenseADCDMA * SAMDCurrentSenseADCDMA::getHardwareAPIInstance ()
86
+ {
87
+
88
+ return &instance;
89
+ }
90
+
91
+ SAMDCurrentSenseADCDMA::SAMDCurrentSenseADCDMA ()
92
+ {
93
+ }
94
+
95
+ void SAMDCurrentSenseADCDMA::init (int pinA, int pinB, int pinC, int pinAREF, float voltageAREF, uint32_t adcBits, uint32_t channelDMA)
96
+ {
97
+ this ->pinA = pinA;
98
+ this ->pinB = pinB;
99
+ this ->pinC = pinC;
100
+ this ->pinAREF = pinAREF;
101
+ this ->channelDMA = channelDMA;
102
+ this ->voltageAREF = voltageAREF;
103
+ this ->maxCountsADC = 1 << adcBits;
104
+ countsToVolts = ( voltageAREF / maxCountsADC );
105
+
106
+ initPins ();
107
+ initADC ();
108
+ initDMA ();
109
+ startADCScan (); // so we have something to read next time we call readResults()
110
+ }
111
+
112
+
113
+ void SAMDCurrentSenseADCDMA::startADCScan (){
114
+ adcToDMATransfer (adcBuffer + oneBeforeFirstAIN, BufferSize);
115
+ adcStartWithDMA ();
116
+ }
117
+
118
+ bool SAMDCurrentSenseADCDMA::readResults (uint16_t & a, uint16_t & b, uint16_t & c){
119
+ if (ADC->CTRLA .bit .ENABLE )
120
+ return false ;
121
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber ;
122
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber ;
123
+ a = adcBuffer[ainA];
124
+ b = adcBuffer[ainB];
125
+ if (_isset (pinC))
126
+ {
127
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber ;
128
+ c = adcBuffer[ainC];
129
+ }
130
+ return true ;
131
+ }
132
+
133
+
134
+ float SAMDCurrentSenseADCDMA::toVolts (uint16_t counts) {
135
+ return counts * countsToVolts;
136
+ }
137
+
138
+ void SAMDCurrentSenseADCDMA::initPins (){
139
+
140
+ pinMode (pinAREF, INPUT);
141
+ pinMode (pinA, INPUT);
142
+ pinMode (pinB, INPUT);
143
+
144
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber ;
145
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber ;
146
+ firstAIN = min (ainA, ainB);
147
+ lastAIN = max (ainA, ainB);
148
+ if ( _isset (pinC) )
149
+ {
150
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber ;
151
+ pinMode (pinC, INPUT);
152
+ firstAIN = min (firstAIN, ainC);
153
+ lastAIN = max (lastAIN, ainC);
154
+ }
155
+
156
+ oneBeforeFirstAIN = firstAIN - 1 ; // hack to discard noisy first readout
157
+ BufferSize = lastAIN - oneBeforeFirstAIN + 1 ;
158
+
159
+ }
160
+
161
+ void SAMDCurrentSenseADCDMA::initADC (){
162
+
163
+ analogRead (pinA); // do some pin init pinPeripheral()
164
+ analogRead (pinB); // do some pin init pinPeripheral()
165
+ analogRead (pinC); // do some pin init pinPeripheral()
166
+
167
+ ADC->CTRLA .bit .ENABLE = 0x00 ; // Disable ADC
168
+ ADCsync ();
169
+ // ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0_Val; // 2.2297 V Supply VDDANA
170
+ ADC->INPUTCTRL .bit .GAIN = ADC_INPUTCTRL_GAIN_1X_Val; // Gain select as 1X
171
+ // ADC->INPUTCTRL.bit.GAIN = ADC_INPUTCTRL_GAIN_DIV2_Val; // default
172
+ ADC->REFCTRL .bit .REFSEL = ADC_REFCTRL_REFSEL_AREFA;
173
+ // ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0;
174
+ ADCsync (); // ref 31.6.16
175
+
176
+ /*
177
+ Bits 19:16 – INPUTSCAN[3:0]: Number of Input Channels Included in Scan
178
+ This register gives the number of input sources included in the pin scan. The number of input sources included is
179
+ INPUTSCAN + 1. The input channels included are in the range from MUXPOS + INPUTOFFSET to MUXPOS +
180
+ INPUTOFFSET + INPUTSCAN.
181
+ The range of the scan mode must not exceed the number of input channels available on the device.
182
+ Bits 4:0 – MUXPOS[4:0]: Positive Mux Input Selection
183
+ These bits define the Mux selection for the positive ADC input. Table 32-14 shows the possible input selections. If
184
+ the internal bandgap voltage or temperature sensor input channel is selected, then the Sampling Time Length bit
185
+ group in the SamplingControl register must be written.
186
+ Table 32-14. Positive Mux Input Selection
187
+ MUXPOS[4:0] Group configuration Description
188
+ 0x00 PIN0 ADC AIN0 pin
189
+ 0x01 PIN1 ADC AIN1 pin
190
+ 0x02 PIN2 ADC AIN2 pin
191
+ 0x03 PIN3 ADC AIN3 pin
192
+ 0x04 PIN4 ADC AIN4 pin
193
+ 0x05 PIN5 ADC AIN5 pin
194
+ 0x06 PIN6 ADC AIN6 pin
195
+ 0x07 PIN7 ADC AIN7 pin
196
+ 0x08 PIN8 ADC AIN8 pin
197
+ 0x09 PIN9 ADC AIN9 pin
198
+ 0x0A PIN10 ADC AIN10 pin
199
+ 0x0B PIN11 ADC AIN11 pin
200
+ 0x0C PIN12 ADC AIN12 pin
201
+ 0x0D PIN13 ADC AIN13 pin
202
+ 0x0E PIN14 ADC AIN14 pin
203
+ 0x0F PIN15 ADC AIN15 pin
204
+ 0x10 PIN16 ADC AIN16 pin
205
+ 0x11 PIN17 ADC AIN17 pin
206
+ 0x12 PIN18 ADC AIN18 pin
207
+ 0x13 PIN19 ADC AIN19 pin
208
+ 0x14-0x17 Reserved
209
+ 0x18 TEMP Temperature reference
210
+ 0x19 BANDGAP Bandgap voltage
211
+ 0x1A SCALEDCOREVCC 1/4 scaled core supply
212
+ 0x1B SCALEDIOVCC 1/4 scaled I/O supply
213
+ 0x1C DAC DAC output
214
+ 0x1D-0x1F Reserved
215
+ */
216
+ ADC->INPUTCTRL .bit .MUXPOS = oneBeforeFirstAIN;
217
+ ADCsync ();
218
+ ADC->INPUTCTRL .bit .INPUTSCAN = lastAIN; // so the adc will scan from oneBeforeFirstAIN to lastAIN (inclusive)
219
+ ADCsync ();
220
+ ADC->INPUTCTRL .bit .INPUTOFFSET = 0 ; // input scan cursor
221
+ ADCsync ();
222
+ ADC->AVGCTRL .reg = 0x00 ; // no averaging
223
+ ADC->SAMPCTRL .reg = 0x05 ; ; // sample length in 1/2 CLK_ADC cycles, see GCLK_ADC and ADC_CTRLB_PRESCALER_DIV16
224
+ // according to the specsheet: f_GCLK_ADC ADC input clock frequency 48 MHz, so same as fCPU
225
+ ADCsync ();
226
+ ADC->CTRLB .reg = ADC_CTRLB_PRESCALER_DIV16 | ADC_CTRLB_FREERUN | ADC_CTRLB_RESSEL_12BIT;
227
+ ADCsync ();
228
+ }
229
+
230
+ volatile dmacdescriptor wrb[12 ] __attribute__ ((aligned (16 )));
231
+
232
+ void SAMDCurrentSenseADCDMA::initDMA () {
233
+ // probably on by default
234
+ PM->AHBMASK .reg |= PM_AHBMASK_DMAC ;
235
+ PM->APBBMASK .reg |= PM_APBBMASK_DMAC ;
236
+ NVIC_EnableIRQ ( DMAC_IRQn ) ;
237
+ DMAC->BASEADDR .reg = (uint32_t )descriptor_section;
238
+ DMAC->WRBADDR .reg = (uint32_t )wrb;
239
+ DMAC->CTRL .reg = DMAC_CTRL_DMAENABLE | DMAC_CTRL_LVLEN (0xf );
240
+ }
241
+
242
+
243
+ void SAMDCurrentSenseADCDMA::adcToDMATransfer (void *rxdata, uint32_t hwords) {
244
+
245
+ DMAC->CHID .reg = DMAC_CHID_ID (channelDMA);
246
+ DMAC->CHCTRLA .reg &= ~DMAC_CHCTRLA_ENABLE;
247
+ DMAC->CHCTRLA .reg = DMAC_CHCTRLA_SWRST;
248
+ DMAC->SWTRIGCTRL .reg &= (uint32_t )(~(1 << channelDMA));
249
+
250
+ DMAC->CHCTRLB .reg = DMAC_CHCTRLB_LVL (0 )
251
+ | DMAC_CHCTRLB_TRIGSRC (ADC_DMAC_ID_RESRDY)
252
+ | DMAC_CHCTRLB_TRIGACT_BEAT;
253
+ DMAC->CHINTENSET .reg = DMAC_CHINTENSET_MASK ; // enable all 3 interrupts
254
+ descriptor.descaddr = 0 ;
255
+ descriptor.srcaddr = (uint32_t ) &ADC->RESULT .reg ;
256
+ descriptor.btcnt = hwords;
257
+ descriptor.dstaddr = (uint32_t )rxdata + hwords*2 ; // end address
258
+ descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_HWORD | DMAC_BTCTRL_DSTINC | DMAC_BTCTRL_VALID;
259
+ memcpy (&descriptor_section[channelDMA],&descriptor, sizeof (dmacdescriptor));
260
+
261
+ // start channel
262
+ DMAC->CHID .reg = DMAC_CHID_ID (channelDMA);
263
+ DMAC->CHCTRLA .reg |= DMAC_CHCTRLA_ENABLE;
264
+ }
265
+
266
+
267
+ int iii = 0 ;
268
+
269
+ void adcStopWithDMA (void ){
270
+ ADCsync ();
271
+ ADC->CTRLA .bit .ENABLE = 0x00 ;
272
+ // ADCsync();
273
+ // if(iii++ % 1000 == 0)
274
+ // {
275
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(a);
276
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: ");
277
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(b);
278
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: ");
279
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(c);
280
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.println("yo!");
281
+ // }
282
+
283
+
284
+ }
285
+
286
+ void adcStartWithDMA (void ){
287
+ ADCsync ();
288
+ ADC->INPUTCTRL .bit .INPUTOFFSET = 0 ;
289
+ ADCsync ();
290
+ ADC->SWTRIG .bit .FLUSH = 1 ;
291
+ ADCsync ();
292
+ ADC->CTRLA .bit .ENABLE = 0x01 ;
293
+ ADCsync ();
294
+ }
295
+
296
+ void DMAC_Handler () {
297
+ uint8_t active_channel;
298
+ active_channel = DMAC->INTPEND .reg & DMAC_INTPEND_ID_Msk; // get channel number
299
+ DMAC->CHID .reg = DMAC_CHID_ID (active_channel);
300
+ adcStopWithDMA ();
301
+ DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_TCMPL; // clear
302
+ DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_TERR;
303
+ DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_SUSP;
304
+
305
+ }
306
+
307
+
308
+ #endif
0 commit comments