diff options
author | Vegard Storheil Eriksen <zyp@jvnv.net> | 2012-08-07 16:54:36 +0200 |
---|---|---|
committer | Vegard Storheil Eriksen <zyp@jvnv.net> | 2012-08-07 16:54:36 +0200 |
commit | 09e89c867c8dc14adee298176a0a4c72d8f32245 (patch) | |
tree | 8d125de0b4a1c9d608ddae6ff927fc3624663bd0 | |
parent | 2fc77d271db27ecb140191c2dfafdba835962ffb (diff) |
Split out reusable parts into the laks project.
-rw-r--r-- | .gitmodules | 3 | ||||
-rw-r--r-- | SConstruct | 31 | ||||
-rw-r--r-- | drivers/gps.h | 10 | ||||
-rw-r--r-- | drivers/l3gd20.h | 4 | ||||
-rw-r--r-- | drivers/lsm303dlm.h | 2 | ||||
-rw-r--r-- | drivers/ppmsum.cpp | 2 | ||||
-rw-r--r-- | drivers/ppmsum.h | 4 | ||||
-rw-r--r-- | drivers/xbee.cpp | 4 | ||||
-rw-r--r-- | entry.cpp | 63 | ||||
-rw-r--r-- | hal/fault.cpp | 41 | ||||
-rw-r--r-- | hal/flash.cpp | 17 | ||||
-rw-r--r-- | hal/flash.h | 30 | ||||
-rw-r--r-- | hal/gpio.h | 43 | ||||
-rw-r--r-- | hal/hal.h | 10 | ||||
-rw-r--r-- | hal/i2c.cpp | 142 | ||||
-rw-r--r-- | hal/i2c.h | 62 | ||||
-rw-r--r-- | hal/interrupt.cpp | 187 | ||||
-rw-r--r-- | hal/interrupt.h | 121 | ||||
-rw-r--r-- | hal/pin.h | 137 | ||||
-rw-r--r-- | hal/rcc.cpp | 51 | ||||
-rw-r--r-- | hal/rcc.h | 217 | ||||
-rw-r--r-- | hal/spi.h | 31 | ||||
-rw-r--r-- | hal/stm32.h | 89 | ||||
-rw-r--r-- | hal/timer.h | 40 | ||||
-rw-r--r-- | hal/usart.cpp | 7 | ||||
-rw-r--r-- | hal/usart.h | 69 | ||||
-rw-r--r-- | hal/usb.h | 93 | ||||
m--------- | laks | 0 | ||||
-rw-r--r-- | main.cpp | 15 | ||||
-rw-r--r-- | openocd.cfg | 23 | ||||
-rw-r--r-- | os/mutex.h | 42 | ||||
-rw-r--r-- | os/pool.cpp | 5 | ||||
-rw-r--r-- | os/pool.h | 146 | ||||
-rw-r--r-- | os/thread.cpp | 4 | ||||
-rw-r--r-- | os/thread.h | 63 | ||||
-rw-r--r-- | os/time.cpp | 3 | ||||
-rw-r--r-- | os/time.h | 23 | ||||
-rw-r--r-- | suzumebachi.ld | 83 |
38 files changed, 29 insertions, 1888 deletions
diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..d59e290 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "laks"] + path = laks + url = git://git.jvnv.net/laks @@ -2,33 +2,14 @@ import os env = Environment(
ENV = os.environ,
-
- CC = 'arm-none-eabi-gcc',
- CXX = 'arm-none-eabi-g++',
- AS = 'arm-none-eabi-gcc',
- CCFLAGS = '-O2 -Wall -ggdb -mcpu=cortex-m4 -mthumb -mhard-float -ffunction-sections -Wno-pmf-conversions',
- CXXFLAGS = '-fno-exceptions -fno-rtti',
- ASFLAGS = '-c -x assembler-with-cpp -mcpu=cortex-m4 -mthumb -mhard-float',
-
- CPPDEFINES = ['STM32F4'],
-
- LINK = 'arm-none-eabi-gcc',
- LINKFLAGS = '-Wall -mcpu=cortex-m4 -mthumb -mhard-float -nostartfiles -Wl,-Tsuzumebachi.ld', # -Wl,--gc-sections
-
- AR = 'arm-none-eabi-ar',
- RANLIB = 'arm-none-eabi-ranlib',
-
- CPPPATH = ['os', 'hal', 'drivers'],
- #LIBPATH = [],
-
- LIBS = ['m'],
)
-sources = Glob('os/*.cpp') + Glob('hal/*.cpp') + Glob('drivers/*.cpp') + Glob('*.cpp')
+SConscript('laks/build_rules')
-firmware = env.Program('suzumebachi.elf', sources)
-env.Depends(firmware, 'suzumebachi.ld')
+env.SelectMCU('stm32f405rg')
-env.Command('prog', ['suzumebachi.elf'], 'openocd -f openocd.cfg -c flash_chip')
+env.Append(
+ CPPPATH = ['drivers'],
+)
-Default('suzumebachi.elf')
+env.Firmware('suzumebachi.elf', Glob('*.cpp') + Glob('drivers/*.cpp'))
diff --git a/drivers/gps.h b/drivers/gps.h index 16a971b..2fcbf6d 100644 --- a/drivers/gps.h +++ b/drivers/gps.h @@ -1,12 +1,12 @@ #ifndef GPS_H #define GPS_H -#include "rcc.h" -#include "usart.h" -#include "interrupt.h" -#include "thread.h" +#include <rcc/rcc.h> +#include <usart/usart.h> +#include <interrupt/interrupt.h> +#include <os/thread.h> -#include "pool.h" +#include <os/pool.h> struct GPSMsg { unsigned int n; diff --git a/drivers/l3gd20.h b/drivers/l3gd20.h index c7e8935..56dff08 100644 --- a/drivers/l3gd20.h +++ b/drivers/l3gd20.h @@ -1,8 +1,8 @@ #ifndef L3GD20_H #define L3GD20_H -#include "pin.h" -#include "spi.h" +#include <gpio/pin.h> +#include <spi/spi.h> class L3GD20 { private: diff --git a/drivers/lsm303dlm.h b/drivers/lsm303dlm.h index 1c4956d..8d25b38 100644 --- a/drivers/lsm303dlm.h +++ b/drivers/lsm303dlm.h @@ -1,7 +1,7 @@ #ifndef LSM303DLM_H #define LSM303DLM_H -#include "i2c.h" +#include <i2c/i2c.h> class LSM303DLM_A { private: diff --git a/drivers/ppmsum.cpp b/drivers/ppmsum.cpp index c1bd101..24d62ac 100644 --- a/drivers/ppmsum.cpp +++ b/drivers/ppmsum.cpp @@ -1,6 +1,6 @@ #include "ppmsum.h" -#include "rcc.h" +#include <rcc/rcc.h> PPMSum* PPMSum::self = 0; diff --git a/drivers/ppmsum.h b/drivers/ppmsum.h index a522b57..98c2984 100644 --- a/drivers/ppmsum.h +++ b/drivers/ppmsum.h @@ -2,8 +2,8 @@ #define PPMSUM_H #include <stdint.h> -#include "timer.h" -#include "interrupt.h" +#include <timer/timer.h> +#include <interrupt/interrupt.h> class PPMSum { friend void interrupt<Interrupt::TIM2>(); diff --git a/drivers/xbee.cpp b/drivers/xbee.cpp index efee619..d23903b 100644 --- a/drivers/xbee.cpp +++ b/drivers/xbee.cpp @@ -1,7 +1,7 @@ #include "xbee.h" -#include "usart.h" -#include "mutex.h" +#include <usart/usart.h> +#include <os/mutex.h> Mutex xbee_mutex; diff --git a/entry.cpp b/entry.cpp deleted file mode 100644 index ae58404..0000000 --- a/entry.cpp +++ /dev/null @@ -1,63 +0,0 @@ -#include <stdint.h> -#include <hal.h> - -int main(); - -typedef void (*funcp_t)(); - -// Symbols from linker script. -extern uint32_t _data_rom; -extern uint32_t _data_start; -extern uint32_t _data_end; -extern uint32_t _bss_start; -extern uint32_t _bss_end; -extern funcp_t _init_array_start; -extern funcp_t _init_array_end; -extern funcp_t _fini_array_start; -extern funcp_t _fini_array_end; - -void __attribute__((naked)) entry() { - // Initialize HAL. - hal_init(); - - // Load .data from rom image. - uint32_t* rp = &_data_rom; - uint32_t* wp = &_data_start; - - while(wp < &_data_end) { - *wp++ = *rp++; - } - - // Clear .bss. - wp = &_bss_start; - - while(wp < &_bss_end) { - *wp++ = 0; - } - - // Call constructors. - funcp_t* fp = &_init_array_start; - - while(fp < &_init_array_end) { - (*fp++)(); - } - - // Call main(). - main(); - - // Call destructors. - fp = &_fini_array_start; - - while(fp < &_fini_array_end) { - (*fp++)(); - } - - // Halt. - while(1); -} - -extern "C" void __cxa_pure_virtual() { - while (1); -} - -void* __dso_handle = 0; diff --git a/hal/fault.cpp b/hal/fault.cpp deleted file mode 100644 index a176ae6..0000000 --- a/hal/fault.cpp +++ /dev/null @@ -1,41 +0,0 @@ -#include "interrupt.h" -#include "thread.h" -#include "time.h" - -inline void __attribute__((naked)) switch_context() { - asm volatile ("cpsid i"); - - // Save unsaved registers. - asm volatile ("push {r4, r5, r6, r7, r8, r9, r10, r11, lr}" ::: "memory"); - - // Store stack pointer for old thread. - asm volatile ("str sp, [%0]" :: "r" (&Thread::active_thread->sp)); - - // Update running thread. - Thread::active_thread = Thread::active_thread->next; - - // Fetch stack pointer for new thread. - asm volatile ("ldr sp, [%0]" :: "r" (&Thread::active_thread->sp)); - - asm volatile ("cpsie i"); - - // Load registers and return. - asm volatile ("pop {r4, r5, r6, r7, r8, r9, r10, r11, pc}" ::: "memory"); -} - -template<> -void interrupt<Interrupt::SVCall>() { - switch_context(); -} - -template<> -void interrupt<Interrupt::SysTick>() { - Time::tick(); -} - -template<> void interrupt<Interrupt::NMI>() { while(1); } -template<> void interrupt<Interrupt::HardFault>() { while(1); } -template<> void interrupt<Interrupt::MemManage>() { while(1); } -template<> void interrupt<Interrupt::BusFault>() { while(1); } -template<> void interrupt<Interrupt::UsageFault>() { while(1); } -template<> void interrupt<Interrupt::PendSV>() { while(1); } diff --git a/hal/flash.cpp b/hal/flash.cpp deleted file mode 100644 index 2b0fb69..0000000 --- a/hal/flash.cpp +++ /dev/null @@ -1,17 +0,0 @@ -#include "flash.h" - -void flash_init() { - #if defined(STM32F1) - - // Set flash latency. - FLASH.ACR = 0x12; - - #elif defined(STM32F4) - - // Set flash latency. - FLASH.ACR = 0x105; - - while(FLASH.ACR != 0x105); - - #endif -} diff --git a/hal/flash.h b/hal/flash.h deleted file mode 100644 index 30d30a5..0000000 --- a/hal/flash.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef FLASH_H -#define FLASH_H - -#include <stdint.h> - -struct FLASH_t { - volatile uint32_t ACR; - volatile uint32_t KEYR; - volatile uint32_t OPTKEYR; - volatile uint32_t SR; - volatile uint32_t CR; - #if defined(STM32F1) - volatile uint32_t AR; - volatile uint32_t RESERVED; - volatile uint32_t OBR; - volatile uint32_t WRPR; - #elif defined(STM32F4) - volatile uint32_t OPTCR; - #endif -}; - -#if defined(STM32F1) -static FLASH_t& FLASH = *(FLASH_t*)0x40022000; -#elif defined(STM32F4) -static FLASH_t& FLASH = *(FLASH_t*)0x40023c00; -#endif - -void flash_init(); - -#endif diff --git a/hal/gpio.h b/hal/gpio.h deleted file mode 100644 index 324950e..0000000 --- a/hal/gpio.h +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef GPIO_H -#define GPIO_H - -struct GPIO_t { - #if defined(STM32F1) - volatile uint32_t CRL; - volatile uint32_t CRH; - volatile uint32_t IDR; - volatile uint32_t ODR; - volatile uint32_t BSRR; - volatile uint32_t BRR; - volatile uint32_t LCKR; - #elif defined(STM32F4) - volatile uint32_t MODER; - volatile uint32_t OTYPER; - volatile uint32_t OSPEEDER; - volatile uint32_t PUPDR; - volatile uint32_t IDR; - volatile uint32_t ODR; - volatile uint32_t BSRR; - volatile uint32_t LCKR; - volatile uint32_t AFRL; - volatile uint32_t AFRH; - #endif -}; - -#if defined(STM32F1) -static GPIO_t& GPIOA = *(GPIO_t*)0x40010800; -static GPIO_t& GPIOB = *(GPIO_t*)0x40010c00; -static GPIO_t& GPIOC = *(GPIO_t*)0x40011000; -#elif defined(STM32F4) -static GPIO_t& GPIOA = *(GPIO_t*)0x40020000; -static GPIO_t& GPIOB = *(GPIO_t*)0x40020400; -static GPIO_t& GPIOC = *(GPIO_t*)0x40020800; -static GPIO_t& GPIOD = *(GPIO_t*)0x40020c00; -static GPIO_t& GPIOE = *(GPIO_t*)0x40021000; -static GPIO_t& GPIOF = *(GPIO_t*)0x40021400; -static GPIO_t& GPIOG = *(GPIO_t*)0x40021800; -static GPIO_t& GPIOH = *(GPIO_t*)0x40021c00; -static GPIO_t& GPIOI = *(GPIO_t*)0x40022000; -#endif - -#endif diff --git a/hal/hal.h b/hal/hal.h deleted file mode 100644 index 4076df3..0000000 --- a/hal/hal.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef HAL_H -#define HAL_H - -#include "rcc.h" - -void hal_init() { - rcc_init(); -} - -#endif diff --git a/hal/i2c.cpp b/hal/i2c.cpp deleted file mode 100644 index db9c919..0000000 --- a/hal/i2c.cpp +++ /dev/null @@ -1,142 +0,0 @@ -#include "i2c.h" - -#include "rcc.h" -#include "thread.h" - -#if defined(STM32F1) -I2C_t I2C1(0x40005400, 36000000, Interrupt::I2C1_EV, Interrupt::I2C1_ER); -I2C_t I2C2(0x40005800, 36000000, Interrupt::I2C2_EV, Interrupt::I2C2_ER); -#elif defined(STM32F4) -I2C_t I2C1(0x40005400, 42000000, Interrupt::I2C1_EV, Interrupt::I2C1_ER); -I2C_t I2C2(0x40005800, 42000000, Interrupt::I2C2_EV, Interrupt::I2C2_ER); -//I2C_t I2C3(0x40005c00, 42000000, Interrupt::I2C3_EV, Interrupt::I2C3_ER); -#endif - -void I2C_t::irq_ev() { - uint32_t sr1 = reg.SR1; - reg.SR2; - - // EV5, SB = 1: Start condition sent. - if(sr1 & 0x01) { - // Send address. - reg.DR = (addr << 1) | (writing ? 0 : 1); - } - - // EV6, ADDR = 1: Address sent. - if(sr1 & 0x02) { - if(writing) { - reg.DR = *write_p++; - writing--; - } else { - if(reading > 1) { - reg.CR1 |= 0x400; // Set ACK. - } else { - reg.CR1 |= 0x200; // Set STOP. - } - } - } - - // EV7, RxNE = 1: Receive buffer not empty. - if(sr1 & 0x40) { - *read_p++ = reg.DR; - reading--; - - if(reading == 1) { - // Unset ACK, set STOP. - reg.CR1 = (reg.CR1 & ~0x400) | 0x200; - } - - if(reading == 0) { - busy = 0; - } - } - - //reg.CR1 &= ~0x400; - - // EV8, TxE = 1, BTF = 0: Transmit buffer empty, still writing. - if(sr1 & 0x80 && !(sr1 & 0x04)) { - if(writing) { - // Send data. - reg.DR = *write_p++; - writing--; - } else { - // All data sent. - - if(reading) { - // Send repeat start. - reg.CR1 |= 0x100; - } else { - // Send stop. - reg.CR1 |= 0x200; - busy = 0; - } - } - } -} - -void I2C_t::irq_er() { - handle_error(); -} - -void I2C_t::handle_error() { - reg.SR1; - reg.SR2; - - //while(1); - reg.CR1 |= 0x200; - busy = 0; -} - -void I2C_t::enable(Pin& scl, Pin& sda) { - RCC.enable(RCC.I2C1); - asm volatile("nop"); - - scl.set_af(4); - sda.set_af(4); - scl.set_type(Pin::OpenDrain); - sda.set_type(Pin::OpenDrain); - scl.set_mode(Pin::AF); - sda.set_mode(Pin::AF); - - reg.CR1 = 0x8000; - reg.CR1 = 0; - - reg.CR2 = 0x700 | (clk / 1000000); - reg.TRISE = clk / 1000000 + 1; - reg.CCR = clk / 2 / 100000; - - Interrupt::enable(irq_ev_n, &I2C_t::irq_ev, this); - Interrupt::enable(irq_er_n, &I2C_t::irq_er, this); - - reg.CR1 = 1; -} - -void I2C_t::write_reg(uint8_t addr_, uint8_t reg_, uint8_t data) { - addr = addr_; - writing = 2; - reading = 0; - volatile uint8_t buf[] = {reg_, data}; - write_p = buf; - busy = 1; - - reg.CR1 |= 0x100; - - while(busy) { - Thread::yield(); - } -} - -void I2C_t::read_reg(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) { - addr = addr_; - writing = 1; - reading = len; - write_p = ®_; - read_p = buf; - busy = 1; - - reg.CR1 |= 0x100; - - while(busy) { - Thread::yield(); - } -} diff --git a/hal/i2c.h b/hal/i2c.h deleted file mode 100644 index a61950c..0000000 --- a/hal/i2c.h +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef I2C_H -#define I2C_H - -#include <stdint.h> -#include "interrupt.h" -#include "pin.h" - -struct I2C_reg_t { - volatile uint32_t CR1; - volatile uint32_t CR2; - volatile uint32_t OAR1; - volatile uint32_t OAR2; - volatile uint32_t DR; - volatile uint32_t SR1; - volatile uint32_t SR2; - volatile uint32_t CCR; - volatile uint32_t TRISE; -}; - -class I2C_t { - private: - volatile uint8_t addr; - volatile uint8_t writing; - volatile uint8_t reading; - volatile uint8_t* write_p; - volatile uint8_t* read_p; - - volatile bool busy; - - public: - I2C_reg_t& reg; - const uint32_t clk; - Interrupt::IRQ irq_ev_n; - Interrupt::IRQ irq_er_n; - - I2C_t(uint32_t reg_addr, uint32_t bus_clk, Interrupt::IRQ ev_n, Interrupt::IRQ er_n) : reg(*(I2C_reg_t*)reg_addr), clk(bus_clk), irq_ev_n(ev_n), irq_er_n(er_n) { - reading = writing = 0; - } - - void irq_ev(); - void irq_er(); - - void handle_error(); - - void enable(Pin& scl, Pin& sda); - - void write_reg(uint8_t addr_, uint8_t reg_, uint8_t data); - void read_reg(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf); -}; - -#if defined(STM32F1) -extern I2C_t I2C1; -extern I2C_t I2C2; -#elif defined(STM32F4) -extern I2C_t I2C1; -extern I2C_t I2C2; -extern I2C_t I2C3; -#endif - -typedef I2C_t I2C; - -#endif diff --git a/hal/interrupt.cpp b/hal/interrupt.cpp deleted file mode 100644 index cebfed7..0000000 --- a/hal/interrupt.cpp +++ /dev/null @@ -1,187 +0,0 @@ -#include "interrupt.h" - -namespace Interrupt { - MFP mf_vectors[16 + NUM_IRQs]; -}; - -void entry(); - -void member_function_interrupt_gate() { - uint32_t interrupt_num; - asm ("mrs %0, ipsr" : "=r" (interrupt_num)); - - Interrupt::mf_vectors[interrupt_num].func_p(Interrupt::mf_vectors[interrupt_num].instance_p); -} - -extern "C" void unused_interrupt() { - member_function_interrupt_gate(); - //while(1); -} - -template<> void interrupt<Interrupt::NMI>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::HardFault>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::MemManage>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::BusFault>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::UsageFault>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SVCall>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::PendSV>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SysTick>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::WWDG>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::PVD>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TAMPER>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::RTC>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::FLASH>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::RCC>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI0>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI4>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel4>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel5>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel6>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA1_Channel7>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::ADC1_2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USB_HP_CAN_TX>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USB_LP_CAN_RX0>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::CAN_RX1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::CAN_SCE>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI9_5>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM1_BRK>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM1_UP>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM1_TRG_COM>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM1_CC>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM4>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::I2C1_EV>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::I2C1_ER>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::I2C2_EV>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::I2C2_ER>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SPI1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SPI2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USART1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USART2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USART3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::EXTI15_10>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::RTCAlarm>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::USBWakeup>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM8_BRK>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM8_UP>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM8_TRG_COM>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM8_CC>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::ADC3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::FSMC>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SDIO>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM5>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::SPI3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::UART4>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::UART5>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM6>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::TIM7>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA2_Channel1>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA2_Channel2>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA2_Channel3>() __attribute__ ((weak, alias ("unused_interrupt"))); -template<> void interrupt<Interrupt::DMA2_Channel4_5>() __attribute__ ((weak, alias ("unused_interrupt"))); - -typedef void (*vector_t)(); - -vector_t vectors[] __attribute__((section(".vectors"))) = { - (vector_t)0x20004ffc, - entry, - interrupt<Interrupt::NMI>, - interrupt<Interrupt::HardFault>, - interrupt<Interrupt::MemManage>, - interrupt<Interrupt::BusFault>, - interrupt<Interrupt::UsageFault>, - 0, - 0, - 0, - 0, - interrupt<Interrupt::SVCall>, - 0, - 0, - interrupt<Interrupt::PendSV>, - interrupt<Interrupt::SysTick>, - interrupt<Interrupt::WWDG>, - interrupt<Interrupt::PVD>, - interrupt<Interrupt::TAMPER>, - interrupt<Interrupt::RTC>, - interrupt<Interrupt::FLASH>, - interrupt<Interrupt::RCC>, - interrupt<Interrupt::EXTI0>, - interrupt<Interrupt::EXTI1>, - interrupt<Interrupt::EXTI2>, - interrupt<Interrupt::EXTI3>, - interrupt<Interrupt::EXTI4>, - interrupt<Interrupt::DMA1_Channel1>, - interrupt<Interrupt::DMA1_Channel2>, - interrupt<Interrupt::DMA1_Channel3>, - interrupt<Interrupt::DMA1_Channel4>, - interrupt<Interrupt::DMA1_Channel5>, - interrupt<Interrupt::DMA1_Channel6>, - interrupt<Interrupt::DMA1_Channel7>, - interrupt<Interrupt::ADC1_2>, - interrupt<Interrupt::USB_HP_CAN_TX>, - interrupt<Interrupt::USB_LP_CAN_RX0>, - interrupt<Interrupt::CAN_RX1>, - interrupt<Interrupt::CAN_SCE>, - interrupt<Interrupt::EXTI9_5>, - interrupt<Interrupt::TIM1_BRK>, - interrupt<Interrupt::TIM1_UP>, - interrupt<Interrupt::TIM1_TRG_COM>, - interrupt<Interrupt::TIM1_CC>, - interrupt<Interrupt::TIM2>, - interrupt<Interrupt::TIM3>, - interrupt<Interrupt::TIM4>, - interrupt<Interrupt::I2C1_EV>, - interrupt<Interrupt::I2C1_ER>, - interrupt<Interrupt::I2C2_EV>, - interrupt<Interrupt::I2C2_ER>, - interrupt<Interrupt::SPI1>, - interrupt<Interrupt::SPI2>, - interrupt<Interrupt::USART1>, - interrupt<Interrupt::USART2>, - interrupt<Interrupt::USART3>, - interrupt<Interrupt::EXTI15_10>, - interrupt<Interrupt::RTCAlarm>, - interrupt<Interrupt::USBWakeup>, - interrupt<Interrupt::TIM8_BRK>, - interrupt<Interrupt::TIM8_UP>, - interrupt<Interrupt::TIM8_TRG_COM>, - interrupt<Interrupt::TIM8_CC>, - interrupt<Interrupt::ADC3>, - interrupt<Interrupt::FSMC>, - interrupt<Interrupt::SDIO>, - interrupt<Interrupt::TIM5>, - interrupt<Interrupt::SPI3>, - interrupt<Interrupt::UART4>, - interrupt<Interrupt::UART5>, - interrupt<Interrupt::TIM6>, - interrupt<Interrupt::TIM7>, - interrupt<Interrupt::DMA2_Channel1>, - interrupt<Interrupt::DMA2_Channel2>, - interrupt<Interrupt::DMA2_Channel3>, - interrupt<Interrupt::DMA2_Channel4_5>, - 0, // 60 - 0, // 61 - 0, // 62 - 0, // 63 - 0, // 64 - 0, // 65 - 0, // 66 - 0, // 67 - 0, // 68 - 0, // 69 - 0, // 70 - 0, // 71 - 0, // 72 - 0, // 73 - 0, // 74 - 0, // 75 - 0, // 76 - interrupt<(Interrupt::IRQ)77>, // 77 -}; diff --git a/hal/interrupt.h b/hal/interrupt.h deleted file mode 100644 index 34651f2..0000000 --- a/hal/interrupt.h +++ /dev/null @@ -1,121 +0,0 @@ -#ifndef INTERRUPT_H -#define INTERRUPT_H - -#include "stm32.h |