aboutsummaryrefslogtreecommitdiff
path: root/center_fw/src
diff options
context:
space:
mode:
Diffstat (limited to 'center_fw/src')
-rw-r--r--center_fw/src/adc.c305
-rw-r--r--center_fw/src/adc.h96
-rw-r--r--center_fw/src/main.c337
-rw-r--r--center_fw/src/protocol.c149
-rw-r--r--center_fw/src/protocol.h33
-rw-r--r--center_fw/src/protocol_test.c163
-rw-r--r--center_fw/src/transmit.c53
-rw-r--r--center_fw/src/transmit.h18
8 files changed, 233 insertions, 921 deletions
diff --git a/center_fw/src/adc.c b/center_fw/src/adc.c
deleted file mode 100644
index 0cf70d1..0000000
--- a/center_fw/src/adc.c
+++ /dev/null
@@ -1,305 +0,0 @@
-/* Megumin LED display firmware
- * Copyright (C) 2018 Sebastian Götte <code@jaseg.net>
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- */
-
-#include "adc.h"
-
-#include <stdbool.h>
-#include <stdlib.h>
-
-#define DETECTOR_CHANNEL a
-
-volatile uint16_t adc_buf[ADC_BUFSIZE];
-volatile struct adc_state adc_state = {0};
-#define st adc_state
-volatile struct adc_measurements adc_data;
-
-static void adc_dma_init(int burstlen, bool enable_interrupt);
-static void adc_timer_init(int psc, int ivl);
-
-
-/* Mode that can be used for debugging */
-void adc_configure_scope_mode(uint8_t channel_mask, int sampling_interval_ns) {
- /* The constant SAMPLE_FAST (0) when passed in as sampling_interval_ns is handled specially in that we turn the ADC
- to continuous mode to get the highest possible sampling rate. */
-
- /* First, disable trigger timer, DMA and ADC in case we're reconfiguring on the fly. */
- TIM1->CR1 &= ~TIM_CR1_CEN;
- ADC1->CR &= ~ADC_CR_ADSTART;
- DMA1_Channel1->CCR &= ~DMA_CCR_EN;
-
- /* keep track of current mode in global variable */
- st.adc_mode = ADC_SCOPE;
-
- adc_dma_init(sizeof(adc_buf)/sizeof(adc_buf[0]), true);
-
- /* Clock from PCLK/4 instead of the internal exclusive high-speed RC oscillator. */
- ADC1->CFGR2 = (2<<ADC_CFGR2_CKMODE_Pos); /* Use PCLK/4=12MHz */
- /* Sampling time 13.5 ADC clock cycles -> total conversion time 2.17us*/
- ADC1->SMPR = (2<<ADC_SMPR_SMP_Pos);
-
- /* Setup DMA and triggering */
- if (sampling_interval_ns == SAMPLE_FAST) /* Continuous trigger */
- ADC1->CFGR1 = ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG | ADC_CFGR1_CONT;
- else /* Trigger from timer 1 Channel 4 */
- ADC1->CFGR1 = ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG | (2<<ADC_CFGR1_EXTEN_Pos) | (1<<ADC_CFGR1_EXTSEL_Pos);
- ADC1->CHSELR = channel_mask;
- /* Perform self-calibration */
- ADC1->CR |= ADC_CR_ADCAL;
- while (ADC1->CR & ADC_CR_ADCAL)
- ;
- /* Enable conversion */
- ADC1->CR |= ADC_CR_ADEN;
- ADC1->CR |= ADC_CR_ADSTART;
-
- if (sampling_interval_ns == SAMPLE_FAST)
- return; /* We don't need the timer to trigger in continuous mode. */
-
- /* An ADC conversion takes 1.1667us, so to be sure we don't get data overruns we limit sampling to every 1.5us.
- Since we don't have a spare PLL to generate the ADC sample clock and re-configuring the system clock just for this
- would be overkill we round to 250ns increments. The minimum sampling rate is about 60Hz due to timer resolution. */
- int cycles = sampling_interval_ns > 1500 ? sampling_interval_ns/250 : 6;
- if (cycles > 0xffff)
- cycles = 0xffff;
- adc_timer_init(12/*250ns/tick*/, cycles);
-}
-
-/* FIXME figure out the proper place to configure this. */
-#define ADC_TIMER_INTERVAL_US 20
-
-/* Regular operation receiver mode. */
-void adc_configure_monitor_mode(const struct command_if_def *cmd_if) {
- /* First, disable trigger timer, DMA and ADC in case we're reconfiguring on the fly. */
- TIM1->CR1 &= ~TIM_CR1_CEN;
- ADC1->CR &= ~ADC_CR_ADSTART;
- DMA1_Channel1->CCR &= ~DMA_CCR_EN;
-
- /* keep track of current mode in global variable */
- st.adc_mode = ADC_MONITOR;
-
- for (int i=0; i<NCH; i++)
- st.adc_aggregate[i] = 0;
- st.mean_aggregator[0] = st.mean_aggregator[1] = st.mean_aggregator[2] = 0;
- st.mean_aggregate_ctr = 0;
-
- st.det_st.hysteresis_mv = 6000;
- /* base_cycles * the ADC timer interval (20us) must match the driver's AC period. */
- st.det_st.base_interval_cycles = 40; /* 40 * 20us = 800us/1.25kHz */
-
- st.det_st.sync = 0;
- st.det_st.last_bit = 0;
- st.det_st.committed_len_ctr = st.det_st.len_ctr = 0;
- xfr_8b10b_reset((struct state_8b10b_dec *)&st.det_st.rx8b10b);
- reset_receiver((struct proto_rx_st *)&st.det_st.rx_st, cmd_if);
-
- adc_dma_init(NCH, true);
-
- /* Setup DMA and triggering: Trigger from Timer 1 Channel 4 */
- ADC1->CFGR1 = ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG | (2<<ADC_CFGR1_EXTEN_Pos) | (1<<ADC_CFGR1_EXTSEL_Pos);
- /* Clock from PCLK/4 instead of the internal exclusive high-speed RC oscillator. */
- ADC1->CFGR2 = (2<<ADC_CFGR2_CKMODE_Pos); /* Use PCLK/4=12MHz */
- /* Sampling time 13.5 ADC clock cycles -> total conversion time 2.17us*/
- ADC1->SMPR = (2<<ADC_SMPR_SMP_Pos);
- /* Internal VCC and temperature sensor channels */
- ADC1->CHSELR = ADC_CHSELR_CHSEL0 | ADC_CHSELR_CHSEL1 | ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17;
- /* Enable internal voltage reference and temperature sensor */
- ADC->CCR = ADC_CCR_TSEN | ADC_CCR_VREFEN;
- /* Perform ADC calibration */
- ADC1->CR |= ADC_CR_ADCAL;
- while (ADC1->CR & ADC_CR_ADCAL)
- ;
- /* Enable ADC */
- ADC1->CR |= ADC_CR_ADEN;
- ADC1->CR |= ADC_CR_ADSTART;
-
- /* Initialize the timer. Set the divider to get a nice round microsecond tick. The interval must be long enough to
- * comfortably fit all conversions inside. There should be some margin since the ADC runs off its own internal RC
- * oscillator and will drift w.r.t. the system clock. 20us is a nice value when four channels are selected (A, B,
- * T and V).
- */
- adc_timer_init(SystemCoreClock/1000000/*1.0us/tick*/, 20/* us */);
-}
-
-static void adc_dma_init(int burstlen, bool enable_interrupt) {
- /* Configure DMA 1 Channel 1 to get rid of all the data */
- DMA1_Channel1->CPAR = (unsigned int)&ADC1->DR;
- DMA1_Channel1->CMAR = (unsigned int)&adc_buf;
- DMA1_Channel1->CNDTR = burstlen;
- DMA1_Channel1->CCR = (0<<DMA_CCR_PL_Pos);
- DMA1_Channel1->CCR |=
- DMA_CCR_CIRC /* circular mode so we can leave it running indefinitely */
- | (1<<DMA_CCR_MSIZE_Pos) /* 16 bit */
- | (1<<DMA_CCR_PSIZE_Pos) /* 16 bit */
- | DMA_CCR_MINC
- | (enable_interrupt ? DMA_CCR_TCIE : 0); /* Enable transfer complete interrupt. */
-
- if (enable_interrupt) {
- /* triggered on transfer completion. We use this to process the ADC data */
- NVIC_EnableIRQ(DMA1_Channel1_IRQn);
- NVIC_SetPriority(DMA1_Channel1_IRQn, 2<<5);
- } else {
- NVIC_DisableIRQ(DMA1_Channel1_IRQn);
- DMA1->IFCR |= DMA_IFCR_CGIF1;
- }
-
- DMA1_Channel1->CCR |= DMA_CCR_EN; /* Enable channel */
-}
-
-static void adc_timer_init(int psc, int ivl) {
- TIM1->BDTR = TIM_BDTR_MOE; /* MOE is needed even though we only "output" a chip-internal signal TODO: Verify this. */
- TIM1->CCMR2 = (6<<TIM_CCMR2_OC4M_Pos); /* PWM Mode 1 to get a clean trigger signal */
- TIM1->CCER = TIM_CCER_CC4E; /* Enable capture/compare unit 4 connected to ADC */
- TIM1->CCR4 = 1; /* Trigger at start of timer cycle */
- /* Set prescaler and interval */
- TIM1->PSC = psc-1;
- TIM1->ARR = ivl-1;
- /* Preload all values */
- TIM1->EGR |= TIM_EGR_UG;
- TIM1->CR1 = TIM_CR1_ARPE;
- /* And... go! */
- TIM1->CR1 |= TIM_CR1_CEN;
-}
-
-/* This acts as a no-op that provides a convenient point to set a breakpoint for the debug scope logic */
-static void gdb_dump(void) {
-}
-
-/* Called on reception of a bit. This feeds the bit to the 8b10b state machine. When the 8b10b state machine recognizes
- * a received symbol, this in turn calls receive_symbol. Since this is called at sampling time roughly halfway into a
- * bit being received, receive_symbol is called roughly half-way through the last bit of the symbol, just before the
- * symbol's end.
- */
-void receive_bit(struct bit_detector_st *st, int bit) {
- int symbol = xfr_8b10b_feed_bit((struct state_8b10b_dec *)&st->rx8b10b, bit);
- if (symbol == -K28_1)
- st->sync = 1;
-
- if (symbol == -DECODING_IN_PROGRESS)
- return;
-
- if (symbol == -DECODING_ERROR)
- st->sync = 0;
- /* Fall through so we also pass the error to receive_symbol */
-
- receive_symbol(&st->rx_st, symbol);
-
- /* Exceedingly handy piece of debug code: The Debug Scope 2000 (TM) */
- /*
- static int debug_buf_pos = 0;
- if (st->sync) {
- if (debug_buf_pos < NCH) {
- debug_buf_pos = NCH;
- } else {
- adc_buf[debug_buf_pos++] = symbol;
-
- if (debug_buf_pos >= sizeof(adc_buf)/sizeof(adc_buf[0])) {
- debug_buf_pos = 0;
- st->sync = 0;
- gdb_dump();
- for (int i=0; i<sizeof(adc_buf)/sizeof(adc_buf[0]); i++)
- adc_buf[i] = -255;
- }
- }
- }
- */
-}
-
-/* From a series of detected line levels, extract discrete bits. This self-synchronizes to signal transitions. This
- * expects base_interval_cycles to be set correctly. When a bit is detected, this calls receive_bit(st, bit). The call
- * to receive_bit happens at the sampling point about half-way through the bit being received.
- */
-void bit_detector(struct bit_detector_st *st, int a) {
- int new_bit = st->last_bit;
- int diff = a-5500; /* FIXME extract constants */
- if (diff < - st->hysteresis_mv/2)
- new_bit = 0;
- else if (diff > st->hysteresis_mv/2)
- new_bit = 1;
- else
- blank(); /* Safety, in case we get an unexpected transition */
-
- st->len_ctr++;
- if (new_bit != st->last_bit) { /* On transition */
- st->last_bit = new_bit;
- st->len_ctr = 0;
- st->committed_len_ctr = st->base_interval_cycles>>1; /* Commit first half of bit */
-
- } else if (st->len_ctr >= st->committed_len_ctr) {
- /* The line stayed constant for a longer interval than the commited length. Interpret this as a transmitted bit.
- *
- * +-- Master clock edges -->| - - - - |<-- One bit period
- * | | |
- * 1 X X X X X X X X
- * ____/^^^^*^^^^\_______________________________________/^^^^*^^^^^^^^^*^^^^\__________________________________
- * 0 v ^ v ^
- * | | | |
- * | +-------------------------------+ +---------+
- * | | |
- * At this point, commit 1/2 bit (until here). This When we arrive at the committed value, commit next
- * happens in the block above. full bit as we're now right in the middle of the
- * first bit. This happens in the line below.
- */
-
- /* Commit second half of this and first half of possible next bit */
- st->committed_len_ctr += st->base_interval_cycles;
- receive_bit(st, st->last_bit);
- }
-}
-
-void DMA1_Channel1_IRQHandler(void) {
- /* ISR timing measurement for debugging */
- //int start = SysTick->VAL;
-
- /* Clear the interrupt flag */
- DMA1->IFCR |= DMA_IFCR_CGIF1;
-
- if (st.adc_mode == ADC_SCOPE)
- return;
-
- /* FIXME This code section currently is a mess since I left it as soon as it worked. Re-work this and try to get
- * back all the useful monitoring stuff, in particular temperature. */
-
- /* This has been copied from the code examples to section 12.9 ADC>"Temperature sensor and internal reference
- * voltage" in the reference manual with the extension that we actually measure the supply voltage instead of
- * hardcoding it. This is not strictly necessary since we're running off a bored little LDO but it's free and
- * the current supply voltage is a nice health value.
- */
- // FIXME DEBUG adc_data.vcc_mv = (3300 * VREFINT_CAL)/(st.adc_aggregate[VREF_CH]);
-
- int64_t vcc = 3300;
- /* FIXME debug
- int64_t vcc = adc_data.vcc_mv;
- int64_t read = st.adc_aggregate[TEMP_CH] * 10 * 10000;
- int64_t cal = TS_CAL1 * 10 * 10000;
- adc_data.temp_celsius_tenths = 300 + ((read/4096 * vcc) - (cal/4096 * 3300))/43000;
- */
-
- /* Calculate the line voltage from the measured ADC voltage and the used resistive divider ratio */
- const long vmeas_r_total = VMEAS_R_HIGH + VMEAS_R_LOW;
- //int a = adc_data.vmeas_a_mv = (st.adc_aggregate[VMEAS_A]*(vmeas_r_total * vcc / VMEAS_R_LOW)) >> 12;
- int a = adc_data.vmeas_a_mv = (adc_buf[VMEAS_A]*13300) >> 12;
- bit_detector((struct bit_detector_st *)&st.det_st, a);
-
- /* ISR timing measurement for debugging */
- /*
- int end = SysTick->VAL;
- int tdiff = start - end;
- if (tdiff < 0)
- tdiff += SysTick->LOAD;
- st.dma_isr_duration = tdiff;
- */
-}
-
diff --git a/center_fw/src/adc.h b/center_fw/src/adc.h
deleted file mode 100644
index 906cb7f..0000000
--- a/center_fw/src/adc.h
+++ /dev/null
@@ -1,96 +0,0 @@
-/* Megumin LED display firmware
- * Copyright (C) 2018 Sebastian Götte <code@jaseg.net>
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- */
-
-#ifndef __ADC_H__
-#define __ADC_H__
-
-#include "global.h"
-#include "8b10b.h"
-#include "protocol.h"
-
-struct adc_measurements {
- int16_t vcc_mv;
- int16_t temp_celsius_tenths;
- int16_t vmeas_a_mv;
- int16_t vmeas_b_mv;
- int16_t mean_a_mv;
- int16_t mean_b_mv;
- int16_t mean_diff_mv;
-};
-
-enum channel_mask {
- MASK_VMEAS_A = ADC_CHSELR_CHSEL0,
- MASK_VMEAS_B = ADC_CHSELR_CHSEL1
-};
-
-enum adc_mode {
- ADC_UNINITIALIZED,
- ADC_MONITOR,
- ADC_SCOPE
-};
-
-enum sampling_mode {
- SAMPLE_FAST = 0
-};
-
-/* The weird order is to match the channels' order in the DMA buffer. Due to some configuration mistake I can't be
-bothered to fix, the DMA controller outputs ADC measurements off-by-one into the output buffer. */
-enum adc_channels {
- VREF_CH,
- VMEAS_A,
- VMEAS_B,
- TEMP_CH,
- NCH
-};
-
-struct bit_detector_st {
- int hysteresis_mv;
- int sync;
- int base_interval_cycles;
- struct proto_rx_st rx_st;
- /* private stuff */
- int last_bit;
- int len_ctr;
- int committed_len_ctr;
- struct state_8b10b_dec rx8b10b;
-};
-
-struct adc_state {
- enum adc_mode adc_mode;
- int dma_isr_duration;
- struct bit_detector_st det_st;
- /* private stuff */
- uint32_t adc_aggregate[NCH]; /* oversampling accumulator */
- uint32_t mean_aggregate_ctr;
- uint32_t mean_aggregator[3];
-};
-
-extern volatile struct adc_state adc_state;
-extern volatile uint16_t adc_buf[ADC_BUFSIZE];
-extern volatile struct adc_measurements adc_data;
-
-void adc_init(void);
-void adc_configure_scope_mode(uint8_t channel_mask, int sampling_interval_ns);
-void adc_configure_monitor_mode(const struct command_if_def *cmd_if);
-
-void bit_detector(struct bit_detector_st *st, int a);
-void receive_bit(struct bit_detector_st *st, int bit);
-
-void blank(void);
-void unblank(int new_bit);
-
-#endif/*__ADC_H__*/
diff --git a/center_fw/src/main.c b/center_fw/src/main.c
index 274abad..59bd7a1 100644
--- a/center_fw/src/main.c
+++ b/center_fw/src/main.c
@@ -17,11 +17,54 @@
#include "global.h"
#include "8b10b.h"
+#include "crc32.h"
+#include "protocol.h"
+#include "xorshift.h"
-static uint16_t adc_data[64*2];
static volatile struct state_8b10b_dec st_8b10b_dec;
-static void quicksort(uint16_t *head, uint16_t *tail);
+/* Modulation constants */
+#define THRESHOLD_ADC_COUNTS 28500 /* ADC counts */
+#define MIN_RECTIFIER_MARGIN 5000 /* ADC counts */
+#define SAMPLES_PER_BAUD 16
+#define OVERSAMPLING_RATIO 16
+#define SAMPLING_PHASE (SAMPLES_PER_BAUD / 2)
+#define LED_DEAD_TIME 4 /* in ADC samples */
+#ifndef CONFIG_MODULE_ADDRESS
+#warn "CONFIG_MODULE_ADDRESS is not defined, defaulting to 0."
+#define CONFIG_MODULE_ADDRESS 0
+#endif /* CONFIG_MODULE_ADDRESS */
+
+#define DEBUG_DISABLE_DRIVERS 1
+
+
+volatile union {
+ struct data_packet packet;
+ uint8_t bytes[sizeof(struct data_packet)];
+} rx_buf;
+
+volatile ssize_t rx_pos;
+volatile bool packet_received;
+volatile bool rng_reset;
+uint32_t packet_rng_state = 0;
+
+struct data_packet foobar;
+int global_brightness;
+int channel_mask;
+
+struct error_counters {
+ int crc_errors;
+ int receive_overflows;
+ int processing_overflows;
+ int decoding_errors;
+} errors;
+
+/* generated by ./gamma.py */
+uint16_t brightness_lut[16] = {
+ 54, 247, 604, 1137, 1857, 2774, 3894, 5223,
+ 6768, 8534, 10525, 12745, 15199, 17891, 20823, 24000
+};
+
int main(void) {
/* Configure clocks for 64 MHz system clock.
@@ -49,40 +92,35 @@ int main(void) {
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
RCC->APBENR1 |= RCC_APBENR1_TIM3EN | RCC_APBENR1_DBGEN;
- RCC->APBENR2 |= RCC_APBENR2_TIM1EN | RCC_APBENR2_ADCEN;
+ RCC->APBENR2 |= RCC_APBENR2_TIM1EN | RCC_APBENR2_ADCEN | RCC_APBENR2_TIM14EN;
RCC->IOPENR |= RCC_IOPENR_GPIOAEN | RCC_IOPENR_GPIOBEN | RCC_IOPENR_GPIOCEN;
- /*
- TIM1->PSC = 0;
- TIM1->ARR = nominal_period;
- TIM1->DIER = TIM_DIER_UIE | TIM_DIER_CC1IE;
- TIM1->CR1 = TIM_CR1_ARPE | TIM_CR1_CEN;
- TIM1->CCR1 = 3000;
- NVIC_EnableIRQ(TIM1_BRK_UP_TRG_COM_IRQn);
- NVIC_SetPriority(TIM1_BRK_UP_TRG_COM_IRQn, 0);
- NVIC_EnableIRQ(TIM1_CC_IRQn);
- NVIC_SetPriority(TIM1_CC_IRQn, 0);
- */
+ TIM14->CR1 = TIM_CR1_ARPE | TIM_CR1_OPM;
+ /* External clock mode, with TIM 3 as source */
+ TIM14->PSC = 0;
+ static_assert(125 * (SAMPLES_PER_BAUD - LED_DEAD_TIME) * OVERSAMPLING_RATIO <= 0xffff);
+ TIM14->ARR = 125 * (SAMPLES_PER_BAUD - LED_DEAD_TIME) * OVERSAMPLING_RATIO;
+ TIM14->CCER = TIM_CCER_CC1E;
+ TIM14->DIER = TIM_DIER_CC1IE;
+ NVIC_EnableIRQ(TIM14_IRQn);
+ NVIC_SetPriority(TIM14_IRQn, 1<<6);
+
+ for (int i=0; i<COUNT_OF(brightness_lut); i++) {
+ }
xfr_8b10b_reset((struct state_8b10b_dec *)&st_8b10b_dec);
+ rx_pos = -1;
+ packet_received = false;
+ rng_reset = false;
+ memset(&errors, 0, sizeof(errors));
TIM3->CR1 = TIM_CR1_ARPE;
TIM3->CR2 = (2<<TIM_CR2_MMS_Pos); /* Update event on TRGO */
TIM3->PSC = 0;
/* We sample 32 times per 1 kHz AC cycle, and use 32 times oversampling. */
- TIM3->ARR = 125*16; /* Output 64 MHz / 125 = 512 kHz signal */
+ TIM3->ARR = 125; /* Output 64 MHz / 125 = 512.0 kHz signal */
TIM3->CR1 |= TIM_CR1_CEN;
- DMAMUX1[0].CCR = 5; /* ADC */
- DMA1_Channel1->CPAR = (uint32_t)&ADC1->DR;
- DMA1_Channel1->CMAR = (uint32_t)(void *)adc_data;
- DMA1_Channel1->CNDTR = COUNT_OF(adc_data);
- DMA1_Channel1->CCR = (1<<DMA_CCR_MSIZE_Pos) | (1<<DMA_CCR_PSIZE_Pos) | DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_HTIE | DMA_CCR_TCIE;
- DMA1_Channel1->CCR |= DMA_CCR_EN;
-
- NVIC_EnableIRQ(DMA1_Channel1_IRQn);
- NVIC_SetPriority(DMA1_Channel1_IRQn, 64);
-
ADC1->ISR = ADC_ISR_CCRDY | ADC_ISR_ADRDY; /* Clear CCRDY */
ADC1->CR = ADC_CR_ADVREGEN;
delay_us(20);
@@ -90,8 +128,8 @@ int main(void) {
while (ADC1->CR & ADC_CR_ADCAL) {
/* wait. */
}
- ADC1->CFGR1 = (1<<ADC_CFGR1_EXTEN_Pos) | (3<<ADC_CFGR1_EXTSEL_Pos) | ADC_CFGR1_DMAEN | ADC_CFGR1_DMACFG; /* TIM3 TRGO */
- ADC1->CFGR2 = (1<<ADC_CFGR2_CKMODE_Pos) | (4<<ADC_CFGR2_OVSR_Pos) | (1<<ADC_CFGR2_OVSS_Pos) | ADC_CFGR2_OVSE;
+ ADC1->CFGR1 = (1<<ADC_CFGR1_EXTEN_Pos) | (3<<ADC_CFGR1_EXTSEL_Pos); /* TIM3 TRGO */
+ ADC1->CFGR2 = (1<<ADC_CFGR2_CKMODE_Pos) | (3<<ADC_CFGR2_OVSR_Pos) | (0<<ADC_CFGR2_OVSS_Pos) | ADC_CFGR2_TOVS | ADC_CFGR2_OVSE;
ADC1->CHSELR = (1<<4); /* Enable input 4 -> PA4 (Vdiff)*/
while (!(ADC1->ISR & ADC_ISR_CCRDY)) {
/* wait. */
@@ -102,6 +140,9 @@ int main(void) {
while (!(ADC1->ISR & ADC_ISR_ADRDY)) {
/* wait. */
}
+ ADC1->IER = ADC_IER_EOCIE;
+ NVIC_EnableIRQ(ADC1_IRQn);
+ NVIC_SetPriority(ADC1_IRQn, 0);
ADC1->CR |= ADC_CR_ADSTART;
GPIOA->MODER = OUT(0) | IN(1) | OUT(2) | OUT(3) | ANALOG(4) | OUT(5) | OUT(6) | IN(7) | ANALOG(9) | ANALOG(10) | OUT(11) | ANALOG(12)| AF(13) | AF(14);
@@ -111,73 +152,187 @@ int main(void) {
DBG->APBFZ1 |= DBG_APB_FZ1_DBG_TIM3_STOP;
DBG->APBFZ2 |= DBG_APB_FZ2_DBG_TIM1_STOP;
while (42) {
+ if (packet_received) {
+ if (rng_reset) {
+ packet_rng_state = xorshift32(1);
+ }
+
+ for(size_t i=0; i<sizeof(rx_buf.packet); i++) {
+ packet_rng_state = xorshift32(packet_rng_state);
+ // rx_buf.bytes[i] ^= packet_rng_state; FIXME DEBUG
+ }
+
+ uint32_t crc_state = crc32_reset();
+ for(size_t i=0; i<offsetof(struct data_packet, crc); i++) {
+ crc_state = crc32_update(crc_state, rx_buf.bytes[i]);
+ }
+ crc_state = crc32_finalize(crc_state);
+
+ if (crc_state == rx_buf.packet.crc) {
+ /* good packet received */
+ int val = rx_buf.packet.brightness[CONFIG_MODULE_ADDRESS/2];
+ if (CONFIG_MODULE_ADDRESS & 1) {
+ val >>= 4;
+ }
+ global_brightness = val;
+ channel_mask = rx_buf.packet.channels[CONFIG_MODULE_ADDRESS];
+
+ } else {
+ errors.crc_errors++;
+ }
+
+ packet_received = false;
+ }
}
}
-/*
-void TIM1_BRK_UP_TRG_COM_IRQHandler(void) {
- TIM1->SR &= ~TIM_SR_UIF;
-}
+int16_t sym_dump[512];
+size_t sym_dump_pos = 0;
+
+uint8_t adc_dump[32];
+size_t adc_dump_pos = 0;
+
+uint8_t bit_dump[4096];
+size_t bit_dump_pos = 0;
-void TIM1_CC_IRQHandler(void) {
- TIM1->SR &= ~TIM_SR_CC1IF;
+void gdb_dump(void) {
}
-*/
-static size_t received_symbols = 0;
-static int symbol_buf[64];
-static size_t received_bits = 0;
-static int16_t bit_buf[256];
-size_t adc_reduced_pos = 0;
-static uint8_t adc_reduced[4096];
-
-void DMA1_Channel1_IRQHandler(void) {
- static int sampling_phase = 0;
- static int last_sample = 0;
-
- uint16_t *buf = (DMA1->ISR & DMA_ISR_HTIF1) ? &adc_data[0] : &adc_data[COUNT_OF(adc_data)/2];
- DMA1->IFCR = DMA_IFCR_CGIF1;
+
+void ADC1_IRQHandler(void) {
+ static int phase = 0;
+ static int last_bit = 0;
GPIOB->BSRR = (1<<7);
- const int threshold_adc_counts = 28500;
- const int sample_per_baud = 16;
+ /* Read sample and apply threshold */
+ int sample = ADC1->DR; /* resets the EOC interrupt flag */
+ int bit = sample > THRESHOLD_ADC_COUNTS;
+ int bit_margin = ((int)sample) - THRESHOLD_ADC_COUNTS;
+ if (bit_margin < 0) {
+ bit_margin = -bit_margin;
+ }
+
+ adc_dump[adc_dump_pos] = (sample>>10) & 0x3f;
- for (size_t i=0; i<COUNT_OF(adc_data)/2; i++) {
- int sample = buf[i];
+ /* Find edges and compute current phase */
+ if (bit && !last_bit) { /* rising edge */
+ phase = 0;
+ adc_dump[adc_dump_pos] |= 0x40;
- adc_reduced[adc_reduced_pos] = (sample & 0xffff)>>9;
+ } else if (last_bit && !bit) { /* falling edge */
+ phase = 0;
+ adc_dump[adc_dump_pos] |= 0x40;
- if ((last_sample <= threshold_adc_counts && sample >= threshold_adc_counts) ||
- (last_sample >= threshold_adc_counts && sample <= threshold_adc_counts)){
- sampling_phase = sample_per_baud / 4; /* /2 for half baud sampling point, /2 for sinusoidal edge shape */
+ } else {
+ phase ++;
+ if (phase == SAMPLES_PER_BAUD) {
+ phase = 0;
+ }
+ }
- } else if (sampling_phase == 0) {
- int bit = sample > threshold_adc_counts;
- adc_reduced[adc_reduced_pos] |= 0x80;
+ /* Trigger 8b10b sample */
+ if (phase == SAMPLING_PHASE) {
+ adc_dump[adc_dump_pos] |= 0x80;
- bit_buf[received_bits] = bit;
- received_bits = (received_bits+1) % COUNT_OF(bit_buf);
+ bit_dump[bit_dump_pos] = bit;
+ bit_dump_pos++;
+ if (bit_dump_pos == COUNT_OF(bit_dump)) {
+ bit_dump_pos = 0;
+ gdb_dump();
+ }
- int rc = xfr_8b10b_feed_bit((struct state_8b10b_dec *)&st_8b10b_dec, bit);
- if (rc > -K_CODES_LAST) {
- symbol_buf[received_symbols] = rc;
- received_symbols = (received_symbols+1) % COUNT_OF(symbol_buf);
+ int rc = xfr_8b10b_feed_bit((struct state_8b10b_dec *)&st_8b10b_dec, bit);
+ if (rc > -K_CODES_LAST) {
+ sym_dump[sym_dump_pos++] = rc;
+ if (sym_dump_pos == COUNT_OF(sym_dump)) {
+ sym_dump_pos = 0;
}
- sampling_phase = sample_per_baud;
+ if (rc < 0) {
+ if (rc == -K28_1) {
+ rng_reset = true;
+ rx_pos = 0;
+
+ } else if (rc == -K27_7) {
+ if (rx_pos >= 0) {
+ rx_pos = 0;
+ }
+ } else {
+ rx_pos = -1;
+ }
+ } else {
+ if (packet_received) {
+ /* receive buffer overflow */
+ rx_pos = -1;
+ errors.processing_overflows++;
+
+ } else {
+ if (rx_pos == sizeof(rx_buf.packet)) {
+ /* receive buffer overflow */
+ rx_pos = -1;
+ errors.receive_overflows++;
+ }
+
+ rx_buf.bytes[rx_pos] = rc;
+ rx_pos++;
+ if (rx_pos == sizeof(rx_buf.packet)) {
+ packet_received = true;
+ }
+ }
+ }
} else {
- sampling_phase--;
+ errors.decoding_errors++;
}
+ }
+
+ adc_dump_pos++;
+ if (adc_dump_pos == COUNT_OF(adc_dump)) {
+ adc_dump_pos = 0;
+ }
- adc_reduced_pos++;
- if (adc_reduced_pos == COUNT_OF(adc_reduced)) {
- adc_reduced_pos =0;
+ /* Trigger synchronous rectifier */
+ if (phase == SAMPLES_PER_BAUD - LED_DEAD_TIME || bit != last_bit || bit_margin < MIN_RECTIFIER_MARGIN) { /* reset */
+ GPIOA->BRR = (1<<11); /* RECT1 */
+ GPIOC->BRR = (1<<15); /* RECT2 */
+ GPIOA->BRR = (1<<6);
+
+ } else if (phase == LED_DEAD_TIME) { /* set */
+ if (bit) {
+ GPIOA->BSRR = (1<<6);
+#ifndef DEBUG_DISABLE_DRIVERS
+ GPIOC->BSRR = (1<<15); /* RECT2 */
+#endif
+ } else {
+#ifndef DEBUG_DISABLE_DRIVERS
+ GPIOA->BSRR = (1<<11); /* RECT1 */
+#endif
}
- last_sample = sample;
+
+ int nibble = (bit ? (channel_mask >> 4) : channel_mask) & 0x0f;
+ int b0 = (nibble>>0) & 1;
+ int b1 = (nibble>>1) & 1;
+ int b2 = (nibble>>2) & 1;
+ int b3 = (nibble>>3) & 1;
+
+#ifndef DEBUG_DISABLE_DRIVERS
+ GPIOA->BSRR = (b0<<2) | (b3<<3) | (b2<<5);
+ GPIOB->BSRR = (b1<<3);
+#endif
+ TIM14->CCR1 = brightness_lut[global_brightness];
+ TIM14->CR1 |= TIM_CR1_CEN;
}
+ last_bit = bit;
GPIOB->BRR = (1<<7);
}
+void TIM14_IRQHandler(void) {
+ TIM14->SR = 0;
+
+ /* Reset all LED outputs */
+ GPIOA->BRR = (1<<2) | (1<<3) | (1<<5);
+ GPIOB->BRR = (1<<3);
+}
+
void delay_us(int duration_us) {
while (duration_us--) {
for (int i=0; i<32; i++) {
@@ -186,6 +341,14 @@ void delay_us(int duration_us) {
}
}
+void *memset(void *s, int c, size_t n) {
+ uint8_t *b = (uint8_t *)s;
+ while (n--) {
+ *b++ = c;
+ }
+ return s;
+}
+
void NMI_Handler(void) {
asm volatile ("bkpt");
}
@@ -208,37 +371,3 @@ void __libc_init_array (void) __attribute__((weak));
void __libc_init_array () {
}
-/* https://github.com/openmv/openmv/blob/2e8d5d505dbe695b8009d832e5ef7691009148e1/src/omv/common/array.c#L117 */
-static void quicksort(uint16_t *head, uint16_t *tail) {
- while (head < tail) {
- uint16_t *h = head - 1;
- uint16_t *t = tail;
- uint16_t v = tail[0];
- for (;;) {
- do {
- ++h;
- } while (h < t && h[0] < v);
- do {
- --t;
- } while (h < t && v < t[0]);
- if (h >= t) {
- break;
- }
- uint16_t x = h[0];
- h[0] = t[0];
- t[0] = x;
- }
- uint16_t x = h[0];
- h[0] = tail[0];
- tail[0] = x;
- // do the smaller recursive call first, to keep stack within O(log(N))
- if (t - head < tail - h - 1) {
- quicksort(head, t);
- head = h + 1;
- } else {
- quicksort(h + 1, tail);
- tail = t;
- }
- }
-}
-
diff --git a/center_fw/src/protocol.c b/center_fw/src/protocol.c
deleted file mode 100644
index dfa0d3e..0000000
--- a/center_fw/src/protocol.c
+++ /dev/null
@@ -1,149 +0,0 @@
-/* Control protocol receiver sitting between 8b10b.c and logical protocol handlers */
-
-#include <unistd.h>
-#include "protocol.h"
-#include "8b10b.h"
-
-volatile uint32_t decoding_error_cnt = 0, protocol_error_cnt = 0;
-volatile bool backchannel_frame = 0;
-
-/* Reset the given protocol state and register the command definition given with it. */
-void reset_receiver(struct proto_rx_st *st, const struct command_if_def *cmd_if) {
- st->rxpos = -1;
- st->address = 5; /* FIXME debug code */
- st->cmd_if = cmd_if;
-}
-
-/* Receive an 8b10b symbol using the given protocol state. Handle any packets matching the enclosed command definition.
- *
- * This method is called from adc.c during the last bit period of the symbol, just before the actual end of the symbol
- * and start of the next symbol.
- */
-void receive_symbol(struct proto_rx_st *st, int symbol) {
-
- if (symbol == -K28_2) { /* Backchannel marker */
- /* This symbol is inserted into the symbol stream at regular intervals. It is not passed to the higher protocol
- * layers but synchronizes the backchannel logic through all nodes. The backchannel works by a node putting a
- * specified additional load of about 100mA (FIXME) on the line (1) or not (0) with all other nodes being
- * silent. The master can detect this additional current. The backchannel is synchronized to the 8b10b frame
- * being sent from the master, and the data is also 8b10b encoded. This means the backchannel is independent
- * from the forward-channel.
- *
- * This means while the forward-channel (the line voltage) might go like the upper trace, the back-channel (the
- * line current drawn by the node) might simultaneously look like the lower trace:
- *
- * Zoomed in on two master frames:
- *
- * |<--- D31.1 --->| |<--- D03.6 --->|
- * Master -> Node 1 0 1 0 1 1 1 0 0 1 1 1 0 0 0 1 0 1 1 0
- * Voltage (V) .../^^\__/^^\__/^^^^^^^^\_____/^^^^^^^^\________/^^\__/^^^^^\___...
- *
- * Current (I) ...\_____________________________/^^^^^V^^^^^^^^V^^V^^V^^^^^V^^\...
- * Node -> Master 0 1
- *
- *
- * Zoomed out on two node frames, or twenty master frames:
- *
- * Master -> Node | | | | | | | | | | | | | | | | | | |<- symbols, one after another
- * Voltage (V) ...XXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXXX...
- *
- * Current (I) ...___/^^^^^\__/^^\_____/^^\__/^^^^^\_____/^^\__/^^^^^\__/^^\___...
- * Node -> Master 0 1 1 0 1 0 0 1 0 1 1 0 0 1 0 1 1 0 1 0
- * |<--- D22.2 --->| |<--- D09.5 --->|
- *
- * Note that during backchannel transmissions only one node transmits at a time, and all nodes including the
- * transmitter keep their LEDs blanked to allow the master to more easily demodulate the transmission.
- *
- * This means that:
- * * backchannel transmissions should be sparse (one per several regular symbols) to not affect brightness
- * too much
- * * backchannel transmissions should be spaced-out evenly and frequent enough to not cause visible flicker
- *
- * A consequence of this is that the backchannel has a bandwidth of only a fraction of the forward-channel. The
- * master can dynamically adjust the frequency of the forward-channel and spacing of the backchannel markers.
- * For 5kHz and 10% backchannel data (every tenth symbol being a backchannel symbol) the bandwidth works out to:
- *
- * BW(forward-channel) = 5 [kHz] / 10 [8b10b] = 500 byte/s
- * BW(backchannel) = 5 [kHz] / 10 [8b10b] / 10 [every 10th symbol] / 10 [8b10b again] = 5 byte/s
- *
- * Luckily, we only use the backchannel for monitoring anyway and at ~20byte per monitoring frame we can easily
- * monitor a bus-load (heh!) of nodes once a minute, which is enough for our purposes.
- */
-
- /* Blank the LEDs for the next frame to keep the bus quiet during backchannel transmission. This happens on all
- * nodes. */
- backchannel_frame = true;
- return; /* We're done handling this symbol */
- } else {
- /* On anything else than a backchannel marker, turn off backchannel blanking for the next frame */
- backchannel_frame = false;
- }
-
- if (symbol == -K28_1) { /* Comma/frame delimiter */
- st->rxpos = 0;
- /* Fall through and return and just ignore incomplete packets */
-
- } else if (symbol == -DECODING_ERROR) {
- if (decoding_error_cnt < UINT32_MAX)
- decoding_error_cnt++;
- goto reset;
-
- } else if (symbol < 0) { /* Unknown comma symbol */
- if (protocol_error_cnt < UINT32_MAX)
- protocol_error_cnt++;
- goto reset;
-
- } else if (st->rxpos == -1) { /* Receiver freshly reset and no comma seen yet */
- return;
-
- } else if (st->rxpos == 0) { /* First data symbol, and not an error or comma symbol */
- st->packet_type = symbol & ~PKT_TYPE_BULK_FLAG;
- if (st->packet_type >= st->cmd_if->packet_type_max)
- goto reset; /* Not a protocol error */
-
- /* If this a bulk packet, calculate and store the offset of our portion of it. Otherwise just prime the state
- * for receiving the indidual packet by setting the offset to the first packet byte after the address. */
- int payload_len = st->cmd_if->payload_len[st->packet_type];
- st->is_bulk = symbol & PKT_TYPE_BULK_FLAG;
- st->offset = (st->is_bulk) ? (st->address*payload_len + 1) : 2;
- st->rxpos++;
-
- if (payload_len == 0 && st->is_bulk) {
- /* Length-0 packet type, handle now for bulk packets as we don't know when the master will send the next
- * comma or other symbol. For individually addressed packets, wait for the address byte. */
- handle_command(st->packet_type, NULL);
- goto reset;
- }
-
- } else if (!st->is_bulk && st->rxpos == 1) { /* First byte (address byte) of individually adressed packet */
- if (symbol != st->address) /* A different node is adressed */
- goto reset;
-
- if (st->cmd_if->payload_len[st->packet_type] == 0) {
- /* Length-0 packet type, handle now as we don't know when the master will send the next comma or other
- * symbol. */
- handle_command(st->packet_type, NULL);
- goto reset;
- }
- st->rxpos++;
-
- } else { /* Receiving packet body */
- if (st->rxpos - st->offset >= 0) {
- /* Either we're receiving an individually adressed packet adressed to us, or we're in the middle of a bulk
- * packet at our offset */
- st->argbuf[st->rxpos - st->offset] = symbol;
- }
- st->rxpos++;
-
- if (st->rxpos - st->offset == st->cmd_if->payload_len[st->packet_type]) {
- /* We're at the end of either an individual packet or our portion of a bulk packet. Handle packet here. */
- handle_command(st->packet_type, (uint8_t *)st->argbuf);
- goto reset;
- }
- }
-
- return;
-reset:
- st->rxpos = -1;
-}
-
diff --git a/center_fw/src/protocol.h b/center_fw/src/protocol.h
deleted file mode 100644
index 89c93e2..0000000
--- a/center_fw/src/protocol.h
+++ /dev/null
@@ -1,33 +0,0 @@
-#ifndef __PROTOCOL_H__
-#define __PROTOCOL_H__
-
-#include <stdint.h>
-#include <stdbool.h>
-
-#define PKT_TYPE_BULK_FLAG 0x80
-
-struct proto_rx_st {
- int packet_type;
- int is_bulk;
- int rxpos;
- int address;
- uint8_t argbuf[8];
- int offset;
- const struct command_if_def *cmd_if;
-};
-
-struct command_if_def {
- int packet_type_max;
- int payload_len[0];
-};
-
-extern volatile uint32_t decoding_error_cnt, protocol_error_cnt;
-extern volatile bool backchannel_frame;
-
-/* Callback */
-void handle_command(int command, uint8_t *args);
-
-void receive_symbol(struct proto_rx_st *st, int symbol);
-void reset_receiver(struct proto_rx_st *st, const struct command_if_def *cmd_if);
-
-#endif
diff --git a/center_fw/src/protocol_test.c b/center_fw/src/protocol_test.c
deleted file mode 100644
index 4a12ef5..0000000
--- a/center_fw/src/protocol_test.c
+++ /dev/null
@@ -1,163 +0,0 @@
-/* Unit test file testing protocol.c */
-
-#include <string.h>
-#include <assert.h>
-#include <stdio.h>
-#include <unistd.h>
-#include <sys/types.h>
-#include <sys/stat.h>
-#include <fcntl.h>
-
-#include "protocol.h"
-#include "8b10b.h"
-
-static int urandom_fd = -1;
-static long long n_tests = 0;
-
-struct test_cmd_if {
- struct command_if_def cmd_if;
- int payload_len[256];
-};
-
-struct {
- int ncalls;
- int last_cmd;
- uint8_t last_args[sizeof(((struct proto_rx_st *)0)->argbuf)];
-} handler_state;
-
-
-void handle_command(int command, uint8_t *args) {
- handler_state.ncalls++;
- handler_state.last_cmd = command;
- if (args)
- memcpy(handler_state.last_args, args, 8);
-}
-
-void send_test_command_single(struct test_cmd_if *cmd_if, struct proto_rx_st *st, int cmd, int address, unsigned char pattern[256]) {
- n_tests++;
- receive_symbol(st, -K28_1);
- receive_symbol(st, cmd);
- receive_symbol(st, address);
- for (int i=0; i<cmd_if->payload_len[cmd]; i++)
- receive_symbol(st, pattern[i]);
-}
-
-void send_test_command_bulk(struct test_cmd_if *cmd_if, struct proto_rx_st *st, int cmd, int index, int len, unsigned char pattern[256]) {
- n_tests++;
- receive_symbol(st, -K28_1);
- receive_symbol(st, cmd | PKT_TYPE_BULK_FLAG);
- for (int j=0; j<len; j++) {
- for (int i=0; i<cmd_if->payload_len[cmd]; i++) {
- if (j == index)
- receive_symbol(st, pattern[i]);
- else
- receive_symbol(st, 0xaa);
- }
- }
-}
-
-void test_commands_with_pattern(struct test_cmd_if *cmd_if, unsigned char pattern[256]) {
- struct proto_rx_st st;
-
- for (int cmd=0; cmd<cmd_if->cmd_if.packet_type_max; cmd++) {
- /* Addresssed tests */
- reset_receiver(&st, &cmd_if->cmd_if);
- st.address = 23;
- handler_state.ncalls = 0;
- send_test_command_single(cmd_if, &st, cmd, 23, pattern);
- assert(handler_state.ncalls == 1);
- assert(handler_state.last_cmd == cmd);
- assert(!memcmp(handler_state.last_args, pattern, cmd_if->payload_len[cmd]));
-
- reset_receiver(&st, &cmd_if->cmd_if);
- st.address = 23;
- handler_state.ncalls = 0;
- send_test_command_single(cmd_if, &st, cmd, 5, pattern);
- assert(handler_state.ncalls == 0);
-
- reset_receiver(&st, &cmd_if->cmd_if);
- st.address = 5;
- handler_state.ncalls = 0;
- send_test_command_single(cmd_if, &st, cmd, 5, pattern);
- assert(handler_state.ncalls == 1);
- assert(handler_state.last_cmd == cmd);
- assert(!memcmp(handler_state.last_args, pattern, cmd_if->payload_len[cmd]));
-
- /* Bulk test */
- reset_receiver(&st, &cmd_if->cmd_if);
- st.address = 5;
- handler_state.ncalls = 0;
- send_test_command_bulk(cmd_if, &st, cmd, 5, 8, pattern);
- assert(handler_state.ncalls == 1);
- assert(handler_state.last_cmd == cmd);
- assert(!memcmp(handler_state.last_args, pattern, cmd_if->payload_len[cmd]));
- }
-}
-
-void test_commands(struct test_cmd_if *cmd_if) {
- unsigned char data[256];
-
- memset(data, 0, sizeof(data));
- test_commands_with_pattern(cmd_if, data);
-
- memset(data, 1, sizeof(data));
- test_commands_with_pattern(cmd_if, data);
-
- memset(data, 255, sizeof(data));
- test_commands_with_pattern(cmd_if, data);
-
- for (int i=0; i<5; i++) {
- assert(read(urandom_fd, (char *)data, sizeof(data)) == sizeof(data));
- test_commands_with_pattern(cmd_if, data);
- }
-}
-
-int main(void) {
- struct test_cmd_if cmd_if;
-
- urandom_fd = open("/dev/urandom", O_RDONLY);
- assert(urandom_fd > 0);
-
- for (int ncmds=1; ncmds<128; ncmds++) {
- cmd_if.cmd_if.packet_type_max = ncmds;
-
- /* Case 1 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = 0;
- test_commands(&cmd_if);
-
- /* Case 2 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = 1;
- test_commands(&cmd_if);
-
- /* Case 3 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = i&1 ? 1 : 0;
- test_commands(&cmd_if);
-
- /* Case 4 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = i&1 ? 0 : 1;
- test_commands(&cmd_if);
-
- /* Case 5 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = i&1 ? 1 : 2;
- test_commands(&cmd_if);
-
- /* Case 6 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = i%8;
- test_commands(&cmd_if);
-
- /* Case 7 */
- for (int i=0; i<ncmds; i++)
- cmd_if.payload_len[i] = 4;
- test_commands(&cmd_if);
- }
-
- assert(!close(urandom_fd));
-
- printf("Successfully ran %lld tests\n", n_tests);
-}
diff --git a/center_fw/src/transmit.c b/center_fw/src/transmit.c
deleted file mode 100644
index c31c833..0000000
--- a/center_fw/src/transmit.c
+++ /dev/null
@@ -1,53 +0,0 @@
-
-#include "global.h"
-#include "transmit.h"
-#include "8b10b.h"
-
-struct {
- uint8_t *buf;
- size_t pos, len;
- uint16_t current_symbol;
- struct state_8b10b_enc enc;
-} tx_state = {0};
-
-volatile uint32_t tx_overflow_cnt = 0;
-
-void tx_init(uint8_t *tx_buf) {
- tx_state.buf = tx_buf;
- tx_state.pos = 0;
- tx_state.current_symbol = 0;
- xfr_8b10b_encode_reset(&tx_state.enc);
-}
-
-int tx_transmit(size_t len) {
- if (!tx_state.buf)
- return TX_ERR_UNINITIALIZED;
-
- if (tx_state.len) {
- tx_overflow_cnt++;
- return TX_ERR_BUSY;
- }
-
- tx_state.len = len;
- tx_state.current_symbol = 1;
- return 0;
-}
-
-int tx_next_bit() {
- if (!tx_state.len)
- return TX_IDLE;
-
- int sym = tx_state.current_symbol;
- if (sym == 1) /* We're transmitting the first bit of a new frame now. */
- sym = xfr_8b10b_encode(&tx_state.enc, tx_state.buf[tx_state.pos++]) | (1<<10);
-
- int bit = sym&1;
- sym >>= 1;
-
- if (sym == 1 && tx_state.pos == tx_state.len)
- /* We're transmitting the last bit of a transmission now. Reset state. */
- tx_state.pos = tx_state.len = sym = 0;
-
- tx_state.current_symbol = sym;
- return bit;
-}
diff --git a/center_fw/src/transmit.h b/center_fw/src/transmit.h
deleted file mode 100644
index dd9bcb9..0000000
--- a/center_fw/src/transmit.h
+++ /dev/null
@@ -1,18 +0,0 @@
-#ifndef __TRANSMIT_H__
-#define __TRANSMIT_H__
-
-#include "global.h"
-#include "8b10b.h"
-
-#define TX_IDLE (-1)
-
-#define TX_ERR_BUSY -1
-#define TX_ERR_UNINITIALIZED -2
-
-extern volatile uint32_t tx_overflow_cnt;
-
-void tx_init(uint8_t *tx_buf);
-int tx_transmit(size_t len);
-int tx_next_bit(void);
-
-#endif /* __TRANSMIT_H__ */