├── .gitignore ├── src ├── spi.h ├── clock.h ├── gpio.h ├── timer.h ├── decoder.h ├── bit_band.h ├── main.c ├── clock.c ├── spi.c ├── gpio.c ├── timer.c ├── decoder.c ├── STM32L476VGTx_FLASH.ld └── startup_stm32l476xx.s ├── .gitmodules ├── README └── Makefile /.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | compile_commands.json 3 | -------------------------------------------------------------------------------- /src/spi.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | void spi_init(); 4 | -------------------------------------------------------------------------------- /src/clock.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | void clock_init(); 4 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "STM32CubeL4"] 2 | path = STM32CubeL4 3 | url = https://github.com/STMicroelectronics/STM32CubeL4.git 4 | -------------------------------------------------------------------------------- /src/gpio.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | void gpio_init(); 4 | 5 | void gpio_set_leds(int red, int green); 6 | 7 | void gpio_debug(int set); 8 | -------------------------------------------------------------------------------- /src/timer.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | void timer_init(); 6 | 7 | void timer_disable_spi_clk(uint32_t n_spi_clks); 8 | -------------------------------------------------------------------------------- /src/decoder.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | #define FRAME_SIZE_BYTES 16 6 | 7 | void decoder_handle_frame(volatile uint8_t *frame); 8 | -------------------------------------------------------------------------------- /src/bit_band.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "stm32l4xx.h" 4 | 5 | // BB converts a memory mapped register to an array of its bits (one per word) 6 | // e.g. BB(SomeReg)[Bit_position] = 1 7 | #define BB(REG) ((volatile uint32_t*)(PERIPH_BB_BASE + ((uint32_t)® - PERIPH_BASE)*32U)) 8 | -------------------------------------------------------------------------------- /src/main.c: -------------------------------------------------------------------------------- 1 | #include "clock.h" 2 | #include "gpio.h" 3 | #include "timer.h" 4 | #include "spi.h" 5 | 6 | #include "stm32l476xx.h" 7 | 8 | int main() { 9 | clock_init(); 10 | gpio_init(); 11 | timer_init(); 12 | spi_init(); 13 | 14 | while(1) { 15 | } 16 | return 0; 17 | } 18 | -------------------------------------------------------------------------------- /README: -------------------------------------------------------------------------------- 1 | Soft S/PDIF decoder 2 | 3 | This is a software S/PDIF decoder for the STM32L476G-Discovery board. 4 | 5 | Wiring: 6 | 7 | - Connect the input signal to PA0 and PE13 8 | - Connect PA1 to PA5 9 | - Connect PA3 to PE15 10 | 11 | This was originally going to output the audio over the DAC but due to the 12 | available GPIO pins I abandoned that plan. The S/PDIF decoding works though. 13 | -------------------------------------------------------------------------------- /src/clock.c: -------------------------------------------------------------------------------- 1 | #include "stm32l476xx.h" 2 | #include "core_cm4.h" 3 | #include "clock.h" 4 | 5 | void clock_init() { 6 | // Assumes reset state, not safe to call except in reset state 7 | // Set flash to 4 wait states, with prefetch 8 | FLASH->ACR |= FLASH_ACR_LATENCY_4WS | FLASH_ACR_PRFTEN; 9 | 10 | // Turn on HSE clock and wait for it to be ready 11 | RCC->CR |= RCC_CR_HSEON; 12 | while (! (RCC->CR & RCC_CR_HSERDY)) {} 13 | 14 | // Configure, turn on, then wait for the PLL 15 | // M=1, N=20, P/Q are unused, R=2 16 | // Output should be 80MHz 17 | RCC->PLLCFGR = RCC_PLLCFGR_PLLSRC_HSE | (20 << RCC_PLLCFGR_PLLN_Pos); 18 | RCC->CR |= RCC_CR_PLLON; 19 | RCC->PLLCFGR |= RCC_PLLCFGR_PLLREN; 20 | while (!(RCC->CR & RCC_CR_PLLRDY)) {} 21 | 22 | RCC->CFGR |= RCC_CFGR_SW_PLL; 23 | } 24 | -------------------------------------------------------------------------------- /src/spi.c: -------------------------------------------------------------------------------- 1 | #include "stm32l476xx.h" 2 | 3 | #include "spi.h" 4 | #include "decoder.h" 5 | 6 | // each subframe is 64 wire bits, store two at a time 7 | static volatile uint8_t spi_buf[FRAME_SIZE_BYTES * 2]; 8 | 9 | #define SPI_CR2_DS_8BIT (SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2) 10 | 11 | void spi_init() { 12 | // enable the clock for SPI1 and DMA 13 | RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; 14 | RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; 15 | NVIC->ISER[0] = 1 << DMA1_Channel2_IRQn; 16 | 17 | // Turn on DMA 18 | DMA1_Channel2->CNDTR = sizeof(spi_buf); 19 | DMA1_Channel2->CPAR = (uint32_t)&(SPI1->DR); 20 | DMA1_Channel2->CMAR = (uint32_t)&spi_buf; 21 | DMA1_CSELR->CSELR |= 1 << DMA_CSELR_C2S_Pos; 22 | DMA1_Channel2->CCR = DMA_CCR_MINC | DMA_CCR_CIRC 23 | | DMA_CCR_TCIE | DMA_CCR_HTIE | DMA_CCR_TEIE | DMA_CCR_EN; 24 | 25 | // Turn on SPI 26 | SPI1->CR2 = SPI_CR2_DS_8BIT | SPI_CR2_RXDMAEN; 27 | SPI1->CR1 = SPI_CR1_RXONLY | SPI_CR1_CPHA | SPI_CR1_SSM | SPI_CR1_SPE; 28 | } 29 | 30 | void DMA1_Channel2_IRQHandler() { 31 | uint32_t isr = DMA1->ISR; 32 | DMA1->IFCR = 0xf0; 33 | if (isr & DMA_ISR_TEIF2) { 34 | while (1) {} // todo handle error 35 | } 36 | if ((isr & DMA_ISR_TCIF2) && (isr & DMA_ISR_HTIF2)) { 37 | while(1) {} // overrun 38 | } 39 | if (isr & DMA_ISR_HTIF2) { 40 | decoder_handle_frame(spi_buf); 41 | } 42 | if (isr & DMA_ISR_TCIF2) { 43 | decoder_handle_frame(spi_buf + sizeof(spi_buf) / 2); 44 | } 45 | } 46 | -------------------------------------------------------------------------------- /src/gpio.c: -------------------------------------------------------------------------------- 1 | #include "stm32l476xx.h" 2 | #include "gpio.h" 3 | 4 | #define MODE_INPUT 0 5 | #define MODE_OUTPUT 1 6 | #define MODE_AF 2 7 | #define MODE_ANALOG 3 8 | 9 | /* 10 | * Pin mappings 11 | * 12 | * PA0: Timer 8 external trigger (spdif in) 13 | * PA1: Timer 5 Channel 2 output (i2s mclk) 14 | * PA2: SAI 2 clock in (i2s mclk) 15 | * PA3: Timer 2 Channel 4 output (spi clk) 16 | * PA5: Timer 2 external trigger (i2s mclk) 17 | * 18 | * PB2: Red LED 19 | * 20 | * PE8: Green LED 21 | * PB10: Debug line 22 | * PE13: SPI CLK (wired to PA5) 23 | * PE15: SPI MOSI (spdif in) 24 | */ 25 | 26 | #define pinmode_mask(pin, mode) (~GPIO_MODER_MODE##pin##_Msk | (mode << GPIO_MODER_MODE##pin##_Pos)) 27 | 28 | void gpio_init() { 29 | RCC->AHB2ENR |= RCC_AHB2ENR_GPIOAEN | RCC_AHB2ENR_GPIOBEN | RCC_AHB2ENR_GPIOEEN; 30 | 31 | // GPIO A 32 | GPIOA->MODER &= pinmode_mask(0, MODE_AF) 33 | & pinmode_mask(1, MODE_AF) 34 | & pinmode_mask(3, MODE_AF) 35 | & pinmode_mask(5, MODE_AF); 36 | GPIOA->AFR[0] = 3 37 | | (2 << GPIO_AFRL_AFSEL1_Pos) 38 | | (1 << GPIO_AFRL_AFSEL3_Pos) 39 | | (2 << GPIO_AFRL_AFSEL5_Pos); 40 | // high speed PWM out 41 | GPIOA->OSPEEDR = 0x3 << GPIO_OSPEEDR_OSPEED1_Pos 42 | | 0x3 << GPIO_OSPEEDR_OSPEED3_Pos 43 | | 0x3 << GPIO_OSPEEDR_OSPEED5_Pos; 44 | 45 | GPIOB->MODER &= pinmode_mask(2, MODE_OUTPUT); 46 | GPIOB->OSPEEDR = 0x3 << GPIO_OSPEEDR_OSPEED2_Pos; 47 | 48 | // GPIO E (for SPI) 49 | GPIOE->MODER &= pinmode_mask(8, MODE_OUTPUT) 50 | & pinmode_mask(10, MODE_OUTPUT) 51 | & pinmode_mask(13, MODE_AF) 52 | & pinmode_mask(15, MODE_AF); 53 | GPIOE->AFR[1] = (5 << GPIO_AFRH_AFSEL13_Pos) 54 | | (5 << GPIO_AFRH_AFSEL15_Pos); 55 | GPIOE->OSPEEDR = 0x3 << GPIO_OSPEEDR_OSPEED10_Pos 56 | | 0x3 << GPIO_OSPEEDR_OSPEED8_Pos; 57 | } 58 | 59 | void gpio_set_leds(int red, int green) { 60 | GPIOB->BSRR = red ? GPIO_BSRR_BS2 : GPIO_BSRR_BR2; 61 | GPIOE->BSRR = green ? GPIO_BSRR_BS8 : GPIO_BSRR_BR8; 62 | } 63 | 64 | void gpio_debug(int set) { 65 | GPIOE->BSRR = set ? GPIO_BSRR_BS10 : GPIO_BSRR_BR10; 66 | } 67 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | NAME=soft-spdif 2 | -include $(DEPS) 3 | 4 | # Tools 5 | PREFIX = arm-none-eabi 6 | CC = $(PREFIX)-gcc 7 | AS = $(PREFIX)-as 8 | OBJCOPY = $(PREFIX)-objcopy 9 | GDB = $(PREFIX)-gdb 10 | 11 | # Directories 12 | CUBE = STM32CubeL4 13 | CMSIS = $(CUBE)/Drivers/CMSIS 14 | CMSIS_DEV=$(CMSIS)/Device/ST/STM32L4xx 15 | 16 | # Include path 17 | INC += -I$(CMSIS)/Include 18 | INC += -I$(CMSIS_DEV)/Include 19 | 20 | # Flags 21 | CFLAGS = -std=c17 -Wall -Wextra -g3 -gdwarf-2 -MMD -MP -O2 22 | CFLAGS += -mcpu=cortex-m4 -mthumb -DSTM32L476xx -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mtune=cortex-m4 -march=armv7e-m 23 | CFLAGS += -T $(LINKER_SCRIPT) --specs=nosys.specs 24 | LFLAGS = -lm 25 | 26 | # CFLAGS for just our sources 27 | EXTRA_CFLAGS = -pedantic -fanalyzer 28 | 29 | # Startup Files 30 | STARTUP_S = src/startup_stm32l476xx.s 31 | SYSTEM_C = $(CMSIS_DEV)/Source/Templates/system_stm32l4xx.c 32 | STARTUP_O = build/startup/$(notdir $(STARTUP_S:.s=.o)) 33 | SYSTEM_O = build/startup/$(notdir $(SYSTEM_C:.c=.o)) 34 | LINKER_SCRIPT = src/STM32L476VGTx_FLASH.ld 35 | 36 | # Our files 37 | SRCS = $(wildcard src/*.c) 38 | OBJS = $(addprefix build/,$(SRCS:.c=.o)) 39 | 40 | DEPS = $(OBJS:.o=.d) $(SYSTEM_O:.o=.d) 41 | # Recipes 42 | 43 | .PHONY: all 44 | all: build/$(NAME).bin 45 | 46 | .PHONY: clean 47 | clean: 48 | rm -f $(OBJS) \ 49 | $(STARTUP_O) \ 50 | $(SYSTEM_O) \ 51 | $(HAL_OBJS) \ 52 | $(BSP_OBS) \ 53 | $(DEPS) \ 54 | build/$(NAME).elf build/$(NAME).bin 55 | 56 | build/src/%.o: src/%.c #build/src 57 | mkdir -p $(@D) 58 | $(CC) -c $(INC) $(CFLAGS) $(EXTRA_CFLAGS) $< -o $@ 59 | 60 | $(STARTUP_O): $(STARTUP_S) #build/startup 61 | mkdir -p $(@D) 62 | $(AS) -c $(INC) $< -o $@ 63 | 64 | $(SYSTEM_O): $(SYSTEM_C) #build/startup 65 | mkdir -p $(@D) 66 | $(CC) -c $(INC) $(CFLAGS) $< -o $@ 67 | 68 | build/$(NAME).elf: $(OBJS) $(STARTUP_O) $(SYSTEM_O) 69 | $(CC) -o $@ $(CFLAGS) $^ $(LFLAGS) 70 | 71 | build/$(NAME).bin: build/$(NAME).elf 72 | $(OBJCOPY) -O binary $< $@ 73 | 74 | .PHONY: gdb 75 | gdb: build/$(NAME).elf 76 | $(GDB) -ex 'target ext :3333' build/$(NAME).elf 77 | 78 | .PHONY: flash 79 | flash: build/$(NAME).elf 80 | $(GDB) -ex 'target ext :3333' -ex 'load' build/$(NAME).elf 81 | -------------------------------------------------------------------------------- /src/timer.c: -------------------------------------------------------------------------------- 1 | #include "stm32l476xx.h" 2 | 3 | #include "timer.h" 4 | #include "bit_band.h" 5 | #include "gpio.h" 6 | 7 | #define TIM_SMCR_TS_EXTTRIG (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) 8 | #define TIM_SMCR_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) 9 | #define TIM_CCMR_OCM_PWM 0x6 10 | 11 | #define SPI_CLK_PERIOD 14 // 80MHz / (44.1kHz * 32bits/frame * 2frames * 2wire bits/real bit) 12 | #define MCLK_PERIOD (SPI_CLK_PERIOD/2) 13 | 14 | #define OPM_DELAY 10 // since the timers cant immedately compare 15 | 16 | // TIM8 is a dummy timer that just relays its TRGI to the mclk timer 17 | #define sync_timer TIM8 18 | 19 | // TIM5 is the i2s master clock, at 2x the freq of the spi clock (~11.2MHz) 20 | #define mclk_timer TIM5 21 | 22 | // TIM5 is the spi clock, using TIM4 as its SPI clock 23 | #define spi_timer TIM2 24 | 25 | // TIM4 is the bit synchronization timer, default on unless we need to shift the bits 26 | #define shift_timer TIM4 27 | 28 | void timer_init() { 29 | // Turn on clock for TIM1 and TIM8 30 | RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; 31 | RCC->APB1ENR1 |= RCC_APB1ENR1_TIM2EN | RCC_APB1ENR1_TIM5EN | RCC_APB1ENR1_TIM4EN; 32 | 33 | // sync timer 34 | // set output CH1 to PWM mode and enable it 35 | sync_timer->CCMR1 = TIM_CCMR_OCM_PWM << TIM_CCMR1_OC1M_Pos; 36 | sync_timer->CCER = TIM_CCER_CC1E; 37 | // set up period/duty cycle 38 | sync_timer->ARR = MCLK_PERIOD - 1; 39 | sync_timer->CCR1 = MCLK_PERIOD / 2; 40 | // Set CH1 as the TRGO 41 | sync_timer->CR2 = TIM_CR2_MMS_2; 42 | // Reset and trigger on external rising edges from spdif 43 | sync_timer->SMCR = TIM_SMCR_SMS_3 | TIM_SMCR_TS_EXTTRIG | TIM_SMCR_MSM; 44 | 45 | // mclk 46 | // set output CH2 to PWM mode and enable it 47 | mclk_timer->CCMR1 = TIM_CCMR_OCM_PWM << TIM_CCMR1_OC2M_Pos; 48 | mclk_timer->CCER = TIM_CCER_CC2E; 49 | // set the clock period and duty cycle 50 | mclk_timer->ARR = MCLK_PERIOD * 2; // doesn't really matter since it will be reset 51 | mclk_timer->CCR2 = MCLK_PERIOD / 2; 52 | // Reset and trigger on ITR3 (which is the sync timer) 53 | mclk_timer->SMCR = TIM_SMCR_SMS_3 | TIM_SMCR_TS_ITR3; 54 | 55 | // spi clk 56 | // set output CH4 to PWM mode 2 and enable it 57 | spi_timer->CCMR2 = (7 << TIM_CCMR2_OC4M_Pos); 58 | spi_timer->CCER = TIM_CCER_CC4E; 59 | // timings for dividing the input clock by 2 60 | spi_timer->CCR4 = 1; 61 | spi_timer->ARR = 1; 62 | // Use the TIM8 output as the external clock 63 | spi_timer->SMCR = TIM_SMCR_ECE // ext clk mode 2 (from mclk over hooked up to ETR (gpio PA5)) 64 | | TIM_SMCR_SMS_0 | TIM_SMCR_SMS_2 // gated mode (on shift timer) 65 | | TIM_SMCR_TS_ITR3; // TRGI is ITR3 (shift timer) 66 | spi_timer->CR1 = TIM_CR1_CEN; 67 | 68 | 69 | // shift 70 | // set output to CH1 and enable it 71 | shift_timer->CCMR1 = TIM_CCMR_OCM_PWM << TIM_CCMR1_OC1M_Pos; 72 | shift_timer->CCER = TIM_CCER_CC1E; 73 | // delay before disabling the clock 74 | shift_timer->CCR1 = OPM_DELAY; 75 | // set TRGO (which gates the spi clk timer) to be CH1 output 76 | shift_timer->CR2 = TIM_CR2_MMS_2; 77 | shift_timer->SMCR = TIM_SMCR_TS_ITR3 // TRGI is TIM8 update 78 | | TIM_SMCR_SMS_0 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_2; // clock on TRGI 79 | // turn on one pulse mode 80 | shift_timer->CR1 = TIM_CR1_OPM; 81 | } 82 | 83 | void timer_disable_spi_clk(uint32_t n_spi_clks) { 84 | // *2 since the input is from mclk not spi clk 85 | shift_timer->ARR = OPM_DELAY + (n_spi_clks * 2) - 1; 86 | BB(shift_timer->CR1)[TIM_CR1_CEN_Pos] = 1; 87 | } 88 | -------------------------------------------------------------------------------- /src/decoder.c: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "decoder.h" 4 | #include "timer.h" 5 | #include "gpio.h" 6 | 7 | #define B_MAGIC 0xE8 8 | #define M_MAGIC 0xE2 9 | #define W_MAGIC 0xE4 10 | #define IB_MAGIC ((uint8_t)~B_MAGIC) 11 | #define IM_MAGIC ((uint8_t)~M_MAGIC) 12 | #define IW_MAGIC ((uint8_t)~W_MAGIC) 13 | 14 | typedef enum DecoderState { 15 | UNSYNCED, 16 | SYNCING, 17 | SYNCED, 18 | } DecoderState; 19 | 20 | static DecoderState state = UNSYNCED; 21 | 22 | static void change_state(DecoderState new); 23 | static uint32_t rev(uint32_t in); 24 | static uint32_t rbit(uint32_t in); 25 | static int32_t get_sync_offset(uint32_t *words); 26 | static int32_t check_sync(const volatile uint8_t *frame); 27 | static void unpack_frame_to_words(const volatile uint8_t *frame, uint32_t *words); 28 | __attribute__((noinline)) static int32_t unpack_data(const uint32_t *frame, int16_t *ret); 29 | 30 | /* 31 | * decoder_handle_frame processes the captured frame, either syncing the spi device to the 32 | * start of the frame or decoding the data if the stream is sycned. 33 | */ 34 | void decoder_handle_frame(volatile uint8_t *frame) { 35 | if (check_sync(frame)) { 36 | change_state(SYNCED); 37 | } else if (state == SYNCED) { 38 | change_state(UNSYNCED); 39 | } 40 | int32_t sync_offset; 41 | uint32_t frame_words[4]; 42 | int16_t data[2] = {0, 0}; 43 | unpack_frame_to_words(frame, frame_words); 44 | 45 | switch (state) { 46 | case UNSYNCED: 47 | // todo unlight synced led 48 | sync_offset = get_sync_offset(frame_words); 49 | if (sync_offset == -1) { 50 | // todo light error led 51 | } else { 52 | timer_disable_spi_clk((uint32_t)sync_offset); 53 | change_state(SYNCING); 54 | } 55 | break; 56 | case SYNCING: 57 | change_state(UNSYNCED); 58 | break; 59 | case SYNCED: 60 | unpack_data(frame_words, data); 61 | // todo, decode biphase mark and copy sample into i2s buffer 62 | break; 63 | } 64 | frame[0] = (uint8_t) data[0]; 65 | 66 | } 67 | 68 | /* 69 | * change_state modifies the decoder state to the new one and sets the LEDs to indicate 70 | * the new state 71 | */ 72 | static void change_state(DecoderState new) { 73 | state = new; 74 | switch (state) { 75 | case UNSYNCED: 76 | gpio_set_leds(0, 0); 77 | break; 78 | case SYNCING: 79 | gpio_set_leds(1, 1); 80 | break; 81 | case SYNCED: 82 | gpio_set_leds(0, 1); 83 | break; 84 | default: 85 | gpio_set_leds(1, 0); 86 | break; 87 | } 88 | } 89 | 90 | // rev is a wrapper around the rev instruction. Swaps endianess. 91 | static uint32_t rev(uint32_t in) { 92 | uint32_t ret; 93 | __asm__("rev %0, %1" 94 | : "=r" (ret) 95 | : "r" (in)); 96 | return ret; 97 | } 98 | 99 | /* 100 | * rbit is a wrapper around the rbit instruction. Reverses the order of bits in the word. 101 | */ 102 | static uint32_t rbit(uint32_t in) { 103 | uint32_t ret; 104 | __asm__("rbit %0, %1" 105 | : "=r" (ret) 106 | : "r" (in)); 107 | return ret; 108 | } 109 | 110 | /* 111 | * unpack_frame_to_words copies the frame's data from frame to words and fixes the endianess 112 | * as well. 113 | */ 114 | static void unpack_frame_to_words(const volatile uint8_t *frame, uint32_t *words) { 115 | volatile uint32_t *frame_as_words = (uint32_t *)frame; 116 | for (int i = 0; i < 4; i++) { 117 | words[i] = rev(frame_as_words[i]); 118 | } 119 | } 120 | 121 | /* 122 | * get_sync_offset returns the offset in spdif clock cycles for where the start of the frame 123 | * is in the currently captured block 124 | */ 125 | static int32_t get_sync_offset(uint32_t *words) { 126 | // Need to do bit operations but the data is DMA'd in the wrong endianess for that 127 | for(int i = 1; i < 72; i++) { 128 | words[0] = (words[0] << 1) | (words[1] >> 31); 129 | uint8_t msb = words[0] >> 24; 130 | switch (msb) { 131 | case B_MAGIC: 132 | case IB_MAGIC: 133 | case M_MAGIC: 134 | case IM_MAGIC: 135 | return i; 136 | case W_MAGIC: 137 | case IW_MAGIC: 138 | return i + 64; 139 | } 140 | words[1] = (words[1] << 1) | (words[2] >> 31); 141 | words[2] = words[2] << 1; 142 | } 143 | return -1; 144 | } 145 | 146 | /* 147 | * check_sync returns if the block of data in frame is actually aligned to the start of a spdif 148 | * frame. 149 | * Returns true if the frame is synced, false otherwise 150 | */ 151 | static int32_t check_sync(const volatile uint8_t *frame) { 152 | switch (frame[0]) { 153 | case B_MAGIC: 154 | case IB_MAGIC: 155 | case M_MAGIC: 156 | case IM_MAGIC: 157 | return (frame[8] == W_MAGIC || frame[8] == IW_MAGIC); 158 | default: 159 | return 0; 160 | } 161 | } 162 | 163 | /* 164 | * unpack_data unpacks the frame into two shorts with the actual values transmitted. Marked 165 | * as noinline purely for debugging purposes. 166 | * */ 167 | __attribute__((noinline)) static int32_t unpack_data(const uint32_t *frame, int16_t *ret) { 168 | uint32_t words[2] = {(frame[0] << 24) | (frame[1] >> 8), 169 | (frame[2] << 24) | (frame[3] >> 8)}; 170 | 171 | int32_t val = 0; 172 | for (int i = 0; i < 2; i++) { 173 | uint32_t tmp = words[i] ^ (words[i] >> 1); 174 | // now every even bit is correct, need to smoosh down to 16 bits 175 | for (int bit = 0; bit < 16; bit ++) { 176 | val |= (int32_t) (((tmp >> (bit*2)) & 0x1) << bit); 177 | } 178 | ret[i] = rbit(val) >> 16; 179 | } 180 | return 0; 181 | } 182 | -------------------------------------------------------------------------------- /src/STM32L476VGTx_FLASH.ld: -------------------------------------------------------------------------------- 1 | /* 2 | ***************************************************************************** 3 | ** 4 | 5 | ** File : LinkerScript.ld 6 | ** 7 | ** Abstract : Linker script for STM32L476VGTx Device with 8 | ** 1024KByte FLASH, 96KByte RAM 9 | ** 10 | ** Set heap size, stack size and stack location according 11 | ** to application requirements. 12 | ** 13 | ** Set memory bank area and size if external memory is used. 14 | ** 15 | ** Target : STMicroelectronics STM32 16 | ** 17 | ** 18 | ** Distribution: The file is distributed as is, without any warranty 19 | ** of any kind. 20 | ** 21 | ** (c)Copyright Ac6. 22 | ** You may use this file as-is or modify it according to the needs of your 23 | ** project. Distribution of this file (unmodified or modified) is not 24 | ** permitted. Ac6 permit registered System Workbench for MCU users the 25 | ** rights to distribute the assembled, compiled & linked contents of this 26 | ** file as part of an application binary file, provided that it is built 27 | ** using the System Workbench for MCU toolchain. 28 | ** 29 | ***************************************************************************** 30 | */ 31 | 32 | /* Entry Point */ 33 | ENTRY(Reset_Handler) 34 | 35 | /* Highest address of the user mode stack */ 36 | _estack = 0x20018000; /* end of RAM */ 37 | /* Generate a link error if heap and stack don't fit into RAM */ 38 | _Min_Heap_Size = 0x200;; /* required amount of heap */ 39 | _Min_Stack_Size = 0x400;; /* required amount of stack */ 40 | 41 | /* Specify the memory areas */ 42 | MEMORY 43 | { 44 | FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K 45 | RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K 46 | } 47 | 48 | /* Define output sections */ 49 | SECTIONS 50 | { 51 | /* The startup code goes first into FLASH */ 52 | .isr_vector : 53 | { 54 | . = ALIGN(8); 55 | KEEP(*(.isr_vector)) /* Startup code */ 56 | . = ALIGN(8); 57 | } >FLASH 58 | 59 | /* The program code and other data goes into FLASH */ 60 | .text : 61 | { 62 | . = ALIGN(8); 63 | *(.text) /* .text sections (code) */ 64 | *(.text*) /* .text* sections (code) */ 65 | *(.glue_7) /* glue arm to thumb code */ 66 | *(.glue_7t) /* glue thumb to arm code */ 67 | *(.eh_frame) 68 | 69 | KEEP (*(.init)) 70 | KEEP (*(.fini)) 71 | 72 | . = ALIGN(8); 73 | _etext = .; /* define a global symbols at end of code */ 74 | } >FLASH 75 | 76 | /* Constant data goes into FLASH */ 77 | .rodata : 78 | { 79 | . = ALIGN(8); 80 | *(.rodata) /* .rodata sections (constants, strings, etc.) */ 81 | *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ 82 | . = ALIGN(8); 83 | } >FLASH 84 | 85 | .ARM.extab : 86 | { 87 | . = ALIGN(8); 88 | *(.ARM.extab* .gnu.linkonce.armextab.*) 89 | . = ALIGN(8); 90 | } >FLASH 91 | .ARM : { 92 | . = ALIGN(8); 93 | __exidx_start = .; 94 | *(.ARM.exidx*) 95 | __exidx_end = .; 96 | . = ALIGN(8); 97 | } >FLASH 98 | 99 | .preinit_array : 100 | { 101 | . = ALIGN(8); 102 | PROVIDE_HIDDEN (__preinit_array_start = .); 103 | KEEP (*(.preinit_array*)) 104 | PROVIDE_HIDDEN (__preinit_array_end = .); 105 | . = ALIGN(8); 106 | } >FLASH 107 | 108 | .init_array : 109 | { 110 | . = ALIGN(8); 111 | PROVIDE_HIDDEN (__init_array_start = .); 112 | KEEP (*(SORT(.init_array.*))) 113 | KEEP (*(.init_array*)) 114 | PROVIDE_HIDDEN (__init_array_end = .); 115 | . = ALIGN(8); 116 | } >FLASH 117 | .fini_array : 118 | { 119 | . = ALIGN(8); 120 | PROVIDE_HIDDEN (__fini_array_start = .); 121 | KEEP (*(SORT(.fini_array.*))) 122 | KEEP (*(.fini_array*)) 123 | PROVIDE_HIDDEN (__fini_array_end = .); 124 | . = ALIGN(8); 125 | } >FLASH 126 | 127 | /* used by the startup to initialize data */ 128 | _sidata = LOADADDR(.data); 129 | 130 | /* Initialized data sections goes into RAM, load LMA copy after code */ 131 | .data : 132 | { 133 | . = ALIGN(8); 134 | _sdata = .; /* create a global symbol at data start */ 135 | *(.data) /* .data sections */ 136 | *(.data*) /* .data* sections */ 137 | 138 | . = ALIGN(8); 139 | _edata = .; /* define a global symbol at data end */ 140 | } >RAM AT> FLASH 141 | 142 | 143 | /* Uninitialized data section */ 144 | . = ALIGN(4); 145 | .bss : 146 | { 147 | /* This is used by the startup in order to initialize the .bss secion */ 148 | _sbss = .; /* define a global symbol at bss start */ 149 | __bss_start__ = _sbss; 150 | *(.bss) 151 | *(.bss*) 152 | *(COMMON) 153 | 154 | . = ALIGN(4); 155 | _ebss = .; /* define a global symbol at bss end */ 156 | __bss_end__ = _ebss; 157 | } >RAM 158 | 159 | /* User_heap_stack section, used to check that there is enough RAM left */ 160 | ._user_heap_stack : 161 | { 162 | . = ALIGN(8); 163 | PROVIDE ( end = . ); 164 | PROVIDE ( _end = . ); 165 | . = . + _Min_Heap_Size; 166 | . = . + _Min_Stack_Size; 167 | . = ALIGN(8); 168 | } >RAM 169 | 170 | 171 | 172 | /* Remove information from the standard libraries */ 173 | /DISCARD/ : 174 | { 175 | libc.a ( * ) 176 | libm.a ( * ) 177 | libgcc.a ( * ) 178 | } 179 | 180 | .ARM.attributes 0 : { *(.ARM.attributes) } 181 | } 182 | 183 | 184 | -------------------------------------------------------------------------------- /src/startup_stm32l476xx.s: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file startup_stm32l476xx.s 4 | * @author MCD Application Team 5 | * @brief STM32L476xx devices vector table GCC toolchain. 6 | * This module performs: 7 | * - Set the initial SP 8 | * - Set the initial PC == Reset_Handler, 9 | * - Set the vector table entries with the exceptions ISR address, 10 | * - Configure the clock system 11 | * - Branches to main in the C library (which eventually 12 | * calls main()). 13 | * After Reset the Cortex-M4 processor is in Thread mode, 14 | * priority is Privileged, and the Stack is set to Main. 15 | ****************************************************************************** 16 | * @attention 17 | * 18 | *

© Copyright (c) 2017 STMicroelectronics. 19 | * All rights reserved.

20 | * 21 | * This software component is licensed by ST under BSD 3-Clause license, 22 | * the "License"; You may not use this file except in compliance with the 23 | * License. You may obtain a copy of the License at: 24 | * opensource.org/licenses/BSD-3-Clause 25 | * 26 | ****************************************************************************** 27 | */ 28 | 29 | .syntax unified 30 | .cpu cortex-m4 31 | .fpu softvfp 32 | .thumb 33 | 34 | .global g_pfnVectors 35 | .global Default_Handler 36 | 37 | /* start address for the initialization values of the .data section. 38 | defined in linker script */ 39 | .word _sidata 40 | /* start address for the .data section. defined in linker script */ 41 | .word _sdata 42 | /* end address for the .data section. defined in linker script */ 43 | .word _edata 44 | /* start address for the .bss section. defined in linker script */ 45 | .word _sbss 46 | /* end address for the .bss section. defined in linker script */ 47 | .word _ebss 48 | 49 | .equ BootRAM, 0xF1E0F85F 50 | /** 51 | * @brief This is the code that gets called when the processor first 52 | * starts execution following a reset event. Only the absolutely 53 | * necessary set is performed, after which the application 54 | * supplied main() routine is called. 55 | * @param None 56 | * @retval : None 57 | */ 58 | 59 | .section .text.Reset_Handler 60 | .weak Reset_Handler 61 | .type Reset_Handler, %function 62 | Reset_Handler: 63 | ldr sp, =_estack /* Set stack pointer */ 64 | 65 | /* Copy the data segment initializers from flash to SRAM */ 66 | movs r1, #0 67 | b LoopCopyDataInit 68 | 69 | CopyDataInit: 70 | ldr r3, =_sidata 71 | ldr r3, [r3, r1] 72 | str r3, [r0, r1] 73 | adds r1, r1, #4 74 | 75 | LoopCopyDataInit: 76 | ldr r0, =_sdata 77 | ldr r3, =_edata 78 | adds r2, r0, r1 79 | cmp r2, r3 80 | bcc CopyDataInit 81 | ldr r2, =_sbss 82 | b LoopFillZerobss 83 | /* Zero fill the bss segment. */ 84 | FillZerobss: 85 | movs r3, #0 86 | str r3, [r2], #4 87 | 88 | LoopFillZerobss: 89 | ldr r3, = _ebss 90 | cmp r2, r3 91 | bcc FillZerobss 92 | 93 | /* Call the clock system intitialization function.*/ 94 | bl SystemInit 95 | /* Call static constructors */ 96 | bl __libc_init_array 97 | /* Call the application's entry point.*/ 98 | bl main 99 | 100 | LoopForever: 101 | b LoopForever 102 | 103 | .size Reset_Handler, .-Reset_Handler 104 | 105 | /** 106 | * @brief This is the code that gets called when the processor receives an 107 | * unexpected interrupt. This simply enters an infinite loop, preserving 108 | * the system state for examination by a debugger. 109 | * 110 | * @param None 111 | * @retval : None 112 | */ 113 | .section .text.Default_Handler,"ax",%progbits 114 | Default_Handler: 115 | Infinite_Loop: 116 | mrs r0, ipsr 117 | b . 118 | .size Default_Handler, .-Default_Handler 119 | /****************************************************************************** 120 | * 121 | * The minimal vector table for a Cortex-M4. Note that the proper constructs 122 | * must be placed on this to ensure that it ends up at physical address 123 | * 0x0000.0000. 124 | * 125 | ******************************************************************************/ 126 | .section .isr_vector,"a",%progbits 127 | .type g_pfnVectors, %object 128 | .size g_pfnVectors, .-g_pfnVectors 129 | 130 | 131 | g_pfnVectors: 132 | .word _estack 133 | .word Reset_Handler 134 | .word NMI_Handler 135 | .word HardFault_Handler 136 | .word MemManage_Handler 137 | .word BusFault_Handler 138 | .word UsageFault_Handler 139 | .word 0 140 | .word 0 141 | .word 0 142 | .word 0 143 | .word SVC_Handler 144 | .word DebugMon_Handler 145 | .word 0 146 | .word PendSV_Handler 147 | .word SysTick_Handler 148 | .word WWDG_IRQHandler 149 | .word PVD_PVM_IRQHandler 150 | .word TAMP_STAMP_IRQHandler 151 | .word RTC_WKUP_IRQHandler 152 | .word FLASH_IRQHandler 153 | .word RCC_IRQHandler 154 | .word EXTI0_IRQHandler 155 | .word EXTI1_IRQHandler 156 | .word EXTI2_IRQHandler 157 | .word EXTI3_IRQHandler 158 | .word EXTI4_IRQHandler 159 | .word DMA1_Channel1_IRQHandler 160 | .word DMA1_Channel2_IRQHandler 161 | .word DMA1_Channel3_IRQHandler 162 | .word DMA1_Channel4_IRQHandler 163 | .word DMA1_Channel5_IRQHandler 164 | .word DMA1_Channel6_IRQHandler 165 | .word DMA1_Channel7_IRQHandler 166 | .word ADC1_2_IRQHandler 167 | .word CAN1_TX_IRQHandler 168 | .word CAN1_RX0_IRQHandler 169 | .word CAN1_RX1_IRQHandler 170 | .word CAN1_SCE_IRQHandler 171 | .word EXTI9_5_IRQHandler 172 | .word TIM1_BRK_TIM15_IRQHandler 173 | .word TIM1_UP_TIM16_IRQHandler 174 | .word TIM1_TRG_COM_TIM17_IRQHandler 175 | .word TIM1_CC_IRQHandler 176 | .word TIM2_IRQHandler 177 | .word TIM3_IRQHandler 178 | .word TIM4_IRQHandler 179 | .word I2C1_EV_IRQHandler 180 | .word I2C1_ER_IRQHandler 181 | .word I2C2_EV_IRQHandler 182 | .word I2C2_ER_IRQHandler 183 | .word SPI1_IRQHandler 184 | .word SPI2_IRQHandler 185 | .word USART1_IRQHandler 186 | .word USART2_IRQHandler 187 | .word USART3_IRQHandler 188 | .word EXTI15_10_IRQHandler 189 | .word RTC_Alarm_IRQHandler 190 | .word DFSDM1_FLT3_IRQHandler 191 | .word TIM8_BRK_IRQHandler 192 | .word TIM8_UP_IRQHandler 193 | .word TIM8_TRG_COM_IRQHandler 194 | .word TIM8_CC_IRQHandler 195 | .word ADC3_IRQHandler 196 | .word FMC_IRQHandler 197 | .word SDMMC1_IRQHandler 198 | .word TIM5_IRQHandler 199 | .word SPI3_IRQHandler 200 | .word UART4_IRQHandler 201 | .word UART5_IRQHandler 202 | .word TIM6_DAC_IRQHandler 203 | .word TIM7_IRQHandler 204 | .word DMA2_Channel1_IRQHandler 205 | .word DMA2_Channel2_IRQHandler 206 | .word DMA2_Channel3_IRQHandler 207 | .word DMA2_Channel4_IRQHandler 208 | .word DMA2_Channel5_IRQHandler 209 | .word DFSDM1_FLT0_IRQHandler 210 | .word DFSDM1_FLT1_IRQHandler 211 | .word DFSDM1_FLT2_IRQHandler 212 | .word COMP_IRQHandler 213 | .word LPTIM1_IRQHandler 214 | .word LPTIM2_IRQHandler 215 | .word OTG_FS_IRQHandler 216 | .word DMA2_Channel6_IRQHandler 217 | .word DMA2_Channel7_IRQHandler 218 | .word LPUART1_IRQHandler 219 | .word QUADSPI_IRQHandler 220 | .word I2C3_EV_IRQHandler 221 | .word I2C3_ER_IRQHandler 222 | .word SAI1_IRQHandler 223 | .word SAI2_IRQHandler 224 | .word SWPMI1_IRQHandler 225 | .word TSC_IRQHandler 226 | .word LCD_IRQHandler 227 | .word 0 228 | .word RNG_IRQHandler 229 | .word FPU_IRQHandler 230 | 231 | 232 | /******************************************************************************* 233 | * 234 | * Provide weak aliases for each Exception handler to the Default_Handler. 235 | * As they are weak aliases, any function with the same name will override 236 | * this definition. 237 | * 238 | *******************************************************************************/ 239 | 240 | .weak NMI_Handler 241 | .thumb_set NMI_Handler,Default_Handler 242 | 243 | .weak HardFault_Handler 244 | .thumb_set HardFault_Handler,Default_Handler 245 | 246 | .weak MemManage_Handler 247 | .thumb_set MemManage_Handler,Default_Handler 248 | 249 | .weak BusFault_Handler 250 | .thumb_set BusFault_Handler,Default_Handler 251 | 252 | .weak UsageFault_Handler 253 | .thumb_set UsageFault_Handler,Default_Handler 254 | 255 | .weak SVC_Handler 256 | .thumb_set SVC_Handler,Default_Handler 257 | 258 | .weak DebugMon_Handler 259 | .thumb_set DebugMon_Handler,Default_Handler 260 | 261 | .weak PendSV_Handler 262 | .thumb_set PendSV_Handler,Default_Handler 263 | 264 | .weak SysTick_Handler 265 | .thumb_set SysTick_Handler,Default_Handler 266 | 267 | .weak WWDG_IRQHandler 268 | .thumb_set WWDG_IRQHandler,Default_Handler 269 | 270 | .weak PVD_PVM_IRQHandler 271 | .thumb_set PVD_PVM_IRQHandler,Default_Handler 272 | 273 | .weak TAMP_STAMP_IRQHandler 274 | .thumb_set TAMP_STAMP_IRQHandler,Default_Handler 275 | 276 | .weak RTC_WKUP_IRQHandler 277 | .thumb_set RTC_WKUP_IRQHandler,Default_Handler 278 | 279 | .weak FLASH_IRQHandler 280 | .thumb_set FLASH_IRQHandler,Default_Handler 281 | 282 | .weak RCC_IRQHandler 283 | .thumb_set RCC_IRQHandler,Default_Handler 284 | 285 | .weak EXTI0_IRQHandler 286 | .thumb_set EXTI0_IRQHandler,Default_Handler 287 | 288 | .weak EXTI1_IRQHandler 289 | .thumb_set EXTI1_IRQHandler,Default_Handler 290 | 291 | .weak EXTI2_IRQHandler 292 | .thumb_set EXTI2_IRQHandler,Default_Handler 293 | 294 | .weak EXTI3_IRQHandler 295 | .thumb_set EXTI3_IRQHandler,Default_Handler 296 | 297 | .weak EXTI4_IRQHandler 298 | .thumb_set EXTI4_IRQHandler,Default_Handler 299 | 300 | .weak DMA1_Channel1_IRQHandler 301 | .thumb_set DMA1_Channel1_IRQHandler,Default_Handler 302 | 303 | .weak DMA1_Channel2_IRQHandler 304 | .thumb_set DMA1_Channel2_IRQHandler,Default_Handler 305 | 306 | .weak DMA1_Channel3_IRQHandler 307 | .thumb_set DMA1_Channel3_IRQHandler,Default_Handler 308 | 309 | .weak DMA1_Channel4_IRQHandler 310 | .thumb_set DMA1_Channel4_IRQHandler,Default_Handler 311 | 312 | .weak DMA1_Channel5_IRQHandler 313 | .thumb_set DMA1_Channel5_IRQHandler,Default_Handler 314 | 315 | .weak DMA1_Channel6_IRQHandler 316 | .thumb_set DMA1_Channel6_IRQHandler,Default_Handler 317 | 318 | .weak DMA1_Channel7_IRQHandler 319 | .thumb_set DMA1_Channel7_IRQHandler,Default_Handler 320 | 321 | .weak ADC1_2_IRQHandler 322 | .thumb_set ADC1_2_IRQHandler,Default_Handler 323 | 324 | .weak CAN1_TX_IRQHandler 325 | .thumb_set CAN1_TX_IRQHandler,Default_Handler 326 | 327 | .weak CAN1_RX0_IRQHandler 328 | .thumb_set CAN1_RX0_IRQHandler,Default_Handler 329 | 330 | .weak CAN1_RX1_IRQHandler 331 | .thumb_set CAN1_RX1_IRQHandler,Default_Handler 332 | 333 | .weak CAN1_SCE_IRQHandler 334 | .thumb_set CAN1_SCE_IRQHandler,Default_Handler 335 | 336 | .weak EXTI9_5_IRQHandler 337 | .thumb_set EXTI9_5_IRQHandler,Default_Handler 338 | 339 | .weak TIM1_BRK_TIM15_IRQHandler 340 | .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler 341 | 342 | .weak TIM1_UP_TIM16_IRQHandler 343 | .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler 344 | 345 | .weak TIM1_TRG_COM_TIM17_IRQHandler 346 | .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler 347 | 348 | .weak TIM1_CC_IRQHandler 349 | .thumb_set TIM1_CC_IRQHandler,Default_Handler 350 | 351 | .weak TIM2_IRQHandler 352 | .thumb_set TIM2_IRQHandler,Default_Handler 353 | 354 | .weak TIM3_IRQHandler 355 | .thumb_set TIM3_IRQHandler,Default_Handler 356 | 357 | .weak TIM4_IRQHandler 358 | .thumb_set TIM4_IRQHandler,Default_Handler 359 | 360 | .weak I2C1_EV_IRQHandler 361 | .thumb_set I2C1_EV_IRQHandler,Default_Handler 362 | 363 | .weak I2C1_ER_IRQHandler 364 | .thumb_set I2C1_ER_IRQHandler,Default_Handler 365 | 366 | .weak I2C2_EV_IRQHandler 367 | .thumb_set I2C2_EV_IRQHandler,Default_Handler 368 | 369 | .weak I2C2_ER_IRQHandler 370 | .thumb_set I2C2_ER_IRQHandler,Default_Handler 371 | 372 | .weak SPI1_IRQHandler 373 | .thumb_set SPI1_IRQHandler,Default_Handler 374 | 375 | .weak SPI2_IRQHandler 376 | .thumb_set SPI2_IRQHandler,Default_Handler 377 | 378 | .weak USART1_IRQHandler 379 | .thumb_set USART1_IRQHandler,Default_Handler 380 | 381 | .weak USART2_IRQHandler 382 | .thumb_set USART2_IRQHandler,Default_Handler 383 | 384 | .weak USART3_IRQHandler 385 | .thumb_set USART3_IRQHandler,Default_Handler 386 | 387 | .weak EXTI15_10_IRQHandler 388 | .thumb_set EXTI15_10_IRQHandler,Default_Handler 389 | 390 | .weak RTC_Alarm_IRQHandler 391 | .thumb_set RTC_Alarm_IRQHandler,Default_Handler 392 | 393 | .weak DFSDM1_FLT3_IRQHandler 394 | .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler 395 | 396 | .weak TIM8_BRK_IRQHandler 397 | .thumb_set TIM8_BRK_IRQHandler,Default_Handler 398 | 399 | .weak TIM8_UP_IRQHandler 400 | .thumb_set TIM8_UP_IRQHandler,Default_Handler 401 | 402 | .weak TIM8_TRG_COM_IRQHandler 403 | .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler 404 | 405 | .weak TIM8_CC_IRQHandler 406 | .thumb_set TIM8_CC_IRQHandler,Default_Handler 407 | 408 | .weak ADC3_IRQHandler 409 | .thumb_set ADC3_IRQHandler,Default_Handler 410 | 411 | .weak FMC_IRQHandler 412 | .thumb_set FMC_IRQHandler,Default_Handler 413 | 414 | .weak SDMMC1_IRQHandler 415 | .thumb_set SDMMC1_IRQHandler,Default_Handler 416 | 417 | .weak TIM5_IRQHandler 418 | .thumb_set TIM5_IRQHandler,Default_Handler 419 | 420 | .weak SPI3_IRQHandler 421 | .thumb_set SPI3_IRQHandler,Default_Handler 422 | 423 | .weak UART4_IRQHandler 424 | .thumb_set UART4_IRQHandler,Default_Handler 425 | 426 | .weak UART5_IRQHandler 427 | .thumb_set UART5_IRQHandler,Default_Handler 428 | 429 | .weak TIM6_DAC_IRQHandler 430 | .thumb_set TIM6_DAC_IRQHandler,Default_Handler 431 | 432 | .weak TIM7_IRQHandler 433 | .thumb_set TIM7_IRQHandler,Default_Handler 434 | 435 | .weak DMA2_Channel1_IRQHandler 436 | .thumb_set DMA2_Channel1_IRQHandler,Default_Handler 437 | 438 | .weak DMA2_Channel2_IRQHandler 439 | .thumb_set DMA2_Channel2_IRQHandler,Default_Handler 440 | 441 | .weak DMA2_Channel3_IRQHandler 442 | .thumb_set DMA2_Channel3_IRQHandler,Default_Handler 443 | 444 | .weak DMA2_Channel4_IRQHandler 445 | .thumb_set DMA2_Channel4_IRQHandler,Default_Handler 446 | 447 | .weak DMA2_Channel5_IRQHandler 448 | .thumb_set DMA2_Channel5_IRQHandler,Default_Handler 449 | 450 | .weak DFSDM1_FLT0_IRQHandler 451 | .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler 452 | 453 | .weak DFSDM1_FLT1_IRQHandler 454 | .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler 455 | 456 | .weak DFSDM1_FLT2_IRQHandler 457 | .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler 458 | 459 | .weak COMP_IRQHandler 460 | .thumb_set COMP_IRQHandler,Default_Handler 461 | 462 | .weak LPTIM1_IRQHandler 463 | .thumb_set LPTIM1_IRQHandler,Default_Handler 464 | 465 | .weak LPTIM2_IRQHandler 466 | .thumb_set LPTIM2_IRQHandler,Default_Handler 467 | 468 | .weak OTG_FS_IRQHandler 469 | .thumb_set OTG_FS_IRQHandler,Default_Handler 470 | 471 | .weak DMA2_Channel6_IRQHandler 472 | .thumb_set DMA2_Channel6_IRQHandler,Default_Handler 473 | 474 | .weak DMA2_Channel7_IRQHandler 475 | .thumb_set DMA2_Channel7_IRQHandler,Default_Handler 476 | 477 | .weak LPUART1_IRQHandler 478 | .thumb_set LPUART1_IRQHandler,Default_Handler 479 | 480 | .weak QUADSPI_IRQHandler 481 | .thumb_set QUADSPI_IRQHandler,Default_Handler 482 | 483 | .weak I2C3_EV_IRQHandler 484 | .thumb_set I2C3_EV_IRQHandler,Default_Handler 485 | 486 | .weak I2C3_ER_IRQHandler 487 | .thumb_set I2C3_ER_IRQHandler,Default_Handler 488 | 489 | .weak SAI1_IRQHandler 490 | .thumb_set SAI1_IRQHandler,Default_Handler 491 | 492 | .weak SAI2_IRQHandler 493 | .thumb_set SAI2_IRQHandler,Default_Handler 494 | 495 | .weak SWPMI1_IRQHandler 496 | .thumb_set SWPMI1_IRQHandler,Default_Handler 497 | 498 | .weak TSC_IRQHandler 499 | .thumb_set TSC_IRQHandler,Default_Handler 500 | 501 | .weak LCD_IRQHandler 502 | .thumb_set LCD_IRQHandler,Default_Handler 503 | 504 | .weak RNG_IRQHandler 505 | .thumb_set RNG_IRQHandler,Default_Handler 506 | 507 | .weak FPU_IRQHandler 508 | .thumb_set FPU_IRQHandler,Default_Handler 509 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 510 | --------------------------------------------------------------------------------