summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGravatar Matthew Wozniak <me@woz.blue> 2025-12-11 23:58:51 -0500
committerGravatar Matthew Wozniak <me@woz.blue> 2025-12-11 23:58:51 -0500
commit5356bc886d53291a9a812f2aba35e4e165d96fba (patch)
tree55fbe7e4f3cb54a5b8c43b40aba4771dc0465d8a
downloadstm32_can_demo-5356bc886d53291a9a812f2aba35e4e165d96fba.tar.gz
stm32_can_demo-5356bc886d53291a9a812f2aba35e4e165d96fba.zip
initial commit
-rw-r--r--.gitignore2
-rw-r--r--.gitmodules6
m---------3p/CMSIS_60
m---------3p/cmsis-device-f10
-rw-r--r--Makefile31
-rw-r--r--compile_flags.txt7
-rw-r--r--intdefs.h25
-rw-r--r--linker_script.ld52
-rw-r--r--main.c246
-rw-r--r--startup.c203
10 files changed, 572 insertions, 0 deletions
diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..20596b5
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,2 @@
+*.o
+*.elf
diff --git a/.gitmodules b/.gitmodules
new file mode 100644
index 0000000..ab4bf36
--- /dev/null
+++ b/.gitmodules
@@ -0,0 +1,6 @@
+[submodule "3p/CMSIS_6"]
+ path = 3p/CMSIS_6
+ url = https://github.com/ARM-software/CMSIS_6
+[submodule "3p/cmsis-device-f1"]
+ path = 3p/cmsis-device-f1
+ url = https://github.com/STMicroelectronics/cmsis-device-f1
diff --git a/3p/CMSIS_6 b/3p/CMSIS_6
new file mode 160000
+Subproject 20143a27aecaae3c46280a6f5ecc12c983292b2
diff --git a/3p/cmsis-device-f1 b/3p/cmsis-device-f1
new file mode 160000
+Subproject c8e9a4a4f16b6d2cb2a2083cbe5161025280fb2
diff --git a/Makefile b/Makefile
new file mode 100644
index 0000000..6b5ce62
--- /dev/null
+++ b/Makefile
@@ -0,0 +1,31 @@
+CC = arm-none-eabi-gcc
+CFLAGS = -mcpu=cortex-m3 -mthumb -ffreestanding -Os -nostartfiles -std=c23 \
+ -DSTM32F103xB \
+ -Wpedantic \
+ -I3p/cmsis-device-f1/Include \
+ -I3p/CMSIS_6/CMSIS/Core/Include
+
+LINKER_FILE=linker_script.ld
+LDFLAGS=-specs=nano.specs -specs=nosys.specs -T $(LINKER_FILE)
+
+all: blink.elf
+
+.PHONY: clean flash debug
+
+clean:
+ rm -v *.o blink.elf
+
+blink.elf: main.o startup.o system_stm32f1xx.o
+ $(CC) $(CFLAGS) $(CPPFLAGS) $(LDFLAGS) $^ -o blink.elf
+
+system_stm32f1xx.o: 3p/cmsis-device-f1/Source/Templates/system_stm32f1xx.c
+ $(CC) $(CFLAGS) 3p/cmsis-device-f1/Source/Templates/system_stm32f1xx.c -c
+
+%.o: %.c
+ $(CC) $(CFLAGS) $< -c -o $@
+
+flash: blink.elf
+ openocd -f interface/stlink.cfg -f target/stm32f1x.cfg -c "program blink.elf verify reset exit"
+
+debug: blink.elf
+ openocd -f interface/stlink.cfg -f target/stm32f1x.cfg
diff --git a/compile_flags.txt b/compile_flags.txt
new file mode 100644
index 0000000..8afe53d
--- /dev/null
+++ b/compile_flags.txt
@@ -0,0 +1,7 @@
+--target=arm-none-eabi
+-mcpu=cortex-m3
+-mthumb
+-DSTM32F103xB
+-std=c23
+-I3p/cmsis-device-f1/Include
+-I3p/CMSIS_6/CMSIS/Core/Include
diff --git a/intdefs.h b/intdefs.h
new file mode 100644
index 0000000..97c6f82
--- /dev/null
+++ b/intdefs.h
@@ -0,0 +1,25 @@
+/* This file is dedicated to the public domain. */
+
+#ifndef INC_INTDEFS_H
+#define INC_INTDEFS_H
+
+typedef signed char schar;
+typedef unsigned char uchar;
+typedef unsigned short ushort;
+typedef unsigned int uint;
+typedef unsigned long ulong;
+typedef long long vlong;
+typedef unsigned long long uvlong;
+
+typedef schar s8;
+typedef uchar u8;
+typedef short s16;
+typedef ushort u16;
+typedef int s32;
+typedef uint u32;
+typedef vlong s64;
+typedef uvlong u64;
+
+#endif
+
+// vi: sw=4 ts=4 noet tw=80 cc=80
diff --git a/linker_script.ld b/linker_script.ld
new file mode 100644
index 0000000..b8d1231
--- /dev/null
+++ b/linker_script.ld
@@ -0,0 +1,52 @@
+ENTRY(reset_handler)
+
+MEMORY
+{
+ FLASH(rx): ORIGIN = 0x08000000, LENGTH = 64K
+ SRAM(rw): ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+SECTIONS
+{
+ .isr_vector :
+ {
+ KEEP(*(.isr_vector))
+ } >FLASH
+
+ .text :
+ {
+ . = ALIGN(4);
+
+ *(.text)
+ *(.rodata)
+
+ . = ALIGN(4);
+ _etext = .;
+ } >FLASH
+
+ _sidata = LOADADDR(.data);
+
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .;
+
+ *(.data)
+
+ . = ALIGN(4);
+ _edata = .;
+ } >SRAM AT> FLASH
+
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+ __bss_start__ = .;
+
+ *(.bss)
+
+ . = ALIGN(4);
+ _ebss = .;
+ __bss_end__ = .;
+ } >SRAM
+}
diff --git a/main.c b/main.c
new file mode 100644
index 0000000..89f96b7
--- /dev/null
+++ b/main.c
@@ -0,0 +1,246 @@
+/*
+ * Copyright © Matthew Wozniak <me@woz.blue>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED “AS IS” AND THE AUTHOR DISCLAIMS ALL WARRANTIES WITH
+ * REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF MERCHANTABILITY
+ * AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT,
+ * INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM
+ * LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR
+ * OTHER TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
+ * PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#include "intdefs.h"
+
+#include "stm32f1xx.h"
+
+#define DOER
+
+/* Our CAN recv queue */
+#define CAN_FRAME_QUEUE_DEPTH 128
+struct {
+ int front;
+ int back;
+ CAN_FIFOMailBox_TypeDef data[CAN_FRAME_QUEUE_DEPTH];
+} can_frames = {};
+
+bool can_recv(CAN_FIFOMailBox_TypeDef *frame) {
+ if (can_frames.front == can_frames.back) return false;
+ *frame = can_frames.data[can_frames.front];
+ can_frames.front = (can_frames.front + 1) % CAN_FRAME_QUEUE_DEPTH;
+ return true;
+}
+
+// This will get called when we get a new frame in FIFO1
+void canrx1_handler() {
+ // if the queue is full just drop the frame
+ if ((can_frames.back + 1) % CAN_FRAME_QUEUE_DEPTH == can_frames.front) {
+ CAN1->RF1R |= CAN_RF1R_RFOM1;
+ return;
+ }
+ can_frames.data[can_frames.back] = CAN1->sFIFOMailBox[1];
+ can_frames.back = (can_frames.back + 1) % CAN_FRAME_QUEUE_DEPTH;
+ // tell the FIFO we are done with this frame
+ CAN1->RF1R |= CAN_RF1R_RFOM1;
+}
+
+/*
+ * Sends a CAN frame over CAN1. If id is longer than 11 bits, sends it with the
+ * extended format. Otherwise uses the standard format.
+ *
+ * Returns false if there is no available mailbox (couldn't send the frame)
+ */
+bool can_send_frame(u32 id, u8 data[8], int len) {
+ // find the first open mailbox
+ for (int i = 0; i < 3; i++) {
+ // is this mailbox empty?
+ if (CAN1->sTxMailBox[i].TIR & CAN_TI0R_TXRQ_Msk)
+ continue;
+ // it is, we will put our new message here
+ CAN_TxMailBox_TypeDef *mb = CAN1->sTxMailBox + i;
+ // set data length
+ mb->TDTR &= ~CAN_TDT0R_DLC_Msk;
+ mb->TDTR |= (len & 0xf) << CAN_TDT0R_DLC_Pos;
+ // set data
+ mb->TDHR = data[7] << 24 | data[6] << 16 | data[5] << 8 | data[4];
+ mb->TDLR = data[3] << 24 | data[2] << 16 | data[1] << 8 | data[0];
+ // set CAN id
+ int tir = 0;
+ if (id > 0x7ff) {
+ tir |= id << CAN_TI0R_EXID_Pos;
+ tir |= CAN_TI0R_IDE;
+ } else {
+ tir |= id << CAN_TI0R_STID_Pos;
+ }
+ // send it off
+ mb->TIR |= tir | CAN_TI0R_TXRQ;
+ return true;
+ }
+ // no empty mailbox!
+ return false;
+}
+
+volatile u32 ticks = 0;
+void systick_handler() {
+ ticks++;
+}
+
+void delay_ms(u32 ms) {
+ u32 start = ticks;
+ u32 end = ticks + ms;
+ while (ticks < end);
+}
+
+int main() {
+ // enable the HSE
+ RCC->CR |= RCC_CR_HSEON;
+ while (!(RCC->CR & RCC_CR_HSERDY_Msk));
+
+ // configure PLL to use HSE clock
+ RCC->CFGR &= ~RCC_CFGR_PLLSRC_Msk;
+ RCC->CFGR |= 1 << RCC_CFGR_PLLSRC_Pos;
+
+ // configure PLL to 9x clock scaling (8MHz * 9 = 72MHz)
+ RCC->CFGR &= ~RCC_CFGR_PLLMULL_Msk;
+ RCC->CFGR |= RCC_CFGR_PLLMULL9_Msk;
+
+ // enable the PLL
+ RCC->CR |= RCC_CR_PLLON;
+ while (!(RCC->CR & RCC_CR_PLLRDY));
+
+ // divide ABP1 by 2 (max frequency is 36MHz)
+ RCC->CFGR &= ~RCC_CFGR_PPRE1_Msk;
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ // 2 waitstate for 72 MHz clock
+ FLASH->ACR |= FLASH_ACR_LATENCY_2;
+
+ // finally, set SYSCLK to use PLL output (72MHz)
+ RCC->CFGR &= ~RCC_CFGR_SW_Msk;
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ // 72M cycles/sec / 1000 cycles = 0.001
+ // 1 ms SysTick interrupt timer
+ SystemCoreClock = 72000000;
+ SysTick_Config(SystemCoreClock / 1000);
+ __enable_irq();
+
+ // GPIO ports C and A and AFIO
+ RCC->APB2ENR |= RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN;
+ // CAN1
+ RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
+
+ // do two dummy reads after enabling the peripheral clocks,
+ // as per the errata
+ volatile u32 dummy;
+ dummy = RCC->APB2ENR; dummy = RCC->APB2ENR;
+ dummy = RCC->APB1ENR; dummy = RCC->APB1ENR;
+
+ // Push pull output
+ GPIOC->CRH |= 1 << GPIO_CRH_MODE13_Pos | 0 << GPIO_CRH_CNF13_Pos;
+
+ // CAN1 remap 0 (PA11 and PA12)
+ AFIO->MAPR &= ~AFIO_MAPR_CAN_REMAP_Msk;
+ // Pin 11 will be initialized to an input
+ // Set GPIO A pin 12 to be the alternate function
+ GPIOA->CRH |= 3 /* 50MHz output */ << GPIO_CRH_MODE12_Pos |
+ 2 /* Alternate function push-pull */ << GPIO_CRH_CNF12_Pos;
+
+ // Set to init mode
+ CAN1->MCR |= CAN_MCR_INRQ;
+ while (!(CAN1->MSR & CAN_MSR_INAK));
+
+ // No silent mode
+ CAN1->BTR &= ~CAN_BTR_SILM;
+ // Enable loopback for now
+ CAN1->BTR |= CAN_BTR_LBKM;
+
+ // Set it to some value
+ CAN1->BTR &= ~CAN_BTR_SJW_Msk;
+ CAN1->BTR |= CAN_BTR_SJW_1;
+
+ /* http://www.bittiming.can-wiki.info
+ * we want the bitrate to be 1,000,000
+ *
+ * One bit:
+ * sync (1 tq)
+ * time seg 1 (15 tq)
+ * time seg 2 (2 tq)
+ * = total 18 time quanta
+ *
+ * So to make the bitrate 1 Mbps we must set the CAN clock prescaler to
+ * send 18 tq per 1 / 1,000,000
+ * Since it sends 1 tq for clock cycle we will set it to 18 MHz
+ * So scale down 36 MHz by 2. So we set the BRP to 1 because it adds 1 for
+ * us.
+ */
+ CAN1->BTR &= ~(CAN_BTR_BRP_Msk | CAN_BTR_TS1_Msk | CAN_BTR_TS2_Msk);
+ CAN1->BTR |=
+ 15 << CAN_BTR_TS1_Pos |
+ 2 << CAN_BTR_TS2_Pos |
+ 7 << CAN_BTR_BRP_Pos;
+
+ // Leave sleep (synchronize on the bus)
+ // Keep CAN working while being debugged
+ // Automatically wakeup when we see something
+ // Recover from any bus off events
+ // Don't resend messages if they aren't acknowledged
+ CAN1->MCR &= ~(CAN_MCR_SLEEP
+ | CAN_MCR_DBF
+ | CAN_MCR_RESET
+ | CAN_MCR_AWUM
+ | CAN_MCR_ABOM
+ | CAN_MCR_NART);
+
+ // Put every received frame in FIFO1 for now
+ CAN1->FMR |= CAN_FMR_FINIT;
+ // Single 32 bit mode
+ CAN1->FS1R |= 1 << CAN_FS1R_FSC0_Pos;
+ // Set to mask mode (should already be unset but just make sure)
+ CAN1->FM1R &= ~(1 << CAN_FM1R_FBM0_Pos);
+ // Send to FIFO1
+ CAN1->FFA1R |= 1 << CAN_FFA1R_FFA0_Pos;
+ // Set filter 0 to active
+ CAN1->FA1R |= 1 << CAN_FA1R_FACT0_Pos;
+ // Match everything
+ CAN1->sFilterRegister[0].FR1 = 0;
+ CAN1->sFilterRegister[0].FR2 = 0;
+ // Activate filters
+ CAN1->FMR &= ~CAN_FMR_FINIT;
+
+ // Interrupt on CAN frame receive so we can move the frame to our own queue
+ CAN1->IER |= CAN_IER_FMPIE1;
+ NVIC_SetPriority(CAN1_RX1_IRQn, 10);
+ NVIC_EnableIRQ(CAN1_RX1_IRQn);
+
+ // exit init mode
+ CAN1->MCR &= ~CAN_MCR_INRQ;
+ while (CAN1->MSR & CAN_MSR_INAK);
+
+ while (1) {
+#ifdef TELLER
+ u8 test_frame_data[8] = { 0, 1, 2, 3, 4, 5, 6, 7 };
+ GPIOC->ODR ^= (1 << 13);
+ if (!can_send_frame(1, test_frame_data, 8)) {
+ for (int i = 0; i < 10; i++) {
+ GPIOC->ODR ^= (1 << 13);
+ delay_ms(50);
+ }
+ }
+ delay_ms(100);
+#endif
+#ifdef DOER
+ CAN_FIFOMailBox_TypeDef frame;
+ if (can_recv(&frame)) {
+ GPIOC->ODR ^= 1 << 13;
+ }
+ delay_ms(10);
+#endif
+ }
+}
+
+// vi: sw=4 ts=4 noet tw=80 cc=80
diff --git a/startup.c b/startup.c
new file mode 100644
index 0000000..12d8784
--- /dev/null
+++ b/startup.c
@@ -0,0 +1,203 @@
+/*
+ * Copyright © Matthew Wozniak <me@woz.blue>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED “AS IS” AND THE AUTHOR DISCLAIMS ALL WARRANTIES WITH
+ * REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF MERCHANTABILITY
+ * AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT,
+ * INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM
+ * LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR
+ * OTHER TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
+ * PERFORMANCE OF THIS SOFTWARE.
+ */
+
+/*
+ * This startup.c file is for the STM32F103C8T6 used on the bluepill boards, and
+ * while it may work for others I provide no guarntees.
+ */
+
+#include "intdefs.h"
+
+#define SRAM_START (0x20000000U)
+#define SRAM_SIZE (20U * 1024U)
+#define SRAM_END (SRAM_START + SRAM_SIZE)
+#define STACK_POINTER_INIT_ADDRESS (SRAM_END)
+
+#include <string.h>
+
+#define ISR_VECTOR_SIZE 76
+
+void reset_handler();
+void default_handler();
+void nmi_handler() __attribute__((weak, alias("default_handler")));
+void hardfault_handler() __attribute__((weak, alias("default_handler")));
+void memory_management_handler() __attribute__((weak, alias("default_handler")));
+void bus_fault_handler() __attribute__((weak, alias("default_handler")));
+void usage_fault_handler() __attribute__((weak, alias("default_handler")));
+void svcall_handler() __attribute__((weak, alias("default_handler")));
+void debug_monitor_handler() __attribute__((weak, alias("default_handler")));
+void pendsv_handler() __attribute__((weak, alias("default_handler")));
+void systick_handler() __attribute__((weak, alias("default_handler")));
+void wwdg_handler() __attribute__((weak, alias("default_handler")));
+void pvd_handler() __attribute__((weak, alias("default_handler")));
+void tamper_handler() __attribute__((weak, alias("default_handler")));
+void rtc_handler() __attribute__((weak, alias("default_handler")));
+void flash_handler() __attribute__((weak, alias("default_handler")));
+void rcc_handler() __attribute__((weak, alias("default_handler")));
+void exti0_handler() __attribute__((weak, alias("default_handler")));
+void exti1_handler() __attribute__((weak, alias("default_handler")));
+void exti2_handler() __attribute__((weak, alias("default_handler")));
+void exti3_handler() __attribute__((weak, alias("default_handler")));
+void exti4_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel1_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel2_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel3_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel4_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel5_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel6_handler() __attribute__((weak, alias("default_handler")));
+void dma1_channel7_handler() __attribute__((weak, alias("default_handler")));
+void adc_handler() __attribute__((weak, alias("default_handler")));
+void usbhp_cantx_handler() __attribute__((weak, alias("default_handler")));
+void usblp_canrx0_handler() __attribute__((weak, alias("default_handler")));
+void canrx1_handler() __attribute__((weak, alias("default_handler")));
+void cansce_handler() __attribute__((weak, alias("default_handler")));
+void exti9_5_handler() __attribute__((weak, alias("default_handler")));
+void tim1brk_handler() __attribute__((weak, alias("default_handler")));
+void tim1up_handler() __attribute__((weak, alias("default_handler")));
+void tim1trgcom_handler() __attribute__((weak, alias("default_handler")));
+void tim1cc_handler() __attribute__((weak, alias("default_handler")));
+void tim2_handler() __attribute__((weak, alias("default_handler")));
+void tim3_handler() __attribute__((weak, alias("default_handler")));
+void tim4_handler() __attribute__((weak, alias("default_handler")));
+void i2c1_ev_handler() __attribute__((weak, alias("default_handler")));
+void i2c1_er_handler() __attribute__((weak, alias("default_handler")));
+void i2c2_ev_handler() __attribute__((weak, alias("default_handler")));
+void i2c2_er_handler() __attribute__((weak, alias("default_handler")));
+void spi1_handler() __attribute__((weak, alias("default_handler")));
+void spi2_handler() __attribute__((weak, alias("default_handler")));
+void usart1_handler() __attribute__((weak, alias("default_handler")));
+void usart2_handler() __attribute__((weak, alias("default_handler")));
+void usart3_handler() __attribute__((weak, alias("default_handler")));
+void exti15_10_handler() __attribute__((weak, alias("default_handler")));
+void rtcalarm_handler() __attribute__((weak, alias("default_handler")));
+void usbwakeup_handler() __attribute__((weak, alias("default_handler")));
+void tim8brk_handler() __attribute__((weak, alias("default_handler")));
+void tim8up_handler() __attribute__((weak, alias("default_handler")));
+void tim8trgcom_handler() __attribute__((weak, alias("default_handler")));
+void tim8cc_handler() __attribute__((weak, alias("default_handler")));
+void adc3_handler() __attribute__((weak, alias("default_handler")));
+void fsmc_handler() __attribute__((weak, alias("default_handler")));
+void sdio_handler() __attribute__((weak, alias("default_handler")));
+void tim5_handler() __attribute__((weak, alias("default_handler")));
+void spi3_handler() __attribute__((weak, alias("default_handler")));
+void uart4_handler() __attribute__((weak, alias("default_handler")));
+void uart5_handler() __attribute__((weak, alias("default_handler")));
+void tim6_handler() __attribute__((weak, alias("default_handler")));
+void tim7_handler() __attribute__((weak, alias("default_handler")));
+void dma2_channel1_handler() __attribute__((weak, alias("default_handler")));
+void dma2_channel2_handler() __attribute__((weak, alias("default_handler")));
+void dma2_channel3_handler() __attribute__((weak, alias("default_handler")));
+void dma2_channel4_5_handler() __attribute__((weak, alias("default_handler")));
+
+void (*isr_vector[ISR_VECTOR_SIZE])() __attribute__((section(".isr_vector"))) = {
+ (void (*)())STACK_POINTER_INIT_ADDRESS,
+ reset_handler,
+ nmi_handler,
+ hardfault_handler,
+ memory_management_handler,
+ bus_fault_handler,
+ usage_fault_handler,
+ nullptr, /* reserved */
+ svcall_handler,
+ debug_monitor_handler,
+ nullptr, /* reserved */
+ nullptr,
+ nullptr,
+ nullptr,
+ pendsv_handler,
+ systick_handler,
+ wwdg_handler,
+ pvd_handler,
+ tamper_handler,
+ rtc_handler,
+ flash_handler,
+ rcc_handler,
+ exti0_handler,
+ exti1_handler,
+ exti2_handler,
+ exti3_handler,
+ exti4_handler,
+ dma1_channel1_handler,
+ dma1_channel2_handler,
+ dma1_channel3_handler,
+ dma1_channel4_handler,
+ dma1_channel5_handler,
+ dma1_channel6_handler,
+ dma1_channel7_handler,
+ adc_handler,
+ usbhp_cantx_handler,
+ usblp_canrx0_handler,
+ canrx1_handler,
+ cansce_handler,
+ exti9_5_handler,
+ tim1brk_handler,
+ tim1up_handler,
+ tim1trgcom_handler,
+ tim1cc_handler,
+ tim2_handler,
+ tim3_handler,
+ tim4_handler,
+ i2c1_ev_handler,
+ i2c1_er_handler,
+ i2c2_ev_handler,
+ i2c2_er_handler,
+ spi1_handler,
+ spi2_handler,
+ usart1_handler,
+ usart2_handler,
+ usart3_handler,
+ exti15_10_handler,
+ rtcalarm_handler,
+ usbwakeup_handler,
+ tim8brk_handler,
+ tim8up_handler,
+ tim8trgcom_handler,
+ tim8cc_handler,
+ adc3_handler,
+ fsmc_handler,
+ sdio_handler,
+ tim5_handler,
+ spi3_handler,
+ uart4_handler,
+ uart5_handler,
+ tim6_handler,
+ tim7_handler,
+ dma2_channel1_handler,
+ dma2_channel2_handler,
+ dma2_channel3_handler,
+ dma2_channel4_5_handler,
+};
+
+void default_handler() {
+ while (1) {}
+}
+
+extern u32 _etext, _sdata, _sidata, _edata, _sbss, _ebss;
+int main();
+
+void reset_handler() {
+ // copy .data from FLASH to SRAM
+ u32 data_sz = (u32)&_edata - (u32)&_sdata;
+ memcpy(&_sdata, &_sidata, data_sz);
+
+ // zero-fill .bss
+ memset(&_sbss, 0, (u32)&_ebss - (u32)&_sbss);
+
+ // run our program
+ main();
+}
+
+// vi: sw=4 ts=4 noet tw=80 cc=80