1
1
2
2
#include " samd21_mcu.h"
3
3
4
+ // Credit: significant portions of this code were pulled from Paul Gould's git https://github.com/gouldpa/FOC-Arduino-Brushless
4
5
5
- void adc_stop_with_DMA (void );
6
- void adc_start_with_DMA (void );
6
+ static void adcStopWithDMA (void );
7
+ static void adcStartWithDMA (void );
7
8
8
9
/* *
9
10
* @brief ADC sync wait
@@ -16,91 +17,66 @@ static void ADCsync() {
16
17
17
18
// ADC DMA sequential free running (6) with Interrupts /////////////////
18
19
19
- typedef struct {
20
- uint16_t btctrl;
21
- uint16_t btcnt;
22
- uint32_t srcaddr;
23
- uint32_t dstaddr;
24
- uint32_t descaddr;
25
- } dmacdescriptor ;
26
- volatile dmacdescriptor wrb[12 ] __attribute__ ((aligned (16 )));
27
- dmacdescriptor descriptor_section[12 ] __attribute__ ((aligned (16 )));
28
- dmacdescriptor descriptor __attribute__ ((aligned (16 )));
29
- DmacDescriptor *desc; // DMA descriptor address (so we can change contents)
30
20
31
21
32
22
33
- SAMDCurrentSensceADC::SAMDCurrentSensceADC (int pinA, int pinB, int pinC, float arefaVoltage, uint32_t adcBits)
34
- : _ADC_VOLTAGE(arefaVoltage), _ADC_RESOLUTION(1 << adcBits)
23
+
24
+ SAMDCurrentSenseADCDMA::SAMDCurrentSenseADCDMA (int pinA, int pinB, int pinC, int pinAREF, float voltageAREF, uint32_t adcBits, uint32_t channelDMA)
25
+ : pinA(pinA), pinB(pinB), pinC(pinC), pinAREF(pinAREF), channelDMA(channelDMA), voltageAREF(voltageAREF), maxCountsADC(1 << adcBits)
35
26
{
36
- ADC_CONV_ = ( _ADC_VOLTAGE / _ADC_RESOLUTION );
37
- this ->pinA = pinA;
38
- this ->pinB = pinB;
39
- this ->pinC = pinC;
27
+ countsToVolts = ( voltageAREF / maxCountsADC );
40
28
}
41
29
42
- void SAMDCurrentSensceADC::init ()
43
- {
44
- _configure3PinsDMA ();
45
- _start3PinsDMA (); // s
30
+ void SAMDCurrentSenseADCDMA::init (){
31
+ initPins ();
32
+ initADC ();
33
+ initDMA ();
34
+ startADCScan (); // so we have something to read next time we call readResults()
46
35
}
47
36
48
37
49
- void SAMDCurrentSensceADC::_start3PinsDMA ()
50
- {
51
- adc_dma (adcBuffer + ADC_OneBeforeFirstPin, BufferSize);
52
- adc_start_with_DMA ();
38
+ void SAMDCurrentSenseADCDMA::startADCScan (){
39
+ adcToDMATransfer (adcBuffer + oneBeforeFirstAIN, BufferSize);
40
+ adcStartWithDMA ();
53
41
}
54
- void SAMDCurrentSensceADC::_read3PinsDMA ( const int pinA, const int pinB, const int pinC, float & a, float & b, float & c)
55
- {
42
+
43
+ void SAMDCurrentSenseADCDMA::readResults ( float & a, float & b, float & c) {
56
44
while (ADC->CTRLA .bit .ENABLE ) ;
57
- uint32_t adcA = g_APinDescription[pinA].ulADCChannelNumber ;
58
- uint32_t adcB = g_APinDescription[pinB].ulADCChannelNumber ;
59
- a = adcBuffer[adcA] * ADC_CONV_;
60
- b = adcBuffer[adcB] * ADC_CONV_;
45
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber ;
46
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber ;
47
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber ;
48
+ a = adcBuffer[ainA] * countsToVolts;
49
+ b = adcBuffer[ainB] * countsToVolts;
61
50
if (_isset (pinC))
62
51
{
63
- uint32_t adcC = g_APinDescription[pinC].ulADCChannelNumber ;
64
- c = adcBuffer[adcC] * ADC_CONV_;
52
+ c = adcBuffer[ainC] * countsToVolts;
65
53
}
66
54
}
67
55
68
- // function reading an ADC value and returning the read voltage
69
- void SAMDCurrentSensceADC::_configure3PinsDMA (){
56
+ void SAMDCurrentSenseADCDMA::initPins (){
70
57
71
- uint32_t adcA = g_APinDescription[pinA].ulADCChannelNumber ;
72
- uint32_t adcB = g_APinDescription[pinB].ulADCChannelNumber ;
73
- uint32_t adcC = g_APinDescription[pinC].ulADCChannelNumber ;
74
-
75
- pinMode (42 , INPUT);
76
- ADC_FirstPin = min (adcA, adcB);
77
- ADC_LastPin = max (adcA, adcB);
58
+ pinMode (pinAREF, INPUT);
78
59
pinMode (pinA, INPUT);
79
60
pinMode (pinB, INPUT);
61
+
62
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber ;
63
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber ;
64
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber ;
65
+ firstAIN = min (ainA, ainB);
66
+ lastAIN = max (ainA, ainB);
80
67
if ( _isset (pinC) )
81
68
{
82
69
pinMode (pinC, INPUT);
83
- ADC_FirstPin = min (ADC_FirstPin, adcC );
84
- ADC_LastPin = max (ADC_LastPin, adcC );
70
+ firstAIN = min (firstAIN, ainC );
71
+ lastAIN = max (lastAIN, ainC );
85
72
}
86
73
87
- ADC_OneBeforeFirstPin = ADC_FirstPin - 1 ; // hack to discard noisy first readout
88
- BufferSize = ADC_LastPin - ADC_OneBeforeFirstPin + 1 ;
74
+ oneBeforeFirstAIN = firstAIN - 1 ; // hack to discard noisy first readout
75
+ BufferSize = lastAIN - oneBeforeFirstAIN + 1 ;
89
76
90
- // ADC and DMA
91
- adc_init ();
92
- dma_init ();
93
77
}
94
78
95
-
96
-
97
-
98
-
99
- /* *
100
- * @brief Initialize ADC
101
- * @retval void
102
- */
103
- void SAMDCurrentSensceADC::adc_init (){
79
+ void SAMDCurrentSenseADCDMA::initADC (){
104
80
105
81
analogRead (pinA); // do some pin init pinPeripheral()
106
82
analogRead (pinB); // do some pin init pinPeripheral()
@@ -155,9 +131,9 @@ void SAMDCurrentSensceADC::adc_init(){
155
131
0x1C DAC DAC output
156
132
0x1D-0x1F Reserved
157
133
*/
158
- ADC->INPUTCTRL .bit .MUXPOS = ADC_OneBeforeFirstPin ;
134
+ ADC->INPUTCTRL .bit .MUXPOS = oneBeforeFirstAIN ;
159
135
ADCsync ();
160
- ADC->INPUTCTRL .bit .INPUTSCAN = ADC_LastPin ; // so the adc will scan from AIN[1] to AIN[ADC_Number+1]
136
+ ADC->INPUTCTRL .bit .INPUTSCAN = lastAIN ; // so the adc will scan from oneBeforeFirstAIN to lastAIN (inclusive)
161
137
ADCsync ();
162
138
ADC->INPUTCTRL .bit .INPUTOFFSET = 0 ; // input scan cursor
163
139
ADCsync ();
@@ -169,12 +145,9 @@ void SAMDCurrentSensceADC::adc_init(){
169
145
ADCsync ();
170
146
}
171
147
148
+ volatile dmacdescriptor wrb[12 ] __attribute__ ((aligned (16 )));
172
149
173
- /* *
174
- * @brief dma_init
175
- * @retval void
176
- */
177
- void SAMDCurrentSensceADC::dma_init () {
150
+ void SAMDCurrentSenseADCDMA::initDMA () {
178
151
// probably on by default
179
152
PM->AHBMASK .reg |= PM_AHBMASK_DMAC ;
180
153
PM->APBBMASK .reg |= PM_APBBMASK_DMAC ;
@@ -184,68 +157,46 @@ void SAMDCurrentSensceADC::dma_init() {
184
157
DMAC->CTRL .reg = DMAC_CTRL_DMAENABLE | DMAC_CTRL_LVLEN (0xf );
185
158
}
186
159
187
- /* *
188
- * @brief adc_dma
189
- * @retval void
190
- */
191
- void SAMDCurrentSensceADC::adc_dma (void *rxdata, size_t hwords) {
192
- uint32_t temp_CHCTRLB_reg;
193
160
194
- DMAC->CHID .reg = DMAC_CHID_ID (ADC_DMA_chnl);
161
+ void SAMDCurrentSenseADCDMA::adcToDMATransfer (void *rxdata, size_t hwords) {
162
+
163
+ DMAC->CHID .reg = DMAC_CHID_ID (channelDMA);
195
164
DMAC->CHCTRLA .reg &= ~DMAC_CHCTRLA_ENABLE;
196
165
DMAC->CHCTRLA .reg = DMAC_CHCTRLA_SWRST;
197
- DMAC->SWTRIGCTRL .reg &= (uint32_t )(~(1 << ADC_DMA_chnl));
198
- temp_CHCTRLB_reg = DMAC_CHCTRLB_LVL (0 ) |
199
- DMAC_CHCTRLB_TRIGSRC (ADC_DMAC_ID_RESRDY) | DMAC_CHCTRLB_TRIGACT_BEAT;
200
- DMAC->CHCTRLB .reg = temp_CHCTRLB_reg;
166
+ DMAC->SWTRIGCTRL .reg &= (uint32_t )(~(1 << channelDMA));
167
+
168
+ DMAC->CHCTRLB .reg = DMAC_CHCTRLB_LVL (0 )
169
+ | DMAC_CHCTRLB_TRIGSRC (ADC_DMAC_ID_RESRDY)
170
+ | DMAC_CHCTRLB_TRIGACT_BEAT;
201
171
DMAC->CHINTENSET .reg = DMAC_CHINTENSET_MASK ; // enable all 3 interrupts
202
172
descriptor.descaddr = 0 ;
203
173
descriptor.srcaddr = (uint32_t ) &ADC->RESULT .reg ;
204
174
descriptor.btcnt = hwords;
205
175
descriptor.dstaddr = (uint32_t )rxdata + hwords*2 ; // end address
206
176
descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_HWORD | DMAC_BTCTRL_DSTINC | DMAC_BTCTRL_VALID;
207
- memcpy (&descriptor_section[ADC_DMA_chnl ],&descriptor, sizeof (dmacdescriptor));
177
+ memcpy (&descriptor_section[channelDMA ],&descriptor, sizeof (dmacdescriptor));
208
178
209
179
// start channel
210
- DMAC->CHID .reg = DMAC_CHID_ID (ADC_DMA_chnl );
180
+ DMAC->CHID .reg = DMAC_CHID_ID (channelDMA );
211
181
DMAC->CHCTRLA .reg |= DMAC_CHCTRLA_ENABLE;
212
182
}
213
183
214
184
215
-
216
-
217
- /* *
218
- * @brief adc_stop_with_DMA
219
- * @retval void
220
- */
221
- void adc_stop_with_DMA (void )
222
- {
185
+ void adcStopWithDMA (void ){
223
186
ADC->CTRLA .bit .ENABLE = 0x00 ;
224
- // SerialUSB.println("DMA stopped!");
225
187
}
226
188
227
- /* *
228
- * @brief adc_start_with_DMA
229
- * @retval void
230
- */
231
- void adc_start_with_DMA (void )
232
- {
233
- // SerialUSB.println("strating DMA...");
234
- // ADC->INPUTCTRL.bit.MUXPOS = ADC_OneBeforeFirstPin;
235
- // ADC->INPUTCTRL.bit.INPUTSCAN = ADC_LastPin;
189
+ void adcStartWithDMA (void ){
236
190
ADC->INPUTCTRL .bit .INPUTOFFSET = 0 ;
237
191
ADC->SWTRIG .bit .FLUSH = 1 ;
238
192
ADC->CTRLA .bit .ENABLE = 0x01 ;
239
193
}
240
- /* *
241
- * @brief DMAC_Handler
242
- * @retval void
243
- */
194
+
244
195
void DMAC_Handler () {
245
196
uint8_t active_channel;
246
197
active_channel = DMAC->INTPEND .reg & DMAC_INTPEND_ID_Msk; // get channel number
247
198
DMAC->CHID .reg = DMAC_CHID_ID (active_channel);
248
- adc_stop_with_DMA ();
199
+ adcStopWithDMA ();
249
200
DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_TCMPL; // clear
250
201
DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_TERR;
251
202
DMAC->CHINTFLAG .reg = DMAC_CHINTENCLR_SUSP;
0 commit comments