diff options
Diffstat (limited to 'firmware')
-rw-r--r-- | firmware/.gitignore | 13 | ||||
-rw-r--r-- | firmware/Makefile | 61 | ||||
-rw-r--r-- | firmware/adc.c | 101 | ||||
-rw-r--r-- | firmware/adc.h | 30 | ||||
-rw-r--r-- | firmware/global.h | 35 | ||||
-rw-r--r-- | firmware/main.c | 333 | ||||
-rw-r--r-- | firmware/openocd.cfg | 12 | ||||
-rw-r--r-- | firmware/openocd_jaseg.cfg | 10 | ||||
-rw-r--r-- | firmware/serial.c | 212 | ||||
-rw-r--r-- | firmware/serial.h | 74 | ||||
-rw-r--r-- | firmware/startup_stm32f030x6.s | 273 | ||||
-rw-r--r-- | firmware/stm32_flash.ld | 127 | ||||
-rw-r--r-- | firmware/system_stm32f0xx.c | 336 |
13 files changed, 1617 insertions, 0 deletions
diff --git a/firmware/.gitignore b/firmware/.gitignore new file mode 100644 index 0000000..4c5ab8e --- /dev/null +++ b/firmware/.gitignore @@ -0,0 +1,13 @@ +*.elf +*.o +*.map +*.lst +*.hex +*.bin + +cmsis_exports.c +sources.c +sources.tar.xz +sources.tar.xz.zip + +STM32Cube* diff --git a/firmware/Makefile b/firmware/Makefile new file mode 100644 index 0000000..be1709b --- /dev/null +++ b/firmware/Makefile @@ -0,0 +1,61 @@ +# put your *.o targets here, make should handle the rest! +CMSIS_PATH ?= STM32Cube/Drivers/CMSIS +CMSIS_DEV_PATH ?= $(CMSIS_PATH)/Device/ST/STM32F0xx +HAL_PATH ?= STM32Cube/Drivers/STM32F0xx_HAL_Driver + +MAC_ADDR ?= 0xDEBE10BB + +CC := arm-none-eabi-gcc +OBJCOPY := arm-none-eabi-objcopy +OBJDUMP := arm-none-eabi-objdump +SIZE := arm-none-eabi-size + +#CFLAGS = -Wall -Wpedantic -Wstrict-aliasing -g -std=gnu11 -Os +CFLAGS = -Wall -Wpedantic -Wstrict-aliasing -g -std=gnu11 -O1 +CFLAGS += -mlittle-endian -mcpu=cortex-m0 -march=armv6-m -mthumb +CFLAGS += -ffunction-sections -fdata-sections -Wl,--gc-sections +CFLAGS += -Wl,-Map=main.map + +# Technically we're using an STM32F030F4, but apart from the TSSOP20 package that one is largely identical to the +# STM32F030*6 and there is no separate device header provided for it, so we're faking a *6 device here. This is +# even documented in stm32f0xx.h. Thanks ST! +CFLAGS += -DSTM32F030x6 -DHSE_VALUE=25000000 -DMAC_ADDR=$(MAC_ADDR) + +CFLAGS += -Tstm32_flash.ld +CFLAGS += -I$(CMSIS_DEV_PATH)/Include -I$(CMSIS_PATH)/Include -I$(HAL_PATH)/Inc -Iconfig +CFLAGS += -L$(CMSIS_PATH)/Lib/GCC -larm_cortexM0l_math + +################################################### + +.PHONY: program clean + +all: main.elf + +cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f030x6.h $(CMSIS_PATH)/Include/core_cm0.h + python3 gen_cmsis_exports.py $^ > $@ + +sources.tar.xz: main.c serial.h global.h serial.c adc.h adc.c Makefile + tar -cf $@ $^ + +# don't ask... +sources.tar.xz.zip: sources.tar.xz + zip $@ $^ + +sources.c: sources.tar.xz.zip + xxd -i $< | head -n -1 | sed 's/=/__attribute__((section(".source_tarball"))) =/' > $@ + +main.elf: main.c adc.c serial.c startup_stm32f030x6.s system_stm32f0xx.c $(HAL_PATH)/Src/stm32f0xx_ll_utils.c cmsis_exports.c sources.c + $(CC) $(CFLAGS) -o $@ $^ + $(OBJCOPY) -O ihex $@ $(@:.elf=.hex) + $(OBJCOPY) -O binary $@ $(@:.elf=.bin) + $(OBJDUMP) -St $@ >$(@:.elf=.lst) + $(SIZE) $@ + +program: main.elf openocd.cfg + openocd -f openocd.cfg -c "program $< verify reset exit" + +clean: + rm -f *.o + rm -f main.elf main.hex main.bin main.map main.lst + rm -f sources.tar.xz sources.tar.xz.zip + diff --git a/firmware/adc.c b/firmware/adc.c new file mode 100644 index 0000000..02517a7 --- /dev/null +++ b/firmware/adc.c @@ -0,0 +1,101 @@ +/* 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 <stm32f0xx.h> +#include <stdint.h> +#include <system_stm32f0xx.h> +#include <stm32f0xx_ll_utils.h> +#include <math.h> + +#include "adc.h" + +volatile int16_t adc_vcc_mv = 0; +volatile int16_t adc_temp_celsius = 0; + +static volatile uint16_t adc_buf[2]; + +void adc_init(void) { + /* The ADC is used for temperature measurement. To compute the temperature from an ADC reading of the internal + * temperature sensor, the supply voltage must also be measured. Thus we are using two channels. + * + * The ADC is triggered by compare channel 4 of timer 1. The trigger is set to falling edge to trigger on compare + * match, not overflow. + */ + 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 the slowest available sample rate */ + ADC1->SMPR = (7<<ADC_SMPR_SMP_Pos); + /* Internal VCC and temperature sensor channels */ + ADC1->CHSELR = 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; + + /* 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 = sizeof(adc_buf)/sizeof(adc_buf[0]); + 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 + | DMA_CCR_TCIE; /* Enable transfer complete interrupt. */ + DMA1_Channel1->CCR |= DMA_CCR_EN; /* Enable channel */ + + /* triggered on transfer completion. We use this to process the ADC data */ + NVIC_EnableIRQ(DMA1_Channel1_IRQn); + NVIC_SetPriority(DMA1_Channel1_IRQn, 3); +} + +void DMA1_Channel1_IRQHandler(void) { + /* This interrupt takes either 1.2us or 13us. It can be pre-empted by the more timing-critical UART and LED timer + * interrupts. */ + static int count = 0; /* oversampling accumulator sample count */ + static uint32_t adc_aggregate[2] = {0, 0}; /* oversampling accumulator */ + + /* Clear the interrupt flag */ + DMA1->IFCR |= DMA_IFCR_CGIF1; + + adc_aggregate[0] += adc_buf[0]; + adc_aggregate[1] += adc_buf[1]; + + if (++count == (1<<ADC_OVERSAMPLING)) { + /* 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. + */ + adc_vcc_mv = (3300 * VREFINT_CAL)/(adc_aggregate[0]>>ADC_OVERSAMPLING); + int32_t temperature = (((uint32_t)TS_CAL1) - ((adc_aggregate[1]>>ADC_OVERSAMPLING) * adc_vcc_mv / 3300)) * 1000; + temperature = (temperature/5336) + 30; + adc_temp_celsius = temperature; + + count = 0; + adc_aggregate[0] = 0; + adc_aggregate[1] = 0; + } +} + diff --git a/firmware/adc.h b/firmware/adc.h new file mode 100644 index 0000000..57a2ce9 --- /dev/null +++ b/firmware/adc.h @@ -0,0 +1,30 @@ +/* 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" + +#define ADC_OVERSAMPLING 8 + +extern volatile int16_t adc_vcc_mv; +extern volatile int16_t adc_temp_celsius; + +void adc_init(void); + +#endif/*__ADC_H__*/ diff --git a/firmware/global.h b/firmware/global.h new file mode 100644 index 0000000..0098d38 --- /dev/null +++ b/firmware/global.h @@ -0,0 +1,35 @@ +#ifndef __GLOBAL_H__ +#define __GLOBAL_H__ + +#define COLOR_SPEC_WHITE 0x00 +#define COLOR_SPEC_SINGLE_COLOR 0x01 +#define COLOR_SPEC_RGB 0x02 +#define COLOR_SPEC_RGBW 0x03 +#define COLOR_SPEC_COLD_WARM_WHITE 0x04 +#define COLOR_SPEC_WWA 0x05 /* cold white/warm white/amber */ + +#define OLSNDOT_V1 0x01 + +#define FIRMWARE_VERSION 2 +#define HARDWARE_VERSION 2 + +/* 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 + +/* Bit count of this device. Note that to change this you will also have to adapt the per-bit timer period lookup table + * in main.c. */ +#define NBITS 14 + +#define NCHANNELS 8 +#define CHANNEL_SPEC 'H' +#define COLOR_SPEC COLOR_SPEC_RGBW +#define DEVICE_TYPE OLSNDOT_V1 + +#define TS_CAL1 (*(uint16_t *)0x1FFFF7B8) +#define VREFINT_CAL (*(uint16_t *)0x1FFFF7BA) + +extern uint32_t sys_time; +extern uint32_t sys_time_seconds; + +#endif/*__GLOBAL_H__*/ diff --git a/firmware/main.c b/firmware/main.c new file mode 100644 index 0000000..9391acd --- /dev/null +++ b/firmware/main.c @@ -0,0 +1,333 @@ +/* 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> + +#include "global.h" +#include "serial.h" +#include "adc.h" + +void do_transpose(void); + +/* 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 }; + +/* Global systick timing variables */ +uint32_t sys_time = 0; +uint32_t sys_time_seconds = 0; + +/* This value sets how long a batch of ADC conversions used for temperature measurement is started before the end of the + * longest cycle. Here too the above caveats apply. + * + * This value is in TIM1 timer counts. */ +#define ADC_PRETRIGGER 300 /* trigger with about 12us margin to TIM1 CC IRQ */ + +/* 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 240 + +/* This is the same as above, but for the reset cycle of the bit period. */ +#define RESET_PERIOD_LENGTH 80 + +/* Defines for brevity */ +#define A TIMER_CYCLES_FOR_SPI_TRANSMISSIONS +#define B 40 + +/* 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 + 1, + A + 3, + A + 9, + A + 29, + A + 71, + A + (B<< 2), + A + (B<< 3), + A + (B<< 4), + A + (B<< 5), + A + (B<< 6), + A + (B<< 7), + A + (B<< 8), + A + (B<< 9), + A + (B<<10), + /* MSB here */ +}; + +/* Don't pollute the global namespace */ +#undef A +#undef B +#undef C + +int main(void) { + /* Get all the good clocks and PLLs on this thing up and running. We're running from an external 25MHz crystal, + * which we're first dividing down by 5 to get 5 MHz, then PLL'ing up by 6 to get 30 MHz as our main system clock. + * + * The busses are all run directly from these 30 MHz 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)); + + // HSE ready, let's configure the PLL + RCC->CFGR &= ~RCC_CFGR_PLLMUL_Msk & ~RCC_CFGR_SW_Msk & ~RCC_CFGR_PPRE_Msk & ~RCC_CFGR_HPRE_Msk; + + // PLLMUL: 6x (0b0100) + RCC->CFGR |= (0b0100<<RCC_CFGR_PLLMUL_Pos) | RCC_CFGR_PLLSRC_HSE_PREDIV; + + // PREDIV: + // HSE / PREDIV = PLL SRC + RCC->CFGR2 &= ~RCC_CFGR2_PREDIV_Msk; + RCC->CFGR2 |= RCC_CFGR2_PREDIV_DIV5; /* prediv :10 -> 5 MHz */ + + RCC->CR |= RCC_CR_PLLON; + while (!(RCC->CR&RCC_CR_PLLRDY)); + + RCC->CFGR |= (2<<RCC_CFGR_SW_Pos); + + SystemCoreClockUpdate(); + SysTick_Config(SystemCoreClock/1000); /* 1ms interval */ + + + /* Enable all the periphery we need */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_DMAEN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN | RCC_APB2ENR_TIM1EN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_ADCEN; + + /* Configure all the GPIOs */ + GPIOA->MODER |= + (3<<GPIO_MODER_MODER0_Pos) /* PA0 - Current measurement analog input */ + | (2<<GPIO_MODER_MODER1_Pos) /* PA1 - RS485 TX enable */ + | (2<<GPIO_MODER_MODER2_Pos) /* PA2 - RS485 TX */ + | (2<<GPIO_MODER_MODER3_Pos) /* PA3 - RS485 RX */ + /* PA4 reserved because */ + | (2<<GPIO_MODER_MODER5_Pos) /* PA5 - Shift register clk/SCLK */ + | (1<<GPIO_MODER_MODER6_Pos) /* PA6 - LED2 open-drain output */ + | (2<<GPIO_MODER_MODER7_Pos) /* PA7 - Shift register data/MOSI */ + | (2<<GPIO_MODER_MODER9_Pos) /* PA9 - Shift register clear (TIM1_CH2) */ + | (2<<GPIO_MODER_MODER10_Pos);/* PA10 - Shift register strobe (TIM1_CH3) */ + + GPIOA->OTYPER |= GPIO_OTYPER_OT_6; /* LED outputs -> open drain */ + + /* Set shift register IO GPIO output speed */ + GPIOA->OSPEEDR |= + (3<<GPIO_OSPEEDR_OSPEEDR5_Pos) /* SCLK */ + | (3<<GPIO_OSPEEDR_OSPEEDR6_Pos) /* LED1 */ + | (3<<GPIO_OSPEEDR_OSPEEDR7_Pos) /* MOSI */ + | (3<<GPIO_OSPEEDR_OSPEEDR9_Pos) /* Clear */ + | (3<<GPIO_OSPEEDR_OSPEEDR10_Pos);/* Strobe */ + + /* Alternate function settings */ + GPIOA->AFR[0] |= + (1<<GPIO_AFRL_AFRL1_Pos) /* USART1_RTS (RS485 DE) */ + | (1<<GPIO_AFRL_AFRL2_Pos) /* USART1_TX */ + | (1<<GPIO_AFRL_AFRL3_Pos) /* USART1_RX */ + | (0<<GPIO_AFRL_AFRL5_Pos) /* SPI1_SCK */ + | (0<<GPIO_AFRL_AFRL7_Pos); /* SPI1_MOSI */ + GPIOA->AFR[1] |= + (2<<GPIO_AFRH_AFRH1_Pos) /* TIM1_CH2 */ + | (2<<GPIO_AFRH_AFRH2_Pos); /* TIM1_CH3 */ + + /* Configure SPI controller */ + /* 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; + + TIM1->PSC = 0; /* Do not prescale, resulting in a 30MHz timer frequency and 33.3ns timer step size. */ + /* CH2 - clear/!MR, CH3 - strobe/STCP */ + TIM1->CCMR1 = (6<<TIM_CCMR1_OC2M_Pos) | TIM_CCMR1_OC2PE; + TIM1->CCMR2 = (6<<TIM_CCMR2_OC3M_Pos) | TIM_CCMR2_OC3PE | (6<<TIM_CCMR2_OC4M_Pos); + TIM1->CCER |= TIM_CCER_CC3E | TIM_CCER_CC2E | TIM_CCER_CC3P | TIM_CCER_CC4E; + TIM1->BDTR = TIM_BDTR_MOE; + TIM1->DIER = TIM_DIER_UIE; /* Enable update (overrun) interrupt */ + TIM1->ARR = 1; + TIM1->CR1 |= TIM_CR1_CEN; + /* TIM1 CC channel 4 is used to trigger an ADC run at the end of the longest bit cycle. This is done by setting a + * value that is large enough to not trigger in shorter bit cycles. */ + TIM1->CCR4 = timer_period_lookup[NBITS-1] - ADC_PRETRIGGER; + + /* 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, 1); + + /* Pre-load initial values, kick of first interrupt */ + TIM1->EGR |= TIM_EGR_UG; + + /* Configure UART for RS485 comm */ + /* 8N1, 1MBd */ + USART1->CR1 = /* 8-bit -> M1, M0 clear */ + /* RTOIE clear */ + (8 << USART_CR1_DEAT_Pos) /* 8 sample cycles/1 bit DE assertion time */ + | (8 << USART_CR1_DEDT_Pos) /* 8 sample cycles/1 bit DE assertion time */ + /* CMIF clear */ + /* WAKE clear */ + /* PCE, PS clear */ + | USART_CR1_RXNEIE + /* other interrupts clear */ + | USART_CR1_TE + | USART_CR1_RE; + USART1->CR3 = USART_CR3_DEM; /* RS485 DE enable (output on RTS) */ + // USART1->BRR = 30; + //USART1->BRR = 40; // 750000 + USART1->BRR = 60; // 500000 + USART1->CR1 |= USART_CR1_UE; + + /* Configure USART1 interrupt on NVIC. Used only for RX. */ + NVIC_EnableIRQ(USART1_IRQn); + NVIC_SetPriority(USART1_IRQn, 2); + + adc_init(); + + /* Idly loop around, occassionally disfiguring some integers. */ + while (42) { + /* Debug output on LED. */ + GPIOA->ODR ^= GPIO_ODR_6; + + if (framebuf_out_of_sync != 0) { + /* This logic is very slightly racy, but that should not matter since we're updating the frame buffer often + * enough so you don't notice one miss every billion frames. */ + framebuf_out_of_sync = 0; + /* Bit-mangle the integer framebuf data to produce raw modulation data */ + do_transpose(); + } + } +} + +/* Modulation data bit golfing routine */ +void do_transpose(void) { + /* For each bit value */ + for (uint32_t i=0; i<NBITS; i++) { + 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<NCHANNELS; j++) + if (rx_buf.set_fb_rq.framebuf[j] & mask) + bv |= 1<<j; + brightness_by_bit[i] = bv; + } +} + +/* 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 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. */ +#if NCHANNELS > 16 + SPI1->DR = (val>>16); + while (SPI1->SR & SPI_SR_BSY); +#endif + SPI1->DR = (val&0xffff); + 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 = 2; /* This value is fixed to produce a very short reset pulse. IOs, PCB and shift registers all can + easily handle this. */ + TIM1->CCR2 = 3; + } 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->CCR2 = TIMER_CYCLES_FOR_SPI_TRANSMISSIONS+1; + 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; +} + +/* Misc IRQ handlers */ +void NMI_Handler(void) { +} + +void HardFault_Handler(void) { + for(;;); +} + +void SVC_Handler(void) { +} + + +void PendSV_Handler(void) { +} + +void SysTick_Handler(void) { + static int n = 0; + sys_time++; + if (n++ == 1000) { + n = 0; + sys_time_seconds++; + } +} + +/* Misc stuff for nostdlib linking */ +void _exit(int status) { while (23); } +void *__bss_start__; +void *__bss_end__; +int __errno; + diff --git a/firmware/openocd.cfg b/firmware/openocd.cfg new file mode 100644 index 0000000..fcbeb8d --- /dev/null +++ b/firmware/openocd.cfg @@ -0,0 +1,12 @@ +telnet_port 4444 +gdb_port 3333 + +interface jlink +#adapter_khz 10000 +transport select swd + +# source /usr/share/openocd/scripts/target/stm32f0x.cfg +# source [find interface/jlink.cfg] +source [find target/stm32f0x.cfg] + +#flash bank sysflash.alias stm32f0x 0x00000000 0 0 0 $_TARGETNAME diff --git a/firmware/openocd_jaseg.cfg b/firmware/openocd_jaseg.cfg new file mode 100644 index 0000000..2dc74f0 --- /dev/null +++ b/firmware/openocd_jaseg.cfg @@ -0,0 +1,10 @@ +telnet_port 4444 +gdb_port 3333 + +interface jlink +#adapter_khz 10000 +transport select swd + +source /usr/share/openocd/scripts/target/stm32f0x.cfg + +#flash bank sysflash.alias stm32f0x 0x00000000 0 0 0 $_TARGETNAME diff --git a/firmware/serial.c b/firmware/serial.c new file mode 100644 index 0000000..aaf7ca3 --- /dev/null +++ b/firmware/serial.c @@ -0,0 +1,212 @@ +/* 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 <stm32f0xx.h> +#include <stdint.h> +#include <system_stm32f0xx.h> +#include <stm32f0xx_ll_utils.h> +#include <math.h> + +#include "serial.h" +#include "adc.h" + +unsigned int uart_overruns = 0; +unsigned int frame_overruns = 0; +unsigned int invalid_frames = 0; + +static union tx_buf_union tx_buf; +volatile union rx_buf_union rx_buf; +volatile uint8_t framebuf_out_of_sync; + +void tx_char(uint8_t c) { + while (!(USART1->ISR & USART_ISR_TC)); + USART1->TDR = c; +} + +void send_frame_formatted(uint8_t *buf, int len) { + uint8_t *p=buf, *q=buf, *end=buf+len; + do { + while (*q && q!=end) + q++; + tx_char(q-p+1); + while (*p && p!=end) + tx_char(*p++); + p++, q++; + } while (p <= end); + tx_char('\0'); +} + +void send_status_reply(void) { + tx_buf.desc_reply.firmware_version = FIRMWARE_VERSION; + tx_buf.desc_reply.hardware_version = HARDWARE_VERSION; + tx_buf.desc_reply.nbits = NBITS; + tx_buf.desc_reply.channel_spec = CHANNEL_SPEC; + tx_buf.desc_reply.nchannels = NCHANNELS; + tx_buf.desc_reply.color_spec = COLOR_SPEC; + tx_buf.desc_reply.uptime_s = sys_time_seconds; + tx_buf.desc_reply.vcc_mv = adc_vcc_mv; + tx_buf.desc_reply.temp_celsius = adc_temp_celsius; + tx_buf.desc_reply.uart_overruns = uart_overruns; + tx_buf.desc_reply.frame_overruns = frame_overruns; + tx_buf.desc_reply.invalid_frames = invalid_frames; + send_frame_formatted(tx_buf.byte_data, sizeof(tx_buf.desc_reply)); +} + +/* This is the higher-level protocol handler for the serial protocol. It gets passed the number of data bytes in this + * frame (which may be zero) and returns a pointer to the buffer where the next frame should be stored. + */ +static volatile inline void packet_received(int len) { + static enum { + PROT_ADDRESSED = 0, + PROT_EXPECT_FRAME_SECOND_HALF = 1, + PROT_IGNORE = 2, + } protocol_state = PROT_IGNORE; + /* Use mac frames as delimiters to synchronize this protocol layer */ + if (len == 1 && rx_buf.byte_data[0] == 0x00) { /* Discovery packet */ + if (sys_time < 100 && sys_time_seconds == 0) { /* Only respond during the first 100ms after boot */ + tx_buf.device_type_reply.mac = MAC_ADDR; + tx_buf.device_type_reply.device_type = DEVICE_TYPE; + send_frame_formatted(tx_buf.byte_data, sizeof(tx_buf.device_type_reply)); + } + + } else if (len == 1) { /* Command packet */ + if (protocol_state == PROT_ADDRESSED) { + switch (rx_buf.byte_data[0]) { + case 0x01: + send_status_reply(); + break; + } + } else { + invalid_frames++; + } + protocol_state = PROT_IGNORE; + + } else if (len == 4) { /* Address packet */ + if (rx_buf.mac_data == MAC_ADDR) { /* we are addressed */ + protocol_state = PROT_ADDRESSED; /* start listening for frame buffer data */ + } else { /* we are not addressed */ + protocol_state = PROT_IGNORE; /* ignore packet */ + } + + } else if (len == sizeof(rx_buf.set_fb_rq)) { + if (protocol_state == PROT_ADDRESSED) { /* First of two half-framebuffer data frames */ + /* Kick off buffer transfer. This triggers the main loop to copy data out of the receive buffer and paste it + * properly formatted into the frame buffer. */ + if (framebuf_out_of_sync == 0) { + framebuf_out_of_sync = 1; + } else { + /* FIXME An overrun happend. What should we do? */ + frame_overruns++; + } + + /* Go to "hang mode" until next zero-length packet. */ + protocol_state = PROT_IGNORE; + } + + } else { + /* FIXME An invalid packet has been received. What should we do? */ + invalid_frames++; + protocol_state = PROT_IGNORE; /* go into "hang mode" until next zero-length packet */ + } +} + +void USART1_IRQHandler(void) { + /* Since a large amount of data will be shoved down this UART interface we need a more reliable and more efficient + * way of framing than just waiting between transmissions. + * + * This code uses "Consistent Overhead Byte Stuffing" (COBS). For details, see its Wikipedia page[0] or the proper + * scientific paper[1] published on it. Roughly, it works like this: + * + * * A frame is at most 254 bytes in length. + * * The null byte 0x00 acts as a frame delimiter. There is no null bytes inside frames. + * * Every frame starts with an "overhead" byte indicating the number of non-null payload bytes until the next null + * byte in the payload, **plus one**. This means this byte can never be zero. + * * Every null byte in the payload is replaced by *its* distance to *its* next null byte as above. + * + * This means, at any point the receiver can efficiently be synchronized on the next frame boundary by simply + * waiting for a null byte. After that, only a simple state machine is necessary to strip the overhead byte and a + * counter to then count skip intervals. + * + * Here is Wikipedia's table of example values: + * + * Unencoded data Encoded with COBS + * 00 01 01 00 + * 00 00 01 01 01 00 + * 11 22 00 33 03 11 22 02 33 00 + * 11 22 33 44 05 11 22 33 44 00 + * 11 00 00 00 02 11 01 01 01 00 + * 01 02 ...FE FF 01 02 ...FE 00 + * + * [0] https://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing + * [1] Cheshire, Stuart; Baker, Mary (1999). "Consistent Overhead Byte Stuffing" + * IEEE/ACM Transactions on Networking. doi:10.1109/90.769765 + * http://www.stuartcheshire.org/papers/COBSforToN.pdf + */ + + /* Index inside the current frame payload */ + static int rxpos = 0; + /* COBS state machine. This implementation might be a little too complicated, but it works well enough and I find it + * reasonably easy to understand. */ + static enum { + COBS_WAIT_SYNC = 0, /* Synchronize with frame */ + COBS_WAIT_START = 1, /* Await overhead byte */ + COBS_RUNNING = 2 /* Process payload */ + } cobs_state = 0; + /* COBS skip counter. During payload processing this contains the remaining non-null payload bytes */ + static int cobs_count = 0; + + if (USART1->ISR & USART_ISR_ORE) { /* Overrun handling */ + uart_overruns++; + /* Reset and re-synchronize. Retry next frame. */ + rxpos = 0; + cobs_state = COBS_WAIT_SYNC; + /* Clear interrupt flag */ + USART1->ICR = USART_ICR_ORECF; + + } else { /* Data received */ + uint8_t data = USART1->RDR; /* This automatically acknowledges the IRQ */ + + if (data == 0x00) { /* End-of-packet */ + if (cobs_state != COBS_WAIT_SYNC) /* Has a packet been received? */ + /* Process higher protocol layers on this packet. */ + packet_received(rxpos); + + /* Reset for next packet. */ + cobs_state = COBS_WAIT_START; + rxpos = 0; + + } else { /* non-null byte */ + if (cobs_state == COBS_WAIT_SYNC) { /* Wait for null byte */ + /* ignore data */ + + } else if (cobs_state == COBS_WAIT_START) { /* Overhead byte */ + cobs_count = data; + cobs_state = COBS_RUNNING; + + } else { /* Payload byte */ + if (--cobs_count == 0) { /* Skip byte */ + cobs_count = data; + data = 0; + } + + /* Write processed payload byte to current receive buffer */ + rx_buf.byte_data[rxpos++] = data; + } + } + } +} + diff --git a/firmware/serial.h b/firmware/serial.h new file mode 100644 index 0000000..96d0e70 --- /dev/null +++ b/firmware/serial.h @@ -0,0 +1,74 @@ +/* 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 __SERIAL_H__ +#define __SERIAL_H__ + +#include "global.h" + +/* High-level stuff */ +void serial_init(void); +void send_status_reply(void); + +/* Internal low-level stuff */ +void tx_char(uint8_t c); +void send_frame_formatted(uint8_t *buf, int len); + +/* Error counters for debugging */ +extern unsigned int uart_overruns; +extern unsigned int frame_overruns; +extern unsigned int invalid_frames; + +union tx_buf_union { + struct __attribute__((packed)) { + uint8_t firmware_version, + hardware_version; + uint8_t nbits; + uint8_t channel_spec; + uint8_t color_spec; + uint16_t nchannels; + uint32_t uptime_s, + uart_overruns, + frame_overruns, + invalid_frames; + int16_t vcc_mv, + temp_celsius; + } desc_reply; + struct __attribute__((packed)) { + uint32_t mac; + uint16_t device_type; + } device_type_reply; + uint8_t byte_data[0]; +}; + +union rx_buf_union { + /* 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 + */ + struct __attribute__((packed)) { uint16_t framebuf[NCHANNELS]; uint8_t end[0]; } set_fb_rq; + uint8_t byte_data[0]; + uint32_t mac_data; +}; +extern volatile union rx_buf_union rx_buf; +extern volatile uint8_t framebuf_out_of_sync; + +#endif/*__SERIAL_H__*/ diff --git a/firmware/startup_stm32f030x6.s b/firmware/startup_stm32f030x6.s new file mode 100644 index 0000000..ce81b76 --- /dev/null +++ b/firmware/startup_stm32f030x6.s @@ -0,0 +1,273 @@ +/** + ****************************************************************************** + * @file startup_stm32f030x6.s + * copied from: STM32Cube/Drivers/CMSIS/Device/ST/STM32F0xx/Source/Templates/gcc + * @author MCD Application Team + * @version V2.3.1 + * @date 04-November-2016 + * @brief STM32F030x4/STM32F030x6 devices vector table for Atollic TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M0 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m0 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =_estack + mov sp, r0 /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2] + adds r2, r2, #4 + + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + +LoopForever: + b LoopForever + + +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M0. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word 0 + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler /* Window WatchDog */ + .word 0 /* Reserved */ + .word RTC_IRQHandler /* RTC through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_1_IRQHandler /* EXTI Line 0 and 1 */ + .word EXTI2_3_IRQHandler /* EXTI Line 2 and 3 */ + .word EXTI4_15_IRQHandler /* EXTI Line 4 to 15 */ + .word 0 /* Reserved */ + .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */ + .word DMA1_Channel2_3_IRQHandler /* DMA1 Channel 2 and Channel 3 */ + .word DMA1_Channel4_5_IRQHandler /* DMA1 Channel 4 and Channel 5 */ + .word ADC1_IRQHandler /* ADC1 */ + .word TIM1_BRK_UP_TRG_COM_IRQHandler /* TIM1 Break, Update, Trigger and Commutation */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word 0 /* Reserved */ + .word TIM3_IRQHandler /* TIM3 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word TIM14_IRQHandler /* TIM14 */ + .word 0 /* Reserved */ + .word TIM16_IRQHandler /* TIM16 */ + .word TIM17_IRQHandler /* TIM17 */ + .word I2C1_IRQHandler /* I2C1 */ + .word 0 /* Reserved */ + .word SPI1_IRQHandler /* SPI1 */ + .word 0 /* Reserved */ + .word USART1_IRQHandler /* USART1 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_1_IRQHandler + .thumb_set EXTI0_1_IRQHandler,Default_Handler + + .weak EXTI2_3_IRQHandler + .thumb_set EXTI2_3_IRQHandler,Default_Handler + + .weak EXTI4_15_IRQHandler + .thumb_set EXTI4_15_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_3_IRQHandler + .thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_5_IRQHandler + .thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak TIM1_BRK_UP_TRG_COM_IRQHandler + .thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak TIM16_IRQHandler + .thumb_set TIM16_IRQHandler,Default_Handler + + .weak TIM17_IRQHandler + .thumb_set TIM17_IRQHandler,Default_Handler + + .weak I2C1_IRQHandler + .thumb_set I2C1_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/firmware/stm32_flash.ld b/firmware/stm32_flash.ld new file mode 100644 index 0000000..4a7f88a --- /dev/null +++ b/firmware/stm32_flash.ld @@ -0,0 +1,127 @@ + +ENTRY(Reset_Handler) + +MEMORY { + FLASH (rx): ORIGIN = 0x08000000, LENGTH = 16K + RAM (xrw): ORIGIN = 0x20000000, LENGTH = 4K +} + +/* highest address of the user mode stack */ +_estack = 0x20001000; + +SECTIONS { + /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ + .isr_vector : { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* the program code is stored in the .text section, which goes to Flash */ + .text : { + . = ALIGN(4); + + *(.text) /* normal code */ + *(.text.*) /* -ffunction-sections code */ + *(.rodata) /* read-only data (constants) */ + *(.rodata*) /* -fdata-sections read only data */ + *(.glue_7) /* TBD - needed ? */ + *(.glue_7t) /* TBD - needed ? */ + + *(.source_tarball) + + /* Necessary KEEP sections (see http://sourceware.org/ml/newlib/2005/msg00255.html) */ + KEEP (*(.init)) + KEEP (*(.fini)) + KEEP (*(.source_tarball)) + + . = ALIGN(4); + _etext = .; + /* This is used by the startup in order to initialize the .data section */ + _sidata = _etext; + } >FLASH + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : AT ( _sidata ) { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _sdata = . ; + _data = . ; + + *(.data) + *(.data.*) + *(.RAMtext) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _edata = . ; + } >RAM + + /* This is the uninitialized data section */ + .bss : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; + _bss = .; + + *(.bss) + *(.bss.*) /* patched by elias - allows the use of -fdata-sections */ + *(COMMON) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _ebss = . ; + } >RAM + + PROVIDE ( end = _ebss); + PROVIDE (_end = _ebss); + + __exidx_start = .; + __exidx_end = .; + + /* after that it's only debugging information. */ + + /* remove the debugging information from the standard libraries */ + /DISCARD/ : { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/firmware/system_stm32f0xx.c b/firmware/system_stm32f0xx.c new file mode 100644 index 0000000..c578424 --- /dev/null +++ b/firmware/system_stm32f0xx.c @@ -0,0 +1,336 @@ +/** + ****************************************************************************** + * @file system_stm32f0xx.c + * copied from: STM32Cube/Drivers/CMSIS/Device/ST/STM32F0xx/Source/Templates + * @author MCD Application Team + * @version V2.3.1 + * @date 04-November-2016 + * @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File. + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f0xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f0xx.s" file, to + * configure the system clock before to branch to main program. + * + * 3. This file configures the system clock as follows: + *============================================================================= + * Supported STM32F0xx device + *----------------------------------------------------------------------------- + * System Clock source | HSI + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 8000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 8000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 1 + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2> + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f0xx_system + * @{ + */ + +/** @addtogroup STM32F0xx_System_Private_Includes + * @{ + */ + +#include "stm32f0xx.h" + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Defines + * @{ + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSI_VALUE */ + +#if !defined (HSI48_VALUE) +#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSI48_VALUE */ +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Variables + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock there is no need to + call the 2 first functions listed above, since SystemCoreClock variable is + updated automatically. + */ +uint32_t SystemCoreClock = 8000000; + +const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system. + * Initialize the default HSI clock source, vector table location and the PLL configuration is reset. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001U; + +#if defined (STM32F051x8) || defined (STM32F058x8) + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE and MCOSEL[2:0] bits */ + RCC->CFGR &= (uint32_t)0xF8FFB80CU; +#else + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE, MCOSEL[2:0], MCOPRE[2:0] and PLLNODIV bits */ + RCC->CFGR &= (uint32_t)0x08FFB80CU; +#endif /* STM32F051x8 or STM32F058x8 */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFFU; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFFU; + + /* Reset PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + RCC->CFGR &= (uint32_t)0xFFC0FFFFU; + + /* Reset PREDIV[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0U; + +#if defined (STM32F072xB) || defined (STM32F078xx) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFCFE2CU; +#elif defined (STM32F071xB) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFCEACU; +#elif defined (STM32F091xC) || defined (STM32F098xx) + /* Reset USART3SW[1:0], USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFF0FEACU; +#elif defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6) || defined (STM32F038xx) || defined (STM32F030xC) + /* Reset USART1SW[1:0], I2C1SW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEECU; +#elif defined (STM32F051x8) || defined (STM32F058xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEACU; +#elif defined (STM32F042x6) || defined (STM32F048xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE2CU; +#elif defined (STM32F070x6) || defined (STM32F070xB) + /* Reset USART1SW[1:0], I2C1SW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE6CU; + /* Set default USB clock to PLLCLK, since there is no HSI48 */ + RCC->CFGR3 |= (uint32_t)0x00000080U; +#else + #warning "No target selected" +#endif + + /* Reset HSI14 bit */ + RCC->CR2 &= (uint32_t)0xFFFFFFFEU; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000U; + +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f0xx_hal.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f0xx_hal.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case RCC_CFGR_SWS_HSE: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case RCC_CFGR_SWS_PLL: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMUL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1; + + if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV) + { + /* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */ + SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull; + } +#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx) + else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV) + { + /* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */ + SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull; + } +#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */ + else + { +#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \ + || defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \ + || defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC) + /* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */ + SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull; +#else + /* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; +#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 || + STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || + STM32F091xC || STM32F098xx || STM32F030xC */ + } + break; + default: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + |