Skip to content

Commit cae3e84

Browse files
committed
Improved pure time series ADC read (moved to God.h)
1 parent fd1dbae commit cae3e84

File tree

4 files changed

+216
-86
lines changed

4 files changed

+216
-86
lines changed

m4/.vscode/settings.json

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,8 @@
55
"mstd_iterator": "cpp",
66
"array": "cpp",
77
"string": "cpp",
8-
"string_view": "cpp"
8+
"string_view": "cpp",
9+
"deque": "cpp",
10+
"vector": "cpp"
911
}
1012
}

m4/src/Peripherals/ADC/ADCController.h

Lines changed: 3 additions & 81 deletions
Original file line numberDiff line numberDiff line change
@@ -56,18 +56,14 @@ class ADCController {
5656
registerMemberFunction(setConversionTimeFW, "CONVERT_TIME_FW");
5757
registerMemberFunction(getConversionTime, "GET_CONVERT_TIME");
5858
registerMemberFunction(getRevisionRegister, "GET_REVISION_REG");
59-
registerMemberFunction(continuousConvertRead,
60-
"CONTINUOUS_CONVERT_READ");
59+
registerMemberFunction(continuousConvertRead, "CONTINUOUS_CONVERT_READ");
6160
registerMemberFunction(idleMode, "IDLE_MODE");
6261
registerMemberFunction(getChannelsActive, "GET_CHANNELS_ACTIVE");
6362
registerMemberFunction(resetAllADCBoards, "RESET");
6463
registerMemberFunction(talkADC, "TALK");
6564
registerMemberFunction(adcZeroScaleCal, "ADC_ZERO_SC_CAL");
66-
registerMemberFunction(adcChannelSystemZeroScaleCal,
67-
"ADC_CH_ZERO_SC_CAL");
68-
registerMemberFunction(adcChannelSystemFullScaleCal,
69-
"ADC_CH_FULL_SC_CAL");
70-
registerMemberFunctionVector(timeSeriesAdcRead, "TIME_SERIES_ADC_READ");
65+
registerMemberFunction(adcChannelSystemZeroScaleCal, "ADC_CH_ZERO_SC_CAL");
66+
registerMemberFunction(adcChannelSystemFullScaleCal, "ADC_CH_FULL_SC_CAL");
7167
registerMemberFunction(setRDYFN, "SET_RDYFN");
7268
registerMemberFunction(unsetRDYFN, "UNSET_RDYFN");
7369
registerMemberFunction(getChZeroScaleCalibration, "GET_ZERO_SCALE_CAL");
@@ -160,80 +156,6 @@ class ADCController {
160156
return adc_boards[board_index].getDataReadyPin();
161157
}
162158

163-
// args: num_channels, channel_indexes, total_duration_us
164-
// ex: TIME_SERIES_ADC_READ 2,0,1,1000000
165-
inline static OperationResult timeSeriesAdcRead(const std::vector<float>& args) {
166-
if (args.size() < 2) {
167-
return OperationResult::Failure("Not enough arguments provided");
168-
}
169-
170-
int numAdcChannels = static_cast<int>(args[0]);
171-
if (args.size() != static_cast<size_t>(numAdcChannels + 2)) {
172-
return OperationResult::Failure("Incorrect number of arguments");
173-
}
174-
std::vector<int> adcChannels;
175-
for (int i = 0; i < numAdcChannels; ++i) {
176-
adcChannels.push_back(static_cast<int>(args[i + 1]));
177-
}
178-
179-
uint32_t totalDuration = static_cast<uint32_t>(args[numAdcChannels + 1]);
180-
if (totalDuration < 82) {
181-
return OperationResult::Failure("Invalid total duration");
182-
}
183-
184-
int x = 0;
185-
186-
float adcConversionTime = numAdcChannels * getConversionTimeFloat(adcChannels[0]);
187-
188-
for (int i = 1; i < numAdcChannels; i++) {
189-
if (getConversionTimeFloat(adcChannels[i]) != adcConversionTime) {
190-
return OperationResult::Failure("All channels must have the same "
191-
"conversion time for time series read");
192-
}
193-
}
194-
195-
const int saved_data_size = totalDuration / adcConversionTime;
196-
197-
setStopFlag(false);
198-
PeripheralCommsController::dataLedOn();
199-
200-
for (int i = 0; i < numAdcChannels; i++) {
201-
ADCController::startContinuousConversion(adcChannels[i]);
202-
}
203-
TimingUtil::setupTimersTimeSeries(10000, adcConversionTime);
204-
205-
206-
while (x < saved_data_size && !getStopFlag()) {
207-
if (TimingUtil::adcFlag) {
208-
float packets[numAdcChannels];
209-
for (int i = 0; i < numAdcChannels; i++) {
210-
float v =
211-
getVoltageDataNoTransaction(adcChannels[i]);
212-
packets[i] = v;
213-
}
214-
m4SendFloat(packets, numAdcChannels);
215-
x++;
216-
// TimingUtil::adcFlag = false;
217-
}
218-
}
219-
220-
TimingUtil::disableDacInterrupt();
221-
TimingUtil::disableAdcInterrupt();
222-
223-
for (int i = 0; i < numAdcChannels; i++) {
224-
ADCController::idleMode(adcChannels[i]);
225-
}
226-
227-
PeripheralCommsController::dataLedOff();
228-
229-
if (getStopFlag()) {
230-
setStopFlag(false);
231-
return OperationResult::Failure("RAMPING_STOPPED");
232-
}
233-
234-
return OperationResult::Success();
235-
}
236-
237159
inline static uint32_t getConversionData(int adc_channel) {
238160
return adc_boards[getBoardIndexFromGlobalIndex(adc_channel)]
239161
.getConversionData(getChannelIndexFromGlobalIndex(adc_channel));

m4/src/Peripherals/God.h

Lines changed: 170 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,9 @@ class God {
2020
registerMemberFunction(initialize, "INITIALIZE");
2121
registerMemberFunction(initialize, "INIT");
2222
registerMemberFunction(initialize, "INNIT");
23-
registerMemberFunctionVector(timeSeriesBufferRampWrapper,
24-
"TIME_SERIES_BUFFER_RAMP");
25-
registerMemberFunctionVector(dacLedBufferRampWrapper,
26-
"DAC_LED_BUFFER_RAMP");
23+
registerMemberFunctionVector(timeSeriesBufferRampWrapper, "TIME_SERIES_BUFFER_RAMP");
24+
registerMemberFunctionVector(dacLedBufferRampWrapper, "DAC_LED_BUFFER_RAMP");
25+
registerMemberFunctionVector(timeSeriesAdcRead, "TIME_SERIES_ADC_READ");
2726
registerMemberFunction(dacChannelCalibration, "DAC_CH_CAL");
2827
registerMemberFunctionVector(boxcarAverageRamp, "BOXCAR_BUFFER_RAMP");
2928
}
@@ -56,6 +55,173 @@ class God {
5655
return BoardUsage{ static_cast<uint8_t>(boards.size()), boards };
5756
}
5857

58+
inline static OperationResult timeSeriesAdcRead(const std::vector<float>& args) {
59+
/**************************************************************************/
60+
// args: num_channels, channel_indexes, conversion_time, total_duration_us
61+
// ex: TIME_SERIES_ADC_READ 2,0,1,1000000
62+
//
63+
// Function takes a vector of floats as input, where:
64+
// args[0] = number of ADC channels = numAdcChannels
65+
// args[1] to args[numAdcChannels] = ADC channel indexes
66+
// args[numAdcChannels + 1] = conversion time in microseconds
67+
// args[numAdcChannels + 2] = total duration in microseconds
68+
/**************************************************************************/
69+
70+
// Check if we have enough arguments
71+
if (args.size() < 4) {
72+
return OperationResult::Failure("Not enough arguments provided");
73+
}
74+
75+
// Check if the first argument is a valid number of ADC channels
76+
int numAdcChannels = static_cast<int>(args[0]);
77+
if (args.size() != static_cast<size_t>(numAdcChannels + 3)) {
78+
return OperationResult::Failure("Incorrect number of arguments");
79+
}
80+
81+
// Setting up a vector of ADC channels from arguments directly after numAdcChannels
82+
std::vector<int> adcChannels_vec;
83+
for (int i = 0; i < numAdcChannels; ++i) {
84+
adcChannels_vec.push_back(static_cast<int>(args[i + 1]));
85+
}
86+
int* adcChannels = adcChannels_vec.data();
87+
88+
// Check to see if the total duration is valid (needs to be at least 82 microseconds)
89+
uint32_t conversion_time = static_cast<uint32_t>(args[numAdcChannels + 1]);
90+
uint32_t totalDuration = static_cast<uint32_t>(args[numAdcChannels + 2]);
91+
if (totalDuration < 82) {
92+
return OperationResult::Failure("Invalid total duration");
93+
}
94+
95+
//Set conversion time for each channel (same conversion time for all channels)
96+
float realConversionTime = 0;
97+
for (int i = 0; i < numAdcChannels; i++) {
98+
ADCController::setConversionTime(adcChannels[i], conversion_time);
99+
}
100+
realConversionTime = ADCController::getConversionTimeFloat(adcChannels[0]);
101+
102+
// Determine the maximum number of independent ADCs used
103+
int adc_usage[4] = {0, 0, 0, 0};
104+
for (int i = 0; i < numAdcChannels; ++i) {
105+
int ch = adcChannels[i];
106+
if (ch < 0) continue; // skip invalid values
107+
uint8_t board = ch / 4; // 0‑based board index
108+
adc_usage[board]++;
109+
}
110+
111+
int max_indep_ADCs = *std::max_element(adc_usage, adc_usage + 4);
112+
113+
//set sampling rate based on +5% conversion time and the number of ADC channels
114+
const double sample_rate_float = max_indep_ADCs * realConversionTime * 1.5f;
115+
const int sample_rate = static_cast<int>(sample_rate_float);
116+
117+
// Calculate the number of data points to save
118+
const int saved_data_size = totalDuration / sample_rate;
119+
120+
// Send the number of bytes to expect before starting the ADC read
121+
m4SendVoltage(&sample_rate_float, 1);
122+
123+
// Toggle stop flag and turn on data LED
124+
setStopFlag(false);
125+
PeripheralCommsController::dataLedOn();
126+
127+
#ifdef __NEW_DAC_ADC__
128+
digitalWrite(adc_sync, LOW); //Set the sync pin low to prevent ADCs from triggering
129+
static void (*isrFunctions[])() = { // Array of ISR functions for each ADC board
130+
TimingUtil::adcSyncISR<0>,
131+
TimingUtil::adcSyncISR<1>,
132+
TimingUtil::adcSyncISR<2>,
133+
TimingUtil::adcSyncISR<3>
134+
};
135+
136+
BoardUsage boardUsage = getUsedBoards(adcChannels, numAdcChannels);
137+
int numAdcBoards = boardUsage.numBoards;
138+
std::vector<uint8_t> adcBoards = boardUsage.idx;
139+
140+
// Attach interrupts for each ADC board's data ready pin
141+
for (int i = 0; i < numAdcBoards; i++) {
142+
uint8_t boardIndex = adcBoards[i];
143+
attachInterrupt(digitalPinToInterrupt(ADCController::getDataReadyPin(boardIndex)), isrFunctions[boardIndex], FALLING);
144+
}
145+
#endif
146+
147+
// reset all ADCs before ramp
148+
ADCController::resetToPreviousConversionTimes();
149+
150+
// Start continous conversion for each ADC channel
151+
for (int i = 0; i < numAdcChannels; i++) {
152+
ADCController::startContinuousConversion(adcChannels[i]);
153+
#ifdef __NEW_DAC_ADC__
154+
ADCController::setRDYFN(adcChannels[i]);
155+
#endif
156+
}
157+
158+
// initialize ADC mask
159+
uint8_t adcMask = 0u;
160+
#ifdef __NEW_DAC_ADC__
161+
for (int i = 0; i < numAdcBoards; i++) {
162+
adcMask |= 1 << i;
163+
}
164+
#else
165+
adcMask = 1;
166+
#endif
167+
168+
// Set up timers for ADC sampling
169+
TimingUtil::setupTimersOnlyADC(sample_rate);
170+
171+
// initialize loop counter
172+
int x = 0;
173+
174+
//Begin main loop
175+
while (x < saved_data_size && !getStopFlag()) {
176+
__WFE(); // Wait for event (WFE) to reduce CPU usage
177+
if (TimingUtil::adcFlag == adcMask) {
178+
double packets[numAdcChannels];
179+
for (int i = 0; i < numAdcChannels; i++) {
180+
double v = ADCController::getVoltageDataNoTransaction(adcChannels[i]);
181+
packets[i] = v;
182+
}
183+
m4SendVoltage(packets, numAdcChannels);
184+
x++;
185+
TimingUtil::adcFlag = 0;
186+
187+
#ifdef __NEW_DAC_ADC__
188+
digitalWrite(adc_sync, LOW);
189+
#endif
190+
}
191+
}
192+
193+
// Clean up after the loop
194+
//Disable ADC timer interrupt
195+
TimingUtil::disableAdcInterrupt();
196+
197+
// Set the ADCs into idle mode and unset the readyfnc bit (this allows single channel ADC conversions -- ready flag goes high after any ADC has unread data)
198+
for (int i = 0; i < numAdcChannels; i++) {
199+
ADCController::idleMode(adcChannels[i]);
200+
#ifdef __NEW_DAC_ADC__
201+
ADCController::unsetRDYFN(adcChannels[i]);
202+
#endif
203+
}
204+
205+
// reset all ADCs after ramp
206+
ADCController::resetToPreviousConversionTimes();
207+
208+
//Detach hardware interrupt for ready pin on ADCs
209+
#ifdef __NEW_DAC_ADC__
210+
for (int i = 0; i < numAdcBoards; i++) {
211+
detachInterrupt(digitalPinToInterrupt(ADCController::getDataReadyPin(adcBoards[i])));
212+
}
213+
#endif
214+
215+
PeripheralCommsController::dataLedOff();
216+
217+
if (getStopFlag()) {
218+
setStopFlag(false);
219+
return OperationResult::Failure("RAMPING_STOPPED");
220+
}
221+
222+
return OperationResult::Success();
223+
}
224+
59225
// args:
60226
// numDacChannels, numAdcChannels, numSteps, dacInterval_us, adcInterval_us,
61227
// dacchannel0, dacv00, dacvf0, dacchannel1, dacv01, dacvf1, ..., adc0, adc1,

m4/src/Utils/TimingUtil.h

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,46 @@ struct TimingUtil {
7575
TIM1->CR1 |= TIM_CR1_CEN;
7676
}
7777

78+
inline static void setupTimersOnlyADC(uint32_t adc_period_us) {
79+
resetTimers();
80+
81+
// Enable TIM8 clock
82+
__HAL_RCC_TIM8_CLK_ENABLE();
83+
84+
uint64_t timerClock = 2 * HAL_RCC_GetPCLK2Freq();
85+
86+
uint64_t total_ticks_adc = (adc_period_us * timerClock) / 1000000;
87+
88+
uint16_t psc_adc;
89+
uint16_t arr_adc;
90+
91+
if (total_ticks_adc <= 65536) {
92+
psc_adc = 0; // No prescaling
93+
arr_adc = total_ticks_adc - 1; // Full resolution within 16 bits
94+
} else {
95+
// Compute the minimal prescaler (PSC+1) needed so that ARR <= 65535
96+
uint32_t prescaler_adc = (total_ticks_adc + 65536 - 1) / 65536; // Rounds up division
97+
psc_adc = prescaler_adc - 1; // Because PSC register = (PSC+1) - 1
98+
arr_adc = (total_ticks_adc / prescaler_adc) - 1; // ARR counts from 0 to ARR, hence subtract 1
99+
}
100+
101+
// Configure TIM8
102+
TIM8->PSC = psc_adc;
103+
TIM8->ARR = arr_adc;
104+
TIM8->CR1 = TIM_CR1_ARPE;
105+
TIM8->DIER |= TIM_DIER_UIE;
106+
107+
TIM8->EGR |= 0x01;
108+
TIM8->SR &= ~TIM_SR_UIF;
109+
110+
// Enable interrupts
111+
NVIC_SetPriority(TIM8_UP_TIM13_IRQn, 3);
112+
NVIC_EnableIRQ(TIM8_UP_TIM13_IRQn);
113+
114+
// Start timer
115+
TIM8->CR1 |= TIM_CR1_CEN;
116+
}
117+
78118
inline static void setupTimersTimeSeries(uint32_t dac_period_us,
79119
uint32_t adc_period_us) {
80120
resetTimers();

0 commit comments

Comments
 (0)