summaryrefslogtreecommitdiff
path: root/olsndot/firmware/main.c
diff options
context:
space:
mode:
Diffstat (limited to 'olsndot/firmware/main.c')
-rw-r--r--olsndot/firmware/main.c387
1 files changed, 240 insertions, 147 deletions
diff --git a/olsndot/firmware/main.c b/olsndot/firmware/main.c
index 5d6c2be..a7cbbef 100644
--- a/olsndot/firmware/main.c
+++ b/olsndot/firmware/main.c
@@ -1,82 +1,83 @@
+/* OpenStep 2
+ * Copyright (C) 2017 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 Affero 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 Affero General Public License for more details.
+ *
+ * You should have received a copy of the GNU Affero General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ */
+
+/* Preliminary remarks.
+ *
+ * This code is intended to run on an ARM Cortex-M0 microcontroller made by ST, part number STM32F030F4C6
+ *
+ * Some terminology:
+ *
+ * * The term "raw channel" refers to a single output of the 32 outputs provided by the driver board. It corresponds to
+ * a single color sub-channel of one RGBW output. One RGBW output consists of four raw channels.
+ *
+ * * The term "logical channel" refers to one RGBW output of four individual colors handled by a group of four raw
+ * channels.
+ */
#include <stm32f0xx.h>
#include <stdint.h>
#include <system_stm32f0xx.h>
#include <stm32f0xx_ll_utils.h>
#include <math.h>
-/*
- * Part number: STM32F030F4C6
+
+/* Bit count of this device. Note that to change this you will also have to adapt the per-bit timer period lookup table
+ * below.
*/
+#define NBITS 14
-#define NBITS 12
-void do_transpose(void);
-uint32_t brightness[32];
-uint32_t sys_time = 0;
-uint32_t sys_time_seconds = 0;
-volatile uint32_t brightness_by_bit[NBITS];
+/* Maximum bit count supported by serial command protocol. The brightness data is assumed to be of this bit width, but
+ * only the uppermost NBITS bits are used. */
+#define MAX_BITS 16
-unsigned int stk_start(void) {
- return SysTick->VAL;
-}
+void do_transpose(void);
-unsigned int stk_end(unsigned int start) {
- return (start - SysTick->VAL) & 0xffffff;
-}
+/* Right-aligned integer raw channel brightness values like so:
+ *
+ * bit index 31 ... 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
+ * | (MSB) serial data put *here* (LSB) |
+ * |<-utterly ignored->| |<-----------------MAX_BITS------------------>|
+ * |<----------------NBITS---------------->| |<>|--ignored
+ * | (MSB) brightness data (LSB) | |<>|--ignored
+ */
+uint32_t brightness[32] = { 0 };
-unsigned int stk_microseconds(void) {
- return sys_time*1000 + (1000 - (SysTick->VAL / (SystemCoreClock/1000000)));
-}
+/* Bit-golfed modulation data generated from the above values by the main loop, ready to be sent out to the shift
+ * registers.
+ */
+volatile uint32_t brightness_by_bit[NBITS] = { 0 };
-void hsv_set(int idx, int hue, int white) {
- int i = hue>>NBITS;
- int j = hue & (~(-1<<NBITS));
- int r=0, g=0, b=0;
- switch (i) {
- case 0:
- r = (1<<NBITS)-1;
- g = 0;
- b = j;
- break;
- case 1:
- r = (1<<NBITS)-1-j;
- g = 0;
- b = (1<<NBITS)-1;
- break;
- case 2:
- r = 0;
- g = j;
- b = (1<<NBITS)-1;
- break;
- case 3:
- r = 0;
- g = (1<<NBITS)-1;
- b = (1<<NBITS)-1-j;
- break;
- case 4:
- r = j;
- g = (1<<NBITS)-1;
- b = 0;
- break;
- case 5:
- r = (1<<NBITS)-1;
- g = (1<<NBITS)-1-j;
- b = 0;
- break;
- }
- brightness[idx*4 + 0] = white;
- brightness[idx*4 + 1] = r;
- brightness[idx*4 + 2] = g;
- brightness[idx*4 + 3] = b;
-}
+/* Global systick timing variables */
+uint32_t sys_time = 0;
+uint32_t sys_time_seconds = 0;
-int hue;
int main(void) {
+ /* Get all the good clocks and PLLs on this thing up and running. We're running from an external 16MHz crystal,
+ * which we're first dividing down by 2 to get 8MHz, then PLL'ing up by 4 to get 32MHz as our main system clock.
+ *
+ * The busses are all run directly from these 32MHz because why not.
+ *
+ * Be careful in mucking around with this code since you can kind of semi-brick the chip if you do it wrong.
+ */
RCC->CR |= RCC_CR_HSEON;
while (!(RCC->CR&RCC_CR_HSERDY));
RCC->CFGR &= ~RCC_CFGR_PLLMUL_Msk & ~RCC_CFGR_SW_Msk & ~RCC_CFGR_PPRE_Msk & ~RCC_CFGR_HPRE_Msk;
- RCC->CFGR |= (2<<RCC_CFGR_PLLMUL_Pos) | RCC_CFGR_PLLSRC_HSE_PREDIV; /* PLL x4 -> 50.0MHz */
+ RCC->CFGR |= (2<<RCC_CFGR_PLLMUL_Pos) | RCC_CFGR_PLLSRC_HSE_PREDIV; /* PLL x4 -> 32.0MHz */
RCC->CFGR2 &= ~RCC_CFGR2_PREDIV_Msk;
- RCC->CFGR2 |= RCC_CFGR2_PREDIV_DIV2; /* prediv :2 -> 12.5MHz */
+ RCC->CFGR2 |= RCC_CFGR2_PREDIV_DIV2; /* prediv :2 -> 8.0MHz */
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR&RCC_CR_PLLRDY));
RCC->CFGR |= (2<<RCC_CFGR_SW_Pos);
@@ -84,10 +85,12 @@ int main(void) {
SysTick_Config(SystemCoreClock/1000); /* 1ms interval */
+ /* Enable all the periphery we need */
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN | RCC_APB2ENR_TIM1EN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_ADCEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
+ /* Configure all the GPIOs */
GPIOA->MODER |=
(3<<GPIO_MODER_MODER0_Pos) /* PA0 - Current measurement analog input */
| (1<<GPIO_MODER_MODER1_Pos) /* PA1 - RS485 TX enable */
@@ -114,6 +117,7 @@ int main(void) {
GPIOB->OSPEEDR |=
(3<<GPIO_OSPEEDR_OSPEEDR1_Pos); /* Clear */
+ /* Alternate function settings */
GPIOA->AFR[0] |=
(1<<GPIO_AFRL_AFRL2_Pos) /* USART1_TX */
| (1<<GPIO_AFRL_AFRL3_Pos) /* USART1_RX */
@@ -125,35 +129,42 @@ int main(void) {
(2<<GPIO_AFRL_AFRL1_Pos); /* TIM1_CH3N */
/* Configure SPI controller */
- /* CPOL=0, CPHA=0, prescaler=8 -> 1MBd */
+ /* CPOL=0, CPHA=0, prescaler=2 -> 16MBd */
SPI1->CR1 = SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE | SPI_CR1_SSM | SPI_CR1_SSI | SPI_CR1_SPE | (0<<SPI_CR1_BR_Pos) | SPI_CR1_MSTR;
SPI1->CR2 = (0xf<<SPI_CR2_DS_Pos);
/* Configure TIM1 for display strobe generation */
- TIM1->CR1 = TIM_CR1_ARPE; // | TIM_CR1_OPM; // | TIM_CR1_URS;
+ TIM1->CR1 = TIM_CR1_ARPE;
- TIM1->PSC = 1; // debug
+ TIM1->PSC = 1; /* Prescale by 2, resulting in a 16MHz timer frequency and 62.5ns timer step size. */
/* CH2 - clear/!MR, CH3 - strobe/STCP */
- TIM1->CCMR2 = (6<<TIM_CCMR2_OC3M_Pos); // | TIM_CCMR2_OC3PE;
+ TIM1->CCMR2 = (6<<TIM_CCMR2_OC3M_Pos) | TIM_CCMR2_OC3PE;
TIM1->CCER |= TIM_CCER_CC3E | TIM_CCER_CC3NE | TIM_CCER_CC3P | TIM_CCER_CC3NP;
- TIM1->BDTR = TIM_BDTR_MOE | (8<<TIM_BDTR_DTG_Pos); /* 1us dead time */
- TIM1->DIER = TIM_DIER_UIE;
+ TIM1->BDTR = TIM_BDTR_MOE | (1<<TIM_BDTR_DTG_Pos); /* really short dead time */
+ TIM1->DIER = TIM_DIER_UIE; /* Enable update (overrun) interrupt */
TIM1->ARR = 1;
TIM1->CR1 |= TIM_CR1_CEN;
+ /* Configure Timer 1 update (overrun) interrupt on NVIC.
+ * Used only for update (overrun) for strobe timing. */
NVIC_EnableIRQ(TIM1_BRK_UP_TRG_COM_IRQn);
NVIC_SetPriority(TIM1_BRK_UP_TRG_COM_IRQn, 2);
+ /* Pre-load initial values, kick of first interrupt */
TIM1->EGR |= TIM_EGR_UG;
+ /* Configure TIM3 for USART timeout handing */
TIM3->CR1 = TIM_CR1_OPM;
TIM3->DIER = TIM_DIER_UIE;
TIM3->PSC = 31;
TIM3->ARR = 1000;
+ /* Configure Timer 3 update (overrun) interrupt on NVIC.
+ * Used only for update (overrun) for USART timeout handling. */
NVIC_EnableIRQ(TIM3_IRQn);
NVIC_SetPriority(TIM3_IRQn, 2);
+ /* Pre-load initial values */
TIM3->EGR |= TIM_EGR_UG;
/* Configure UART for RS485 comm */
@@ -169,47 +180,34 @@ int main(void) {
/* other interrupts clear */
| USART_CR1_TE
| USART_CR1_RE;
- //USART1->CR2 = USART_CR2_RTOEN; /* Timeout enable */
USART1->CR3 = USART_CR3_DEM; /* RS485 DE enable (output on RTS) */
USART1->BRR = 32;
USART1->CR1 |= USART_CR1_UE;
- //NVIC_EnableIRQ(USART1_IRQn);
+ /* Configure USART1 interrupt on NVIC. Used only for RX. */
+ NVIC_EnableIRQ(USART1_IRQn);
NVIC_SetPriority(USART1_IRQn, 2);
+ /* Idly loop around, occassionally disfiguring some integers. */
while (42) {
-#define HUE_MAX ((1<<NBITS)*6)
-#define HUE_OFFX 0.15F /* 0-1 */
-#define HUE_AMPLITUDE 0.05F /* 0-1 */
-#define CHANNEL_SPACING 1.5F /* in radians */
-#define WHITE 0.2F /* 0-1 */
- for (float v=0; v<8*M_PI; v += 0.01F) {
- GPIOA->ODR ^= GPIO_ODR_6;
- /* generate hsv fade */
- for (int ch=0; ch<8; ch++) {
- hue = HUE_MAX * (HUE_OFFX + HUE_AMPLITUDE*sinf(v + ch*CHANNEL_SPACING));
- hue %= HUE_MAX;
- //hsv_set(ch, hue, WHITE*(1<<NBITS));
- brightness[ch*4+0] = 128;
- brightness[ch*4+1] = 0;
- brightness[ch*4+2] = 128;
- brightness[ch*4+3] = 0;
- }
- do_transpose();
- for (int k=0; k<10000; k++) {
- asm volatile("nop");
- }
- }
+ /* Debug output on LED. */
+ GPIOA->ODR ^= GPIO_ODR_6;
+
+ /* Bit-mangle the integer brightness data to produce raw modulation data */
+ do_transpose();
+
+ /* Wait a moment */
+ for (int k=0; k<10000; k++)
+ asm volatile("nop");
}
}
-uint32_t brightness[32] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
-volatile uint32_t brightness_by_bit[NBITS] = { 0 };
-
+/* Modulation data bit golfing routine */
void do_transpose(void) {
+ /* For each bit value */
for (uint32_t i=0; i<NBITS; i++) {
- uint32_t bv = 0;
- uint32_t mask = 1<<i<<(16-NBITS);
+ uint32_t mask = 1<<i<<(MAX_BITS-NBITS); /* Bit mask for this bit value. */
+ uint32_t bv = 0; /* accumulator thing */
for (uint32_t j=0; j<32; j++) {
if (brightness[j] & mask)
bv |= 1<<j;
@@ -218,45 +216,115 @@ void do_transpose(void) {
}
}
+/* Bit timing base value. This is the lowes bit interval used */
+#define PERIOD_BASE 4
+
+/* This value is a constant offset added to every bit period to allow for the timer IRQ handler to execute. This is set
+ * empirically using a debugger and a logic analyzer. */
+#define TIMER_CYCLES_FOR_SPI_TRANSMISSIONS 120
+/* This is the same as above, but for the reset cycle of the bit period. */
+#define RESET_PERIOD_LENGTH 40
+
+/* Defines for brevity */
+#define A TIMER_CYCLES_FOR_SPI_TRANSMISSIONS
+#define B PERIOD_BASE
+
+/* This is a constant offset containing some empirically determined correction values */
+#define C (1 /* reset pulse comp */ - 3 /* analog snafu comp */)
+
+/* This lookup table maps bit positions to timer period values. This is a lookup table to allow for the compensation for
+ * non-linear effects of ringing at lower bit durations.
+ */
+static uint16_t timer_period_lookup[NBITS] = {
+ /* LSB here */
+ A - C + (B<< 0),
+ A - C + (B<< 1),
+ A - C + (B<< 2),
+ A - C + (B<< 3),
+ A - C + (B<< 4),
+ A - C + (B<< 5),
+ A - C + (B<< 6),
+ A - C + (B<< 7),
+ A - C + (B<< 8),
+ A - C + (B<< 9),
+ A - C + (B<<10),
+ A - C + (B<<11),
+ A - C + (B<<12),
+ A - C + (B<<13),
+ /* MSB here */
+};
+
+/* Don't pollute the global namespace */
+#undef A
+#undef B
+#undef C
+
+/* Timer 1 main IRQ handler. This is used only for overflow ("update" or UP event in ST's terminology). */
void TIM1_BRK_UP_TRG_COM_IRQHandler(void) {
/* The index of the currently active bit. On entry of this function, this is the bit index of the upcoming period.
* On exit it is the index of the *next* period. */
- static uint32_t idx = 0;
-
- /* Access bits offset by one as we are setting the *next* period based on idx below. */
- uint32_t val = brightness_by_bit[idx];
-
- idx++;
- if (idx >= NBITS)
- idx = 0;
-
- GPIOA->ODR ^= GPIO_ODR_6; /* LED1 */
-
- /* Shift out the current period's data. The shift register clear and strobe lines are handled by the timers
- * capture/compare channel 3 complementary outputs. The dead-time generator is used to sequence the clear and strobe
- * edges one after another. Since there may be small variations in IRQ service latency it is critical to allow for
- * some leeway between the end of this data transmission and strobe and clear. */
- SPI1->DR = (val&0xffff);
- while (SPI1->SR & SPI_SR_BSY);
- SPI1->DR = (val>>16);
- while (SPI1->SR & SPI_SR_BSY);
-
- /* Set up everything for the *next* period. The timer is set to count from 0 to ARR. ARR and CCR3 are pre-loaded, so
- * the values written above will only be latched on timer overrun at the end of this period. This is a little
- * complicated, but doing it this way has the advantage of keeping both duty cycle and frame rate precisely
- * constant. */
- const int period_base = 4; /* 1us */
- const int period = (period_base<<idx) + 4 /* 1us dead time */;
- const int timer_cycles_for_spi_transmissions = 128;
- TIM1->ARR = period + timer_cycles_for_spi_transmissions;
- TIM1->CCR3 = timer_cycles_for_spi_transmissions;
+ static int idx = 0;
+ /* We modulate all outputs simultaneously in n periods, with n being the modulation depth (the number of bits).
+ * Each period is split into two timer cycles. First, a long one during which the data for the current period is
+ * shifted out and subsequently latched to the outputs. Then, a short one that is used to reset all outputs in time
+ * for the next period.
+ *
+ * bit value: | <-- least significant, shortest period / most significant, longest period --> |
+ * bit number: | b0 | b1 | ... | b10 | b11 |
+ * name: | data cycle | reset cycle | | | | |
+ * function: | shift data <strobe> wait | | ... | ... | ... | ... |
+ * duration: | fixed variable | fixed | | | | |
+ *
+ * Now, alternate between the two cycles in one phase.
+ */
+ static int clear = 0;
+ if ((clear = !clear)) {
+ /* Access bits offset by one as we are setting the *next* period based on idx below. */
+ uint32_t val = brightness_by_bit[idx];
+
+ /* Shift out the current period's data. The shift register clear and strobe lines are handled by the timers
+ * capture/compare channel 3 complementary outputs. The dead-time generator is used to sequence the clear and strobe
+ * edges one after another. Since there may be small variations in IRQ service latency it is critical to allow for
+ * some leeway between the end of this data transmission and strobe and clear. */
+ SPI1->DR = (val&0xffff);
+ while (SPI1->SR & SPI_SR_BSY);
+ SPI1->DR = (val>>16);
+ while (SPI1->SR & SPI_SR_BSY);
+
+ /* Increment the bit index for the next cycle */
+ idx++;
+ if (idx >= NBITS)
+ idx = 0;
+
+ /* Set up the following reset pulse cycle. This cycle is short as it only needs to be long enough for the below
+ * part of this ISR handler routine to run. */
+ TIM1->ARR = RESET_PERIOD_LENGTH;
+ TIM1->CCR3 = 1; /* This value is fixed to produce a very short reset pulse. IOs, PCB and shift registers all can
+ easily handle this. */
+ } else {
+ /* Set up everything for the data cycle of the *next* period. The timer is set to count from 0 to ARR. ARR and
+ * CCR3 are pre-loaded, so the values written above will only be latched on timer overrun at the end of this
+ * period. This is a little complicated, but doing it this way has the advantage of keeping both duty cycle and
+ * frame rate precisely constant. */
+ TIM1->CCR3 = TIMER_CYCLES_FOR_SPI_TRANSMISSIONS;
+ TIM1->ARR = timer_period_lookup[idx];
+ }
+ /* Reset the update interrupt flag. This ISR handler routine is only used for timer update events. */
TIM1->SR &= ~TIM_SR_UIF_Msk;
}
+/* The data format of the serial command interface.
+ *
+ * The serial interface uses short packets. Currently, there is only one packet type defined: a "set RGBW" packet, using
+ * command ID 0x23. The packet starts with the command ID, followed by the addressed channel group, followed by four
+ * times two bytes of big-endian RGBW channel data.
+ *
+ *
+ */
union packet {
struct {
uint8_t cmd; /* 0x23 */
- uint8_t step; /* 0-12, numbered from bottom */
+ uint8_t step; /* logical channel. The USART_CHANNEL_OFFX is applied on this number below. */
union {
uint16_t rgbw[4];
struct {
@@ -276,9 +344,33 @@ void TIM3_IRQHandler(void) {
rxpos = 0;
}
-#define USART_OFFX 8
+/* This macro defines the lowest channel number of this board on the serial command bus. On a shared bus with several
+ * boards, you would generally assign increasing USART_CHANNEL_OFFX values to each one (0, 8, 16, 24, ...).
+ *
+ * Example: Let USART_CHANNEL_OFFX be 8.
+ *
+ * /--Command channel number received in command packet (packet.set_step.step)
+ * | /--USART_OFFX
+ * | | /--4 raw channels per logical channel (step): R, G, B, W
+ * | | | /--Raw channel offset for R, G, B, W
+ * | | | | /--Resulting raw channels for R, G, B, W data received in command packet
+ * | | | | |
+ * v v v v v
+ *
+ * (8 - 8) * 4 + {0, 1, 2, 3} = {0, 1, 2, 3}
+ * (9 - 8) * 4 + {0, 1, 2, 3}
+ * (10 - 8) * 4 + {0, 1, 2, 3}
+ * (11 - 8) * 4 + {0, 1, 2, 3}
+ * (12 - 8) * 4 + {0, 1, 2, 3}
+ * (13 - 8) * 4 + {0, 1, 2, 3}
+ * (14 - 8) * 4 + {0, 1, 2, 3}
+ * (15 - 8) * 4 + {0, 1, 2, 3}
+ */
+#ifndef USART_CHANNEL_OFFX
+#define USART_CHANNEL_OFFX 8
+#endif//USART_CHANNEL_OFFX
+
#define NCHANNELS (sizeof(brightness)/sizeof(brightness[0]))
-int last_step = NCHANNELS/4;
void USART1_IRQHandler() {
static union packet rxbuf;
@@ -287,36 +379,34 @@ void USART1_IRQHandler() {
/* Overrun detected? */
if (isr & USART_ISR_ORE) {
USART1->ICR = USART_ICR_ORECF; /* Acknowledge overrun */
- //asm("bkpt"); FIXME
+ //asm("bkpt"); /* uncomment for debug */
return;
}
if (!(isr & USART_ISR_RXNE)) {
- //asm("bkpt"); FIXME
+ //asm("bkpt"); /* uncomment for debug */
return;
}
+ /* Store received data */
uint8_t data = USART1->RDR;
rxbuf.data[rxpos] = data;
rxpos++;
+ /* If we finished receiving a packet, deal with it. */
if (rxpos == sizeof(union packet)) {
+ /* Check packet header */
if (rxbuf.set_step.cmd == 0x23 &&
- rxbuf.set_step.step >= USART_OFFX &&
- rxbuf.set_step.step < USART_OFFX+NCHANNELS) {
- if (rxbuf.set_step.step != last_step+1)
- if (last_step != USART_OFFX+(NCHANNELS/4)-1 && rxbuf.set_step.step != 0) {
- //asm("bkpt");
- }
- last_step = rxbuf.set_step.step;
-
- /*
- if (rxbuf.set_step.step == 8 && last_step != 15)
- asm("bkpt");
- */
-
- uint32_t *out = &brightness[(rxbuf.set_step.step - USART_OFFX)*4];
- /* (matti) (treppe)
+ /* bounds-check received channel number. This allows several driver boards to share one common serial bus */
+ rxbuf.set_step.step >= USART_CHANNEL_OFFX &&
+ rxbuf.set_step.step < USART_CHANNEL_OFFX+NCHANNELS) {
+
+ /* Calculate raw channel brightness value base address for logical channel */
+ uint32_t *out = &brightness[(rxbuf.set_step.step - USART_CHANNEL_OFFX)*4];
+
+ /* Correct RGBW raw channel ordering per logical channel according to SUB-D pinout used.
+ *
+ * (matti) (treppe)
* weiß blau
* rot weiß
* grün rot
@@ -327,13 +417,16 @@ void USART1_IRQHandler() {
out[3] = rxbuf.set_step.rgbw[2];
out[0] = rxbuf.set_step.rgbw[3];
}
+ /* Reset receive data counter */
rxpos = 0;
}
+ /* Reset usart timeout handler */
TIM3->CNT = 0;
TIM3->CR1 |= TIM_CR1_CEN;
}
+/* Misc IRQ handlers */
void NMI_Handler(void) {
}
@@ -357,9 +450,9 @@ void SysTick_Handler(void) {
}
}
-/* FIXME */
+/* Misc stuff for nostdlib linking */
void _exit(int status) { while (23); }
void *__bss_start__;
void *__bss_end__;
-
int __errno;
+