aboutsummaryrefslogtreecommitdiffstats
path: root/source
diff options
context:
space:
mode:
authorClyne Sullivan <clyne@bitgloo.com>2021-01-22 21:43:36 -0500
committerClyne Sullivan <clyne@bitgloo.com>2021-01-22 21:43:36 -0500
commit48026bb824fd2d9cfb00ecd040db6ef3a416bae9 (patch)
treec14713aedfe78ee8b34f2e1252408782e2e2ff5d /source
parente080a26651f90c88176140d63a74c93c2f4041a2 (diff)
upload initial port
Diffstat (limited to 'source')
-rw-r--r--source/adc.cpp61
-rw-r--r--source/common.hpp34
-rw-r--r--source/dac.cpp26
-rw-r--r--source/main.cpp724
-rw-r--r--source/usbcfg.c2
5 files changed, 450 insertions, 397 deletions
diff --git a/source/adc.cpp b/source/adc.cpp
index bdfeea8..a830017 100644
--- a/source/adc.cpp
+++ b/source/adc.cpp
@@ -11,11 +11,12 @@
#include "adc.hpp"
-ADCDriver *ADC::m_driver = &ADCD1;
+ADCDriver *ADC::m_driver = &ADCD3;
GPTDriver *ADC::m_timer = &GPTD6;
const ADCConfig ADC::m_config = {
- .difsel = 0
+ .difsel = 0,
+ .calibration = 0,
};
ADCConversionGroup ADC::m_group_config = {
@@ -24,19 +25,23 @@ ADCConversionGroup ADC::m_group_config = {
.end_cb = ADC::conversionCallback,
.error_cb = nullptr,
.cfgr = ADC_CFGR_EXTEN_RISING | ADC_CFGR_EXTSEL_SRC(13), /* TIM6_TRGO */
- .cfgr2 = ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR_0 | ADC_CFGR2_OVSS_1, // Oversampling 2x
- .tr1 = ADC_TR(0, 4095),
+ .cfgr2 = 0,//ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR_0 | ADC_CFGR2_OVSS_1, // Oversampling 2x
+ .ccr = 0,
+ .pcsel = 0,
+ .ltr1 = 0, .htr1 = 0x0FFF,
+ .ltr2 = 0, .htr2 = 0x0FFF,
+ .ltr3 = 0, .htr3 = 0x0FFF,
.smpr = {
ADC_SMPR1_SMP_AN5(ADC_SMPR_SMP_12P5), 0
},
.sqr = {
ADC_SQR1_SQ1_N(ADC_CHANNEL_IN5),
0, 0, 0
- }
+ },
};
const GPTConfig ADC::m_timer_config = {
- .frequency = 36000000,
+ .frequency = 4800000,
.callback = nullptr,
.cr2 = TIM_CR2_MMS_1, /* TRGO */
.dier = 0
@@ -56,17 +61,17 @@ adcsample_t *ADC::m_current_buffer = nullptr;
size_t ADC::m_current_buffer_size = 0;
ADC::Operation ADC::m_operation = nullptr;
-unsigned int ADC::m_timer_divisor = 2;
+unsigned int ADC::m_timer_divisor = 50;
void ADC::begin()
{
- palSetPadMode(GPIOA, 0, PAL_MODE_INPUT_ANALOG);
+ palSetPadMode(GPIOF, 3, PAL_MODE_INPUT_ANALOG);
adcStart(m_driver, &m_config);
adcSTM32EnableVREF(m_driver);
gptStart(m_timer, &m_timer_config);
- setRate(Rate::R32K);
+ //setRate(Rate::R32K);
}
void ADC::start(adcsample_t *buffer, size_t count, Operation operation)
@@ -91,25 +96,25 @@ void ADC::stop()
void ADC::setRate(ADC::Rate rate)
{
- auto& preset = m_rate_presets[static_cast<int>(rate)];
- auto pllnr = (preset[0] << RCC_PLLSAI2CFGR_PLLSAI2N_Pos) |
- (preset[1] << RCC_PLLSAI2CFGR_PLLSAI2R_Pos);
- bool oversample = preset[2] != 0;
- m_timer_divisor = preset[3];
-
- adcStop(m_driver);
-
- // Adjust PLLSAI2
- RCC->CR &= ~(RCC_CR_PLLSAI2ON);
- while ((RCC->CR & RCC_CR_PLLSAI2RDY) == RCC_CR_PLLSAI2RDY);
- RCC->PLLSAI2CFGR = (RCC->PLLSAI2CFGR & ~(RCC_PLLSAI2CFGR_PLLSAI2N_Msk | RCC_PLLSAI2CFGR_PLLSAI2R_Msk)) | pllnr;
- RCC->CR |= RCC_CR_PLLSAI2ON;
- while ((RCC->CR & RCC_CR_PLLSAI2RDY) != RCC_CR_PLLSAI2RDY);
-
- // Set 2x oversampling
- m_group_config.cfgr2 = oversample ? ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR_0 | ADC_CFGR2_OVSS_1 : 0;
-
- adcStart(m_driver, &m_config);
+// auto& preset = m_rate_presets[static_cast<int>(rate)];
+// auto pllnr = (preset[0] << RCC_PLLSAI2CFGR_PLLSAI2N_Pos) |
+// (preset[1] << RCC_PLLSAI2CFGR_PLLSAI2R_Pos);
+// bool oversample = preset[2] != 0;
+// m_timer_divisor = preset[3];
+
+// adcStop(m_driver);
+//
+// // Adjust PLLSAI2
+// RCC->CR &= ~(RCC_CR_PLLSAI2ON);
+// while ((RCC->CR & RCC_CR_PLLSAI2RDY) == RCC_CR_PLLSAI2RDY);
+// RCC->PLLSAI2CFGR = (RCC->PLLSAI2CFGR & ~(RCC_PLLSAI2CFGR_PLLSAI2N_Msk | RCC_PLLSAI2CFGR_PLLSAI2R_Msk)) | pllnr;
+// RCC->CR |= RCC_CR_PLLSAI2ON;
+// while ((RCC->CR & RCC_CR_PLLSAI2RDY) != RCC_CR_PLLSAI2RDY);
+//
+// // Set 2x oversampling
+// m_group_config.cfgr2 = oversample ? ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR_0 | ADC_CFGR2_OVSS_1 : 0;
+//
+// adcStart(m_driver, &m_config);
}
void ADC::setOperation(ADC::Operation operation)
diff --git a/source/common.hpp b/source/common.hpp
index 1045b32..f6a8cd0 100644
--- a/source/common.hpp
+++ b/source/common.hpp
@@ -1,20 +1,31 @@
#include <array>
#include <cstdint>
-constexpr unsigned int MAX_SAMPLE_BUFFER_SIZE = 6000;
+//#define ENABLE_SIGGEN
+
+constexpr unsigned int MAX_SAMPLE_BUFFER_SIZE = 4000;
using Sample = uint16_t;
class SampleBuffer
{
public:
+ SampleBuffer(Sample *buffer) :
+ m_buffer(buffer) {}
+
void clear() {
- m_buffer.fill(0);
+ /*static const Sample ref[21] = {
+ 100, 200, 400, 600, 800, 1000, 1200, 1400, 1600, 1800,
+ 2000, 2200, 2400, 2600, 2800, 3000, 3200, 3400, 3600, 3800, 4095
+ };
+ for (unsigned int i = 0; i < m_size; i++)
+ m_buffer[i] = ref[i % 21];*/
+ std::fill(m_buffer, m_buffer + m_size, 2048);
}
void modify(Sample *data, unsigned int srcsize) {
auto size = srcsize < m_size ? srcsize : m_size;
- std::copy(data, data + size, m_buffer.data());
- m_modified = m_buffer.data();
+ std::copy(data, data + size, m_buffer);
+ m_modified = m_buffer;
}
void midmodify(Sample *data, unsigned int srcsize) {
auto size = srcsize < m_size / 2 ? srcsize : m_size / 2;
@@ -26,14 +37,14 @@ public:
m_size = size < MAX_SAMPLE_BUFFER_SIZE ? size : MAX_SAMPLE_BUFFER_SIZE;
}
- Sample *data() /*const*/ {
- return m_buffer.data();
+ Sample *data() {
+ return m_buffer;
}
- Sample *middata() /*const*/ {
- return m_buffer.data() + m_size / 2;
+ Sample *middata() {
+ return m_buffer + m_size / 2;
}
- uint8_t *bytedata() /*const*/ {
- return reinterpret_cast<uint8_t *>(m_buffer.data());
+ uint8_t *bytedata() {
+ return reinterpret_cast<uint8_t *>(m_buffer);
}
Sample *modified() {
@@ -49,7 +60,8 @@ public:
}
private:
- std::array<Sample, MAX_SAMPLE_BUFFER_SIZE> m_buffer;
+ //std::array<Sample, MAX_SAMPLE_BUFFER_SIZE> m_buffer;
+ Sample *m_buffer = nullptr;
unsigned int m_size = MAX_SAMPLE_BUFFER_SIZE;
Sample *m_modified = nullptr;
};
diff --git a/source/dac.cpp b/source/dac.cpp
index ed08461..283d8a9 100644
--- a/source/dac.cpp
+++ b/source/dac.cpp
@@ -13,9 +13,9 @@
#include "dac.hpp"
DACDriver *DAC::m_driver[2] = {
- &DACD1, &DACD2
+ &DACD1, nullptr/*&DACD2*/
};
-GPTDriver *DAC::m_timer = &GPTD7;
+GPTDriver *DAC::m_timer = nullptr;//&GPTD7;
int DAC::m_timer_user_count = 0;
const DACConfig DAC::m_config = {
@@ -28,11 +28,11 @@ const DACConversionGroup DAC::m_group_config = {
.num_channels = 1,
.end_cb = nullptr,
.error_cb = nullptr,
- .trigger = DAC_TRG(2)
+ .trigger = 5
};
const GPTConfig DAC::m_timer_config = {
- .frequency = 36000000,
+ .frequency = 4800000,
.callback = nullptr,
.cr2 = TIM_CR2_MMS_1, /* TRGO */
.dier = 0
@@ -44,28 +44,28 @@ void DAC::begin()
palSetPadMode(GPIOA, 5, PAL_MODE_INPUT_ANALOG);
dacStart(m_driver[0], &m_config);
- dacStart(m_driver[1], &m_config);
- gptStart(m_timer, &m_timer_config);
+ //dacStart(m_driver[1], &m_config);
+ //gptStart(m_timer, &m_timer_config);
}
void DAC::start(int channel, dacsample_t *buffer, size_t count)
{
- if (channel >= 0 && channel < 2) {
+ if (channel >= 0 && channel < 1) {
dacStartConversion(m_driver[channel], &m_group_config, buffer, count);
- if (m_timer_user_count == 0)
- gptStartContinuous(m_timer, ADC::getTimerDivisor());
- m_timer_user_count++;
+ //if (m_timer_user_count == 0)
+ // gptStartContinuous(m_timer, ADC::getTimerDivisor());
+ //m_timer_user_count++;
}
}
void DAC::stop(int channel)
{
- if (channel >= 0 && channel < 2) {
+ if (channel >= 0 && channel < 1) {
dacStopConversion(m_driver[channel]);
- if (--m_timer_user_count == 0)
- gptStopTimer(m_timer);
+ //if (--m_timer_user_count == 0)
+ // gptStopTimer(m_timer);
}
}
diff --git a/source/main.cpp b/source/main.cpp
index b77bd2f..639f455 100644
--- a/source/main.cpp
+++ b/source/main.cpp
@@ -1,344 +1,380 @@
-/**
- * @file main.cpp
- * @brief Program entry point.
- *
- * Copyright (C) 2020 Clyne Sullivan
- *
- * Distributed under the GNU GPL v3 or later. You should have received a copy of
- * the GNU General Public License along with this program.
- * If not, see <https://www.gnu.org/licenses/>.
- */
-
-#include "ch.h"
-#include "hal.h"
-
-static_assert(sizeof(adcsample_t) == sizeof(uint16_t));
-static_assert(sizeof(dacsample_t) == sizeof(uint16_t));
-
-#include "common.hpp"
-#include "error.hpp"
-
-#include "adc.hpp"
-#include "dac.hpp"
-#include "elf_load.hpp"
-#include "usbserial.hpp"
-
-#include <array>
-
-constexpr unsigned int MAX_ELF_FILE_SIZE = 8 * 1024;
-
-enum class RunStatus : char
-{
- Idle = '1',
- Running
-};
-static RunStatus run_status = RunStatus::Idle;
-
-#define MSG_CONVFIRST (1)
-#define MSG_CONVSECOND (2)
-#define MSG_CONVFIRST_MEASURE (3)
-#define MSG_CONVSECOND_MEASURE (4)
-
-#define MSG_FOR_FIRST(m) (m & 1)
-#define MSG_FOR_MEASURE(m) (m > 2)
-
-static msg_t conversionMBBuffer[4];
-static MAILBOX_DECL(conversionMB, conversionMBBuffer, 4);
-
-static THD_WORKING_AREA(conversionThreadWA, 2048);
-static THD_FUNCTION(conversionThread, arg);
-
-static time_measurement_t conversion_time_measurement;
-
-static ErrorManager EM;
-
-static SampleBuffer samplesIn;
-static SampleBuffer samplesOut;
-static SampleBuffer samplesSigGen;
-
-static unsigned char elf_file_store[MAX_ELF_FILE_SIZE];
-static ELF::Entry elf_entry = nullptr;
-
-static void signal_operate(adcsample_t *buffer, size_t count);
-static void signal_operate_measure(adcsample_t *buffer, size_t count);
-static void main_loop();
-
-int main()
-{
- // Initialize the RTOS
- halInit();
- chSysInit();
-
- // Enable FPU
- SCB->CPACR |= 0xF << 20;
-
- // Prepare LED
- palSetPadMode(GPIOA, 5, PAL_MODE_OUTPUT_PUSHPULL);
- palClearPad(GPIOA, 5);
-
- ADC::begin();
- DAC::begin();
- USBSerial::begin();
-
- // Start the conversion manager thread
- chTMObjectInit(&conversion_time_measurement);
- chThdCreateStatic(conversionThreadWA, sizeof(conversionThreadWA),
- NORMALPRIO,
- conversionThread, nullptr);
-
- main_loop();
-}
-
-void main_loop()
-{
-
- while (1) {
- if (USBSerial::isActive()) {
- // Attempt to receive a command packet
- if (unsigned char cmd[3]; USBSerial::read(&cmd[0], 1) > 0) {
- // Packet received, first byte represents the desired command/action
- switch (cmd[0]) {
-
- case 'a':
- USBSerial::write(samplesIn.bytedata(), samplesIn.bytesize());
- break;
- case 'A':
- USBSerial::read(samplesIn.bytedata(), samplesIn.bytesize());
- break;
-
- case 'B':
- if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle) &&
- EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize))
- {
- unsigned int count = (cmd[1] | (cmd[2] << 8)) * 2;
- if (EM.assert(count <= MAX_SAMPLE_BUFFER_SIZE, Error::BadParam)) {
- samplesIn.setSize(count);
- samplesOut.setSize(count);
- }
- }
- break;
-
- case 'd':
- USBSerial::write(samplesOut.bytedata(), samplesOut.bytesize());
- break;
- case 'D':
- if (EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize)) {
- unsigned int count = cmd[1] | (cmd[2] << 8);
- if (EM.assert(count <= MAX_SAMPLE_BUFFER_SIZE, Error::BadParam)) {
- samplesSigGen.setSize(count);
- USBSerial::read(samplesSigGen.bytedata(), samplesSigGen.bytesize());
- }
- }
- break;
-
- // 'E' - Reads in and loads the compiled conversion code binary from USB.
- case 'E':
- if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle) &&
- EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize))
- {
- // Only load the binary if it can fit in the memory reserved for it.
- unsigned int size = cmd[1] | (cmd[2] << 8);
- if (EM.assert(size < sizeof(elf_file_store), Error::BadUserCodeSize)) {
- USBSerial::read(elf_file_store, size);
- elf_entry = ELF::load(elf_file_store);
-
- EM.assert(elf_entry != nullptr, Error::BadUserCodeLoad);
- }
- }
- break;
-
- // 'e' - Unloads the currently loaded conversion code
- case 'e':
- elf_entry = nullptr;
- break;
-
- // 'i' - Sends an identifying string to confirm that this is the stmdsp device.
- case 'i':
- USBSerial::write(reinterpret_cast<const uint8_t *>("stmdsp"), 6);
- break;
-
- // 'I' - Sends the current run status.
- case 'I':
- {
- unsigned char buf[2] = {
- static_cast<unsigned char>(run_status),
- static_cast<unsigned char>(EM.pop())
- };
- USBSerial::write(buf, sizeof(buf));
- }
- break;
-
- // 'M' - Begins continuous sampling, but measures the execution time of the first
- // sample processing. This duration can be later read through 'm'.
- case 'M':
- if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle)) {
- run_status = RunStatus::Running;
- samplesOut.clear();
- ADC::start(samplesIn.data(), samplesIn.size(), signal_operate_measure);
- DAC::start(0, samplesOut.data(), samplesOut.size());
- }
- break;
-
- // 'm' - Returns the last measured sample processing time, presumably in processor
- // ticks.
- case 'm':
- USBSerial::write(reinterpret_cast<uint8_t *>(&conversion_time_measurement.last),
- sizeof(rtcnt_t));
- break;
-
- // 'R' - Begin continuous sampling/conversion of the ADC. Samples will go through
- // the conversion code, and will be sent out over the DAC.
- case 'R':
- if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle)) {
- run_status = RunStatus::Running;
- samplesOut.clear();
- ADC::start(samplesIn.data(), samplesIn.size(), signal_operate);
- DAC::start(0, samplesOut.data(), samplesOut.size());
- }
- break;
-
- case 'r':
- if (EM.assert(USBSerial::read(&cmd[1], 1) == 1, Error::BadParamSize)) {
- if (cmd[1] == 0xFF) {
- unsigned char r = static_cast<unsigned char>(ADC::getRate());
- USBSerial::write(&r, 1);
- } else {
- ADC::setRate(static_cast<ADC::Rate>(cmd[1]));
- }
- }
- break;
-
- // 'S' - Stops the continuous sampling/conversion.
- case 'S':
- if (run_status == RunStatus::Running) {
- DAC::stop(0);
- ADC::stop();
- run_status = RunStatus::Idle;
- }
- break;
-
- case 's':
- if (auto samps = samplesOut.modified(); samps != nullptr) {
- unsigned char buf[2] = {
- static_cast<unsigned char>(samplesOut.size() / 2 & 0xFF),
- static_cast<unsigned char>(((samplesOut.size() / 2) >> 8) & 0xFF)
- };
- USBSerial::write(buf, 2);
- unsigned int total = samplesOut.bytesize() / 2;
- unsigned int offset = 0;
- unsigned char unused;
- while (total > 512) {
- USBSerial::write(reinterpret_cast<uint8_t *>(samps) + offset, 512);
- while (USBSerial::read(&unused, 1) == 0);
- offset += 512;
- total -= 512;
- }
- USBSerial::write(reinterpret_cast<uint8_t *>(samps) + offset, total);
- while (USBSerial::read(&unused, 1) == 0);
- } else {
- USBSerial::write(reinterpret_cast<const uint8_t *>("\0\0"), 2);
- }
- break;
-
- case 'W':
- DAC::start(1, samplesSigGen.data(), samplesSigGen.size());
- break;
- case 'w':
- DAC::stop(1);
- break;
-
- default:
- break;
- }
- }
- }
-
- chThdSleepMicroseconds(100);
- }
-}
-
-void conversion_abort()
-{
- elf_entry = nullptr;
- DAC::stop(0);
- ADC::stop();
- EM.add(Error::ConversionAborted);
-}
-
-THD_FUNCTION(conversionThread, arg)
-{
- (void)arg;
-
- while (1) {
- msg_t message;
- if (chMBFetchTimeout(&conversionMB, &message, TIME_INFINITE) == MSG_OK) {
- auto samples = MSG_FOR_FIRST(message) ? samplesIn.data() : samplesIn.middata();
- auto size = samplesIn.size() / 2;
-
- if (elf_entry) {
- if (!MSG_FOR_MEASURE(message)) {
- samples = elf_entry(samples, size);
- } else {
- chTMStartMeasurementX(&conversion_time_measurement);
- samples = elf_entry(samples, size);
- chTMStopMeasurementX(&conversion_time_measurement);
- }
- }
-
- if (MSG_FOR_FIRST(message))
- samplesOut.modify(samples, size);
- else
- samplesOut.midmodify(samples, size);
- }
- }
-}
-
-void signal_operate(adcsample_t *buffer, [[maybe_unused]] size_t count)
-{
- if (chMBGetUsedCountI(&conversionMB) > 1)
- conversion_abort();
- else
- chMBPostI(&conversionMB, buffer == samplesIn.data() ? MSG_CONVFIRST : MSG_CONVSECOND);
-}
-
-void signal_operate_measure(adcsample_t *buffer, [[maybe_unused]] size_t count)
-{
- chMBPostI(&conversionMB, buffer == samplesIn.data() ? MSG_CONVFIRST_MEASURE : MSG_CONVSECOND_MEASURE);
- ADC::setOperation(signal_operate);
-}
-
-extern "C" {
-
-__attribute__((naked))
-void HardFault_Handler()
-{
- //asm("push {lr}");
-
- uint32_t *stack;
- uint32_t lr;
- asm("\
- tst lr, #4; \
- ite eq; \
- mrseq %0, msp; \
- mrsne %0, psp; \
- mov %1, lr; \
- " : "=r" (stack), "=r" (lr));
- //stack++;
- stack[7] |= (1 << 24); // Keep Thumb mode enabled
-
- conversion_abort();
-
- // TODO test lr and decide how to recover
-
- //if (run_status == RunStatus::Converting) {
- stack[6] = stack[5]; // Escape from elf_entry code
- //} else /*if (run_status == RunStatus::Recovered)*/ {
- // stack[6] = (uint32_t)main_loop & ~1; // Return to safety
- //}
-
- //asm("pop {lr}; bx lr");
- asm("bx lr");
-}
-
-} // extern "C"
-
+/**
+ * @file main.cpp
+ * @brief Program entry point.
+ *
+ * Copyright (C) 2020 Clyne Sullivan
+ *
+ * Distributed under the GNU GPL v3 or later. You should have received a copy of
+ * the GNU General Public License along with this program.
+ * If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#include "ch.h"
+#include "hal.h"
+
+static_assert(sizeof(adcsample_t) == sizeof(uint16_t));
+static_assert(sizeof(dacsample_t) == sizeof(uint16_t));
+
+#include "common.hpp"
+#include "error.hpp"
+
+#include "adc.hpp"
+#include "dac.hpp"
+#include "elf_load.hpp"
+#include "usbserial.hpp"
+
+#include <array>
+
+constexpr unsigned int MAX_ELF_FILE_SIZE = 8 * 1024;
+
+enum class RunStatus : char
+{
+ Idle = '1',
+ Running
+};
+static RunStatus run_status = RunStatus::Idle;
+
+#define MSG_CONVFIRST (1)
+#define MSG_CONVSECOND (2)
+#define MSG_CONVFIRST_MEASURE (3)
+#define MSG_CONVSECOND_MEASURE (4)
+
+#define MSG_FOR_FIRST(m) (m & 1)
+#define MSG_FOR_MEASURE(m) (m > 2)
+
+static msg_t conversionMBBuffer[4];
+static MAILBOX_DECL(conversionMB, conversionMBBuffer, 4);
+
+static THD_WORKING_AREA(conversionThreadWA, 2048);
+static THD_FUNCTION(conversionThread, arg);
+
+static time_measurement_t conversion_time_measurement;
+
+static ErrorManager EM;
+
+static SampleBuffer samplesIn (reinterpret_cast<Sample *>(0x38000000));
+static SampleBuffer samplesOut (reinterpret_cast<Sample *>(0x38002000));
+#ifdef ENABLE_SIGGEN
+static SampleBuffer samplesSigGen;
+#endif
+
+static unsigned char elf_file_store[MAX_ELF_FILE_SIZE];
+static ELF::Entry elf_entry = nullptr;
+
+static void signal_operate(adcsample_t *buffer, size_t count);
+static void signal_operate_measure(adcsample_t *buffer, size_t count);
+static void main_loop();
+
+static THD_WORKING_AREA(waThread1, 128);
+static THD_FUNCTION(Thread1, arg);
+
+int main()
+{
+ // Initialize the RTOS
+ halInit();
+ chSysInit();
+
+ //SCB_DisableDCache();
+
+ // Enable FPU
+ SCB->CPACR |= 0xF << 20;
+
+ ADC::begin();
+ DAC::begin();
+ USBSerial::begin();
+
+ // Start the conversion manager thread
+ chTMObjectInit(&conversion_time_measurement);
+ chThdCreateStatic(waThread1, sizeof(waThread1), NORMALPRIO, Thread1,
+ nullptr);
+ chThdCreateStatic(conversionThreadWA, sizeof(conversionThreadWA),
+ NORMALPRIO, conversionThread, nullptr);
+
+ main_loop();
+}
+
+void main_loop()
+{
+
+ while (1) {
+ if (USBSerial::isActive()) {
+ // Attempt to receive a command packet
+ if (unsigned char cmd[3]; USBSerial::read(&cmd[0], 1) > 0) {
+ // Packet received, first byte represents the desired command/action
+ switch (cmd[0]) {
+
+ case 'a':
+ USBSerial::write(samplesIn.bytedata(), samplesIn.bytesize());
+ break;
+ case 'A':
+ USBSerial::read(samplesIn.bytedata(), samplesIn.bytesize());
+ break;
+
+ case 'B':
+ if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle) &&
+ EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize))
+ {
+ unsigned int count = (cmd[1] | (cmd[2] << 8)) * 2;
+ if (EM.assert(count <= MAX_SAMPLE_BUFFER_SIZE, Error::BadParam)) {
+ samplesIn.setSize(count);
+ samplesOut.setSize(count);
+ }
+ }
+ break;
+
+ case 'd':
+ USBSerial::write(samplesOut.bytedata(), samplesOut.bytesize());
+ break;
+#ifdef ENABLE_SIGGEN
+ case 'D':
+ if (EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize)) {
+ unsigned int count = cmd[1] | (cmd[2] << 8);
+ if (EM.assert(count <= MAX_SAMPLE_BUFFER_SIZE, Error::BadParam)) {
+ samplesSigGen.setSize(count);
+ USBSerial::read(samplesSigGen.bytedata(), samplesSigGen.bytesize());
+ }
+ }
+ break;
+#endif
+
+ // 'E' - Reads in and loads the compiled conversion code binary from USB.
+ case 'E':
+ if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle) &&
+ EM.assert(USBSerial::read(&cmd[1], 2) == 2, Error::BadParamSize))
+ {
+ // Only load the binary if it can fit in the memory reserved for it.
+ unsigned int size = cmd[1] | (cmd[2] << 8);
+ if (EM.assert(size < sizeof(elf_file_store), Error::BadUserCodeSize)) {
+ USBSerial::read(elf_file_store, size);
+ elf_entry = ELF::load(elf_file_store);
+
+ EM.assert(elf_entry != nullptr, Error::BadUserCodeLoad);
+ }
+ }
+ break;
+
+ // 'e' - Unloads the currently loaded conversion code
+ case 'e':
+ elf_entry = nullptr;
+ break;
+
+ // 'i' - Sends an identifying string to confirm that this is the stmdsp device.
+ case 'i':
+ USBSerial::write(reinterpret_cast<const uint8_t *>("stmdsp"), 6);
+ break;
+
+ // 'I' - Sends the current run status.
+ case 'I':
+ {
+ unsigned char buf[2] = {
+ static_cast<unsigned char>(run_status),
+ static_cast<unsigned char>(EM.pop())
+ };
+ USBSerial::write(buf, sizeof(buf));
+ }
+ break;
+
+ // 'M' - Begins continuous sampling, but measures the execution time of the first
+ // sample processing. This duration can be later read through 'm'.
+ case 'M':
+ if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle)) {
+ run_status = RunStatus::Running;
+ samplesOut.clear();
+ ADC::start(samplesIn.data(), samplesIn.size(), signal_operate_measure);
+ DAC::start(0, samplesOut.data(), samplesOut.size());
+ }
+ break;
+
+ // 'm' - Returns the last measured sample processing time, presumably in processor
+ // ticks.
+ case 'm':
+ USBSerial::write(reinterpret_cast<uint8_t *>(&conversion_time_measurement.last),
+ sizeof(rtcnt_t));
+ break;
+
+ // 'R' - Begin continuous sampling/conversion of the ADC. Samples will go through
+ // the conversion code, and will be sent out over the DAC.
+ case 'R':
+ if (EM.assert(run_status == RunStatus::Idle, Error::NotIdle)) {
+ run_status = RunStatus::Running;
+ samplesOut.clear();
+ ADC::start(samplesIn.data(), samplesIn.size(), signal_operate);
+ DAC::start(0, samplesOut.data(), samplesOut.size());
+ }
+ break;
+
+ case 'r':
+ if (EM.assert(USBSerial::read(&cmd[1], 1) == 1, Error::BadParamSize)) {
+ if (cmd[1] == 0xFF) {
+ unsigned char r = static_cast<unsigned char>(ADC::getRate());
+ USBSerial::write(&r, 1);
+ } else {
+ ADC::setRate(static_cast<ADC::Rate>(cmd[1]));
+ }
+ }
+ break;
+
+ // 'S' - Stops the continuous sampling/conversion.
+ case 'S':
+ if (run_status == RunStatus::Running) {
+ DAC::stop(0);
+ ADC::stop();
+ run_status = RunStatus::Idle;
+ }
+ break;
+
+ case 's':
+ if (auto samps = samplesOut.modified(); samps != nullptr) {
+ unsigned char buf[2] = {
+ static_cast<unsigned char>(samplesOut.size() / 2 & 0xFF),
+ static_cast<unsigned char>(((samplesOut.size() / 2) >> 8) & 0xFF)
+ };
+ USBSerial::write(buf, 2);
+ unsigned int total = samplesOut.bytesize() / 2;
+ unsigned int offset = 0;
+ unsigned char unused;
+ while (total > 512) {
+ USBSerial::write(reinterpret_cast<uint8_t *>(samps) + offset, 512);
+ while (USBSerial::read(&unused, 1) == 0);
+ offset += 512;
+ total -= 512;
+ }
+ USBSerial::write(reinterpret_cast<uint8_t *>(samps) + offset, total);
+ while (USBSerial::read(&unused, 1) == 0);
+ } else {
+ USBSerial::write(reinterpret_cast<const uint8_t *>("\0\0"), 2);
+ }
+ break;
+
+#ifdef ENABLE_SIGGEN
+ case 'W':
+ DAC::start(1, samplesSigGen.data(), samplesSigGen.size());
+ break;
+ case 'w':
+ DAC::stop(1);
+ break;
+#endif
+
+ default:
+ break;
+ }
+ }
+ }
+
+ chThdSleepMicroseconds(100);
+ }
+}
+
+void conversion_abort()
+{
+ elf_entry = nullptr;
+ DAC::stop(0);
+ ADC::stop();
+ EM.add(Error::ConversionAborted);
+}
+
+THD_FUNCTION(conversionThread, arg)
+{
+ (void)arg;
+
+ while (1) {
+ msg_t message;
+ if (chMBFetchTimeout(&conversionMB, &message, TIME_INFINITE) == MSG_OK) {
+ auto samples = MSG_FOR_FIRST(message) ? samplesIn.data() : samplesIn.middata();
+ auto size = samplesIn.size() / 2;
+
+ if (elf_entry) {
+ if (!MSG_FOR_MEASURE(message)) {
+ samples = elf_entry(samples, size);
+ } else {
+ chTMStartMeasurementX(&conversion_time_measurement);
+ samples = elf_entry(samples, size);
+ chTMStopMeasurementX(&conversion_time_measurement);
+ }
+ }
+
+ if (MSG_FOR_FIRST(message))
+ samplesOut.modify(samples, size);
+ else
+ samplesOut.midmodify(samples, size);
+ }
+ }
+}
+
+void signal_operate(adcsample_t *buffer, size_t)
+{
+ chSysLockFromISR();
+
+ if (chMBGetUsedCountI(&conversionMB) > 1) {
+ chSysUnlockFromISR();
+ conversion_abort();
+ } else {
+ chMBPostI(&conversionMB, buffer == samplesIn.data() ? MSG_CONVFIRST : MSG_CONVSECOND);
+ chSysUnlockFromISR();
+ }
+}
+
+void signal_operate_measure(adcsample_t *buffer, [[maybe_unused]] size_t count)
+{
+ chSysLockFromISR();
+ chMBPostI(&conversionMB, buffer == samplesIn.data() ? MSG_CONVFIRST_MEASURE : MSG_CONVSECOND_MEASURE);
+ chSysUnlockFromISR();
+
+ ADC::setOperation(signal_operate);
+}
+
+THD_FUNCTION(Thread1, arg)
+{
+ (void)arg;
+ while (1) {
+ palSetLine(LINE_LED1);
+ chThdSleepMilliseconds(70);
+ palSetLine(LINE_LED2);
+ chThdSleepMilliseconds(70);
+ palSetLine(LINE_LED3);
+ chThdSleepMilliseconds(240);
+ palClearLine(LINE_LED1);
+ chThdSleepMilliseconds(70);
+ palClearLine(LINE_LED2);
+ chThdSleepMilliseconds(70);
+ palClearLine(LINE_LED3);
+ chThdSleepMilliseconds(240);
+ }
+}
+
+extern "C" {
+
+__attribute__((naked))
+void HardFault_Handler()
+{
+ while (1);
+// //asm("push {lr}");
+//
+// uint32_t *stack;
+// uint32_t lr;
+// asm("\
+// tst lr, #4; \
+// ite eq; \
+// mrseq %0, msp; \
+// mrsne %0, psp; \
+// mov %1, lr; \
+// " : "=r" (stack), "=r" (lr));
+// //stack++;
+// stack[7] |= (1 << 24); // Keep Thumb mode enabled
+//
+// conversion_abort();
+//
+// // TODO test lr and decide how to recover
+//
+// //if (run_status == RunStatus::Converting) {
+// stack[6] = stack[5]; // Escape from elf_entry code
+// //} else /*if (run_status == RunStatus::Recovered)*/ {
+// // stack[6] = (uint32_t)main_loop & ~1; // Return to safety
+// //}
+//
+// //asm("pop {lr}; bx lr");
+// asm("bx lr");
+}
+
+} // extern "C"
+
diff --git a/source/usbcfg.c b/source/usbcfg.c
index 4c5809a..051fcd5 100644
--- a/source/usbcfg.c
+++ b/source/usbcfg.c
@@ -335,7 +335,7 @@ const USBConfig usbcfg = {
* Serial over USB driver configuration.
*/
const SerialUSBConfig serusbcfg = {
- &USBD1,
+ &USBD2,
USBD1_DATA_REQUEST_EP,
USBD1_DATA_AVAILABLE_EP,
USBD1_INTERRUPT_REQUEST_EP