From 2fa9b4de82e67849532475016a339bc1e6e44fd6 Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Thu, 17 Apr 2014 19:40:22 +0200 Subject: [PATCH] cpu: Initial import of stm32f4 --- cpu/stm32f4/Makefile | 7 + cpu/stm32f4/Makefile.include | 28 + cpu/stm32f4/cpu.c | 150 + cpu/stm32f4/hwtimer_arch.c | 77 + cpu/stm32f4/include/cpu-conf.h | 55 + cpu/stm32f4/include/hwtimer_cpu.h | 32 + cpu/stm32f4/include/stm32f407xx.h | 7952 +++++++++++++++++++++++ cpu/stm32f4/io_arch.c | 31 + cpu/stm32f4/lpm_arch.c | 53 + cpu/stm32f4/periph/Makefile | 3 + cpu/stm32f4/periph/gpio.c | 758 +++ cpu/stm32f4/periph/timer.c | 335 + cpu/stm32f4/periph/uart.c | 313 + cpu/stm32f4/reboot_arch.c | 34 + cpu/stm32f4/startup.c | 307 + cpu/stm32f4/stm32f407vg_linkerscript.ld | 144 + cpu/stm32f4/syscalls.c | 271 + 17 files changed, 10550 insertions(+) create mode 100644 cpu/stm32f4/Makefile create mode 100644 cpu/stm32f4/Makefile.include create mode 100644 cpu/stm32f4/cpu.c create mode 100644 cpu/stm32f4/hwtimer_arch.c create mode 100644 cpu/stm32f4/include/cpu-conf.h create mode 100644 cpu/stm32f4/include/hwtimer_cpu.h create mode 100644 cpu/stm32f4/include/stm32f407xx.h create mode 100644 cpu/stm32f4/io_arch.c create mode 100644 cpu/stm32f4/lpm_arch.c create mode 100644 cpu/stm32f4/periph/Makefile create mode 100644 cpu/stm32f4/periph/gpio.c create mode 100644 cpu/stm32f4/periph/timer.c create mode 100644 cpu/stm32f4/periph/uart.c create mode 100644 cpu/stm32f4/reboot_arch.c create mode 100644 cpu/stm32f4/startup.c create mode 100644 cpu/stm32f4/stm32f407vg_linkerscript.ld create mode 100644 cpu/stm32f4/syscalls.c diff --git a/cpu/stm32f4/Makefile b/cpu/stm32f4/Makefile new file mode 100644 index 000000000..9311ee74b --- /dev/null +++ b/cpu/stm32f4/Makefile @@ -0,0 +1,7 @@ +# define the module that is build +MODULE = cpu + +# add a list of subdirectories, that should also be build +DIRS = periph $(CORTEX_M4_COMMON) + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f4/Makefile.include b/cpu/stm32f4/Makefile.include new file mode 100644 index 000000000..511a37959 --- /dev/null +++ b/cpu/stm32f4/Makefile.include @@ -0,0 +1,28 @@ +# this CPU implementation is using the explicit core/CPU interface +export CFLAGS += -DCOREIF_NG=1 + +# export the peripheral drivers to be linked into the final binary +export USEMODULE += periph + +# tell the build system that the CPU depends on the Cortex-M common files +export USEMODULE += cortex-m4_common + +# define path to cortex-m common module, which is needed for this CPU +export CORTEX_M4_COMMON = $(RIOTCPU)/cortex-m4_common/ + +# CPU depends on the cortex-m common module, so include it +include $(CORTEX_M4_COMMON)Makefile.include + +# define the linker script to use for this CPU +export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld + +#export the CPU model +MODEL = $(shell echo $(CPU_MODEL)|tr 'a-z' 'A-Z') +export CFLAGS += -DCPU_MODEL_$(MODEL) + +# include CPU specific includes +export INCLUDES += -I$(RIOTCPU)/$(CPU)/include + +# add the CPU specific system calls implementations for the linker +export UNDEF += $(BINDIR)cpu/syscalls.o +export UNDEF += $(BINDIR)cpu/startup.o diff --git a/cpu/stm32f4/cpu.c b/cpu/stm32f4/cpu.c new file mode 100644 index 000000000..588f66ad6 --- /dev/null +++ b/cpu/stm32f4/cpu.c @@ -0,0 +1,150 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Implementation of the CPU initialization + * + * @author Hauke Petersen + * @} + */ + +#include +#include "cpu.h" +#include "periph_conf.h" + +/** + * @name Pattern to write into the Coprocessor Access Control Register to allow full FPU access + */ +#define FULL_FPU_ACCESS (0x00f00000) + + +static void cpu_clock_init(void); + +/** + * @brief Initialize the CPU, set IRQ priorities + */ +void cpu_init(void) +{ + /* give full access to the FPU */ + SCB->CPACR |= (uint32_t)FULL_FPU_ACCESS; + + /* configure the vector table location to internal flash */ + SCB->VTOR = FLASH_BASE; + + /* initialize the clock system */ + cpu_clock_init(); + + /* set pendSV interrupt to lowest possible priority */ + NVIC_SetPriority(PendSV_IRQn, 0xff); +} + +/** + * @brief Configure the controllers clock system + * + * The clock initialization make the following assumptions: + * - the external HSE clock from an external oscillator is used as base clock + * - the internal PLL circuit is used for clock refinement + * + * Use the following formulas to calculate the needed values: + * + * SYSCLK = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_P + * USB, SDIO and RNG Clock = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_Q + * + * The actual used values are specified in the board's `periph_conf.h` file. + * + * NOTE: currently there is not timeout for initialization of PLL and other locks + * -> when wrong values are chosen, the initialization could stall + */ +static void cpu_clock_init(void) +{ + /* configure the HSE clock */ + + /* enable the HSI clock */ + RCC->CR |= RCC_CR_HSION; + + /* reset clock configuration register */ + RCC->CFGR = 0; + + /* disable HSE, CSS and PLL */ + RCC->CR &= ~(RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON | RCC_CR_PLLON); + + /* disable all clock interrupts */ + RCC->CIR = 0; + + /* enable the HSE clock */ + RCC->CR |= RCC_CR_HSEON; + + /* wait for HSE to be ready */ + while (!(RCC->CR & RCC_CR_HSERDY)); + + /* setup power module */ + + /* enable the power module */ + RCC->APB1ENR |= RCC_APB1ENR_PWREN; + /* set the voltage scaling to 1 to enable the maximum frequency */ + PWR->CR |= PWR_CR_VOS_1; + + /* setup the peripheral bus prescalers */ + + /* set the AHB clock divider */ + RCC->CFGR &= ~RCC_CFGR_HPRE; + RCC->CFGR |= CLOCK_AHB_DIV; + /* set the APB2 (high speed) bus clock divider */ + RCC->CFGR &= ~RCC_CFGR_PPRE2; + RCC->CFGR |= CLOCK_APB2_DIV; + /* set the APB1 (low speed) bus clock divider */ + RCC->CFGR &= ~RCC_CFGR_PPRE1; + RCC->CFGR |= CLOCK_APB1_DIV; + + /* configure the PLL */ + + /* reset PLL config register */ + RCC->PLLCFGR = 0; + /* set HSE as source for the PLL */ + RCC->PLLCFGR |= RCC_PLLCFGR_PLLSRC_HSE; + /* set division factor for main PLL input clock */ + RCC->PLLCFGR |= (CLOCK_PLL_M & 0x3F); + /* set main PLL multiplication factor for VCO */ + RCC->PLLCFGR |= (CLOCK_PLL_N & 0x1FF) << 6; + /* set main PLL division factor for main system clock */ + RCC->PLLCFGR |= (((CLOCK_PLL_P & 0x03) >> 1) - 1) << 16; + /* set main PLL division factor for USB OTG FS, SDIO and RNG clocks */ + RCC->PLLCFGR |= (CLOCK_PLL_Q & 0x0F) << 24; + + /* enable PLL again */ + RCC->CR |= RCC_CR_PLLON; + /* wait until PLL is stable */ + while(!(RCC->CR & RCC_CR_PLLRDY)); + + /* configure flash latency */ + + /* reset flash access control register */ + FLASH->ACR = 0; + /* enable instruction cache */ + FLASH->ACR |= FLASH_ACR_ICEN; + /* enable data cache */ + FLASH->ACR |= FLASH_ACR_DCEN; + /* enable pre-fetch buffer */ + // FLASH->ACR |= FLASH_ACR_PRFTEN; + /* set flash latency */ + FLASH->ACR &= ~FLASH_ACR_LATENCY; + FLASH->ACR |= CLOCK_FLASH_LATENCY; + + /* configure the sysclock and the peripheral clocks */ + + /* set sysclock to be driven by the PLL clock */ + RCC->CFGR &= ~RCC_CFGR_SW; + RCC->CFGR |= RCC_CFGR_SW_PLL; + + /* wait for sysclock to be stable */ + while (!(RCC->CFGR & RCC_CFGR_SWS_PLL)); +} diff --git a/cpu/stm32f4/hwtimer_arch.c b/cpu/stm32f4/hwtimer_arch.c new file mode 100644 index 000000000..d2ac531d5 --- /dev/null +++ b/cpu/stm32f4/hwtimer_arch.c @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Implementation of the kernels hwtimer interface + * + * @author Hauke Petersen + * + * @} + */ + +#include "arch/hwtimer_arch.h" +#include "board.h" +#include "periph/timer.h" +#include "thread.h" + +/** + * @brief Callback function that is given to the low-level timer + * + * @param[in] channel the channel of the low-level timer that was triggered + */ +void irq_handler(int channel); + +/** + * @brief Hold a reference to the hwtimer callback + */ +void (*timeout_handler)(int); + +void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu) +{ + timeout_handler = handler; + timer_init(HW_TIMER, 1, &irq_handler); +} + +void hwtimer_arch_enable_interrupt(void) +{ + timer_irq_enable(HW_TIMER); +} + +void hwtimer_arch_disable_interrupt(void) +{ + timer_irq_disable(HW_TIMER); +} + +void hwtimer_arch_set(unsigned long offset, short timer) +{ + timer_set(HW_TIMER, timer, offset); +} + +void hwtimer_arch_set_absolute(unsigned long value, short timer) +{ + timer_set_absolute(HW_TIMER, timer, value); +} + +void hwtimer_arch_unset(short timer) +{ + timer_clear(HW_TIMER, timer); +} + +unsigned long hwtimer_arch_now(void) +{ + return timer_read(HW_TIMER); +} + +void irq_handler(int channel) +{ + timeout_handler((short)(channel)); +} diff --git a/cpu/stm32f4/include/cpu-conf.h b/cpu/stm32f4/include/cpu-conf.h new file mode 100644 index 000000000..61b0a6564 --- /dev/null +++ b/cpu/stm32f4/include/cpu-conf.h @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @defgroup cpu_stm32f4 STM32F4 + * @ingroup cpu + * @brief CPU specific implementations for the STM32F4 + * @{ + * + * @file + * @brief Implementation specific CPU configuration options + * + * @author Hauke Petersen + */ + +#ifndef __CPU_CONF_H +#define __CPU_CONF_H + +#ifdef CPU_MODEL_STM32F407VG +#include "stm32f407xx.h" +#endif + +/** + * @name Kernel configuration + * + * TODO: measure and adjust for the Cortex-M4f + * @{ + */ +#define KERNEL_CONF_STACKSIZE_PRINTF (2500) + +#ifndef KERNEL_CONF_STACKSIZE_DEFAULT +#define KERNEL_CONF_STACKSIZE_DEFAULT (2500) +#endif + +#define KERNEL_CONF_STACKSIZE_IDLE (512) +/** @} */ + +/** + * @name UART0 buffer size definition for compatibility reasons + * + * TODO: remove once the remodeling of the uart0 driver is done + * @{ + */ +#ifndef UART0_BUFSIZE +#define UART0_BUFSIZE (128) +#endif +/** @} */ + +#endif /* __CPU_CONF_H */ +/** @} */ diff --git a/cpu/stm32f4/include/hwtimer_cpu.h b/cpu/stm32f4/include/hwtimer_cpu.h new file mode 100644 index 000000000..498cb7864 --- /dev/null +++ b/cpu/stm32f4/include/hwtimer_cpu.h @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief CPU specific hwtimer configuration options + * + * @author Hauke Petersen + */ + +#ifndef __HWTIMER_CPU_H +#define __HWTIMER_CPU_H + +/** + * @name Hardware timer configuration + * @{ + */ +#define HWTIMER_MAXTIMERS 4 /**< the CPU implementation supports 4 HW timers */ +#define HWTIMER_SPEED 1000000 /**< the HW timer runs with 1MHz */ +#define HWTIMER_MAXTICKS (0xFFFFFFFF) /**< 32-bit timer */ +/** @} */ + +#endif /* __HWTIMER_CPU_H */ +/** @} */ diff --git a/cpu/stm32f4/include/stm32f407xx.h b/cpu/stm32f4/include/stm32f407xx.h new file mode 100644 index 000000000..a6dcb99df --- /dev/null +++ b/cpu/stm32f4/include/stm32f407xx.h @@ -0,0 +1,7952 @@ +/** + ****************************************************************************** + * @file stm32f407xx.h + * @author MCD Application Team + * @version V2.1.0 + * @date 19-June-2014 + * @brief CMSIS STM32F407xx Device Peripheral Access Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2014 STMicroelectronics

+ * + * 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 stm32f407xx + * @{ + */ + +#ifndef __STM32F407xx_H +#define __STM32F407xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M4 Processor and Core Peripherals + */ +#define __CM4_REV 0x0001 /*!< Core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */ +#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1 /*!< FPU present */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F4XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ + DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ + DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ + DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ + DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ + DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ + DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ + ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ + CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ + CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global interrupt */ + DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ + DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ + DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ + DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ + DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + DCMI_IRQn = 78, /*!< DCMI global interrupt */ + HASH_RNG_IRQn = 80, /*!< Hash and RNG global interrupt */ + FPU_IRQn = 81 /*!< FPU global interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ + __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ + __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ + __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ + __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ + __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ + __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ + __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + __IO uint32_t TDLR; /*!< CAN mailbox data low register */ + __IO uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ + __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CAN_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DCMI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ + __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ + __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ + __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ + __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ + __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ + __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ + __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ + __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ + __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ + __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ +} DCMI_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA stream x configuration register */ + __IO uint32_t NDTR; /*!< DMA stream x number of data register */ + __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ + __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ + __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ + __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ +} DMA_Stream_TypeDef; + +typedef struct +{ + __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ + __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ + __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ + __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ +} DMA_TypeDef; + + +/** + * @brief Ethernet MAC + */ + +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACFFR; + __IO uint32_t MACHTHR; + __IO uint32_t MACHTLR; + __IO uint32_t MACMIIAR; + __IO uint32_t MACMIIDR; + __IO uint32_t MACFCR; + __IO uint32_t MACVLANTR; /* 8 */ + uint32_t RESERVED0[2]; + __IO uint32_t MACRWUFFR; /* 11 */ + __IO uint32_t MACPMTCSR; + uint32_t RESERVED1[2]; + __IO uint32_t MACSR; /* 15 */ + __IO uint32_t MACIMR; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; /* 24 */ + uint32_t RESERVED2[40]; + __IO uint32_t MMCCR; /* 65 */ + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; /* 69 */ + uint32_t RESERVED3[14]; + __IO uint32_t MMCTGFSCCR; /* 84 */ + __IO uint32_t MMCTGFMSCCR; + uint32_t RESERVED4[5]; + __IO uint32_t MMCTGFCR; + uint32_t RESERVED5[10]; + __IO uint32_t MMCRFCECR; + __IO uint32_t MMCRFAECR; + uint32_t RESERVED6[10]; + __IO uint32_t MMCRGUFCR; + uint32_t RESERVED7[334]; + __IO uint32_t PTPTSCR; + __IO uint32_t PTPSSIR; + __IO uint32_t PTPTSHR; + __IO uint32_t PTPTSLR; + __IO uint32_t PTPTSHUR; + __IO uint32_t PTPTSLUR; + __IO uint32_t PTPTSAR; + __IO uint32_t PTPTTHR; + __IO uint32_t PTPTTLR; + __IO uint32_t RESERVED8; + __IO uint32_t PTPTSSR; + uint32_t RESERVED9[565]; + __IO uint32_t DMABMR; + __IO uint32_t DMATPDR; + __IO uint32_t DMARPDR; + __IO uint32_t DMARDLAR; + __IO uint32_t DMATDLAR; + __IO uint32_t DMASR; + __IO uint32_t DMAOMR; + __IO uint32_t DMAIER; + __IO uint32_t DMAMFBOCR; + __IO uint32_t DMARSWTR; + uint32_t RESERVED10[8]; + __IO uint32_t DMACHTDR; + __IO uint32_t DMACHRDR; + __IO uint32_t DMACHTBAR; + __IO uint32_t DMACHRBAR; +} ETH_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ + __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ + __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ + __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ + __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ + __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ + __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ + __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ +} FLASH_TypeDef; + + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ + uint32_t RESERVED1; /*!< Reserved, 0x78 */ + uint32_t RESERVED2; /*!< Reserved, 0x7C */ + __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED3; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FSMC_Bank2_3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ + __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ + __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ + __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ + __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ +} FSMC_Bank4_TypeDef; + + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint16_t BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */ + __IO uint16_t BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ +} GPIO_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ + __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ +} SYSCFG_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ + __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ + __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ + __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ + __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ + __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ + __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ + __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved, 0x3C */ + __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ + uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, 0x5C */ + __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ + uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ + __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ + __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ + __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ + +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ + __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ + __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ + __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ + __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ + __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ + __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ + uint32_t RESERVED7; /*!< Reserved, 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ + __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ + __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ + __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ + __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ + __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ + __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ + __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ + __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ + __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ + __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ + __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ + __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ + __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ + __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ + __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ + __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ + __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ + __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ + __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ +} RTC_TypeDef; + + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ + __I uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ + __I uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ + __I uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ + __I uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ + __I uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ + __I uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ + __I uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ + __I uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ + uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ + __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ + __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ + __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ + __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ + __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ + __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ + __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ + __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ + __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ + __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + +/** + * @brief RNG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + + + +/** + * @brief __USB_OTG_Core_register + */ +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h*/ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h*/ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h*/ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch*/ + __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h*/ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h*/ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h*/ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch*/ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h*/ + __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register 024h*/ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h*/ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch*/ + uint32_t Reserved30[2]; /* Reserved 030h*/ + __IO uint32_t GCCFG; /* General Purpose IO Register 038h*/ + __IO uint32_t CID; /* User ID Register 03Ch*/ + uint32_t Reserved40[48]; /* Reserved 040h-0FFh*/ + __IO uint32_t HPTXFSIZ; /* Host Periodic Tx FIFO Size Reg 100h*/ + __IO uint32_t DIEPTXF[0x0F];/* dev Periodic Transmit FIFO */ +} +USB_OTG_GlobalTypeDef; + + + +/** + * @brief __device_Registers + */ +typedef struct +{ + __IO uint32_t DCFG; /* dev Configuration Register 800h*/ + __IO uint32_t DCTL; /* dev Control Register 804h*/ + __IO uint32_t DSTS; /* dev Status Register (RO) 808h*/ + uint32_t Reserved0C; /* Reserved 80Ch*/ + __IO uint32_t DIEPMSK; /* dev IN Endpoint Mask 810h*/ + __IO uint32_t DOEPMSK; /* dev OUT Endpoint Mask 814h*/ + __IO uint32_t DAINT; /* dev All Endpoints Itr Reg 818h*/ + __IO uint32_t DAINTMSK; /* dev All Endpoints Itr Mask 81Ch*/ + uint32_t Reserved20; /* Reserved 820h*/ + uint32_t Reserved9; /* Reserved 824h*/ + __IO uint32_t DVBUSDIS; /* dev VBUS discharge Register 828h*/ + __IO uint32_t DVBUSPULSE; /* dev VBUS Pulse Register 82Ch*/ + __IO uint32_t DTHRCTL; /* dev thr 830h*/ + __IO uint32_t DIEPEMPMSK; /* dev empty msk 834h*/ + __IO uint32_t DEACHINT; /* dedicated EP interrupt 838h*/ + __IO uint32_t DEACHMSK; /* dedicated EP msk 83Ch*/ + uint32_t Reserved40; /* dedicated EP mask 840h*/ + __IO uint32_t DINEP1MSK; /* dedicated EP mask 844h*/ + uint32_t Reserved44[15]; /* Reserved 844-87Ch*/ + __IO uint32_t DOUTEP1MSK; /* dedicated EP msk 884h*/ +} +USB_OTG_DeviceTypeDef; + + +/** + * @brief __IN_Endpoint-Specific_Register + */ +typedef struct +{ + __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h*/ + __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h*/ + __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h*/ + __IO uint32_t DTXFSTS;/*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h*/ + uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch*/ +} +USB_OTG_INEndpointTypeDef; + + +/** + * @brief __OUT_Endpoint-Specific_Registers + */ +typedef struct +{ + __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ +} +USB_OTG_OUTEndpointTypeDef; + + +/** + * @brief __Host_Mode_Register_Structures + */ +typedef struct +{ + __IO uint32_t HCFG; /* Host Configuration Register 400h*/ + __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ + __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ + uint32_t Reserved40C; /* Reserved 40Ch*/ + __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ + __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ + __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ +} +USB_OTG_HostTypeDef; + + +/** + * @brief __Host_Channel_Specific_Registers + */ +typedef struct +{ + __IO uint32_t HCCHAR; + __IO uint32_t HCSPLT; + __IO uint32_t HCINT; + __IO uint32_t HCINTMSK; + __IO uint32_t HCTSIZ; + __IO uint32_t HCDMA; + uint32_t Reserved[2]; +} +USB_OTG_HostChannelTypeDef; + + +/** + * @brief Peripheral_memory_map + */ +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH(up to 1 MB) base address in the alias region */ +#define CCMDATARAM_BASE ((uint32_t)0x10000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region */ +#define SRAM1_BASE ((uint32_t)0x20000000) /*!< SRAM1(112 KB) base address in the alias region */ +#define SRAM2_BASE ((uint32_t)0x2001C000) /*!< SRAM2(16 KB) base address in the alias region */ +#define SRAM3_BASE ((uint32_t)0x20020000) /*!< SRAM3(64 KB) base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ +#define BKPSRAM_BASE ((uint32_t)0x40024000) /*!< Backup SRAM(4 KB) base address in the alias region */ +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ +#define CCMDATARAM_BB_BASE ((uint32_t)0x12000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the bit-band region */ +#define SRAM1_BB_BASE ((uint32_t)0x22000000) /*!< SRAM1(112 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE ((uint32_t)0x2201C000) /*!< SRAM2(16 KB) base address in the bit-band region */ +#define SRAM3_BB_BASE ((uint32_t)0x22020000) /*!< SRAM3(64 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ +#define BKPSRAM_BB_BASE ((uint32_t)0x42024000) /*!< Backup SRAM(4 KB) base address in the bit-band region */ +#define FLASH_END ((uint32_t)0x080FFFFF) /*!< FLASH end address */ +#define CCMDATARAM_END ((uint32_t)0x1000FFFF) /*!< CCM data RAM end address */ + +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000) + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) + +/*!< APB2 peripherals */ +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADC_BASE (APB2PERIPH_BASE + 0x2300) +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800) + +/*!< AHB1 peripherals */ +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00) +#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8) +#define ETH_BASE (AHB1PERIPH_BASE + 0x8000) +#define ETH_MAC_BASE (ETH_BASE) +#define ETH_MMC_BASE (ETH_BASE + 0x0100) +#define ETH_PTP_BASE (ETH_BASE + 0x0700) +#define ETH_DMA_BASE (ETH_BASE + 0x1000) + +/*!< AHB2 peripherals */ +#define DCMI_BASE (AHB2PERIPH_BASE + 0x50000) +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800) + +/*!< FSMC Bankx registers base address */ +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) +#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060) +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE ((uint32_t )0xE0042000) + +/*!< USB registers base address */ +#define USB_OTG_HS_PERIPH_BASE ((uint32_t )0x40040000) +#define USB_OTG_FS_PERIPH_BASE ((uint32_t )0x50000000) + +#define USB_OTG_GLOBAL_BASE ((uint32_t )0x000) +#define USB_OTG_DEVICE_BASE ((uint32_t )0x800) +#define USB_OTG_IN_ENDPOINT_BASE ((uint32_t )0x900) +#define USB_OTG_OUT_ENDPOINT_BASE ((uint32_t )0xB00) +#define USB_OTG_EP_REG_SIZE ((uint32_t )0x20) +#define USB_OTG_HOST_BASE ((uint32_t )0x400) +#define USB_OTG_HOST_PORT_BASE ((uint32_t )0x440) +#define USB_OTG_HOST_CHANNEL_BASE ((uint32_t )0x500) +#define USB_OTG_HOST_CHANNEL_SIZE ((uint32_t )0x20) +#define USB_OTG_PCGCCTL_BASE ((uint32_t )0xE00) +#define USB_OTG_FIFO_BASE ((uint32_t )0x1000) +#define USB_OTG_FIFO_SIZE ((uint32_t )0x1000) + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define ADC ((ADC_Common_TypeDef *) ADC_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) +#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) +#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) +#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) +#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) +#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) +#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) +#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) +#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) +#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) +#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) +#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) +#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) +#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) +#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) +#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) +#define ETH ((ETH_TypeDef *) ETH_BASE) +#define DCMI ((DCMI_TypeDef *) DCMI_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) +#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD ((uint32_t)0x00000001) /*! + * + * @} + */ + +#include "board.h" +#include "arch/io_arch.h" +#include "periph/uart.h" + +int io_arch_puts(char *data, int size) +{ + for (int i = 0; i < size; i++) { + uart_write_blocking(STDIO, data[i]); + } + return size; +} diff --git a/cpu/stm32f4/lpm_arch.c b/cpu/stm32f4/lpm_arch.c new file mode 100644 index 000000000..c375d44d6 --- /dev/null +++ b/cpu/stm32f4/lpm_arch.c @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Implementation of the kernels power management interface + * + * @author Hauke Petersen + * + * @} + */ + +#include "arch/lpm_arch.h" + +void lpm_arch_init(void) +{ + /* TODO */ +} + +enum lpm_mode lpm_arch_set(enum lpm_mode target) +{ + /* TODO */ + return 0; +} + +enum lpm_mode lpm_arch_get(void) +{ + /* TODO */ + return 0; +} + +void lpm_arch_awake(void) +{ + /* TODO */ +} + +void lpm_arch_begin_awake(void) +{ + /* TODO */ +} + +void lpm_arch_end_awake(void) +{ + /* TODO */ +} diff --git a/cpu/stm32f4/periph/Makefile b/cpu/stm32f4/periph/Makefile new file mode 100644 index 000000000..6d1887b64 --- /dev/null +++ b/cpu/stm32f4/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f4/periph/gpio.c b/cpu/stm32f4/periph/gpio.c new file mode 100644 index 000000000..be7873b23 --- /dev/null +++ b/cpu/stm32f4/periph/gpio.c @@ -0,0 +1,758 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Low-level GPIO driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include "cpu.h" +#include "sched.h" +#include "thread.h" +#include "periph/gpio.h" +#include "periph_conf.h" + +typedef struct { + void (*cb)(void); +} gpio_state_t; + +/** + * @brief Unified IRQ handler shared by all interrupt routines + * + * @param[in] dev the device that triggered the interrupt + */ +static inline void irq_handler(gpio_t dev); + +/** + * @brief Hold one callback function pointer for each gpio device + */ +static gpio_state_t config[GPIO_NUMOF]; + +int gpio_init_out(gpio_t dev, gpio_pp_t pushpull) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + GPIO_0_CLKEN(); + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#if GPIO_1_EN + case GPIO_1: + GPIO_1_CLKEN(); + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#if GPIO_2_EN + case GPIO_2: + GPIO_2_CLKEN(); + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#if GPIO_3_EN + case GPIO_3: + GPIO_3_CLKEN(); + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#if GPIO_4_EN + case GPIO_4: + GPIO_4_CLKEN(); + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#if GPIO_5_EN + case GPIO_5: + GPIO_5_CLKEN(); + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#if GPIO_6_EN + case GPIO_6: + GPIO_6_CLKEN(); + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#if GPIO_7_EN + case GPIO_7: + GPIO_7_CLKEN(); + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#if GPIO_8_EN + case GPIO_8: + GPIO_8_CLKEN(); + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#if GPIO_9_EN + case GPIO_9: + GPIO_9_CLKEN(); + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#if GPIO_10_EN + case GPIO_10: + GPIO_10_CLKEN(); + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#if GPIO_11_EN + case GPIO_11: + GPIO_11_CLKEN(); + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + port->MODER &= ~(2 << (2 * pin)); /* set pin to output mode */ + port->MODER |= (1 << (2 * pin)); + port->OTYPER &= ~(1 << pin); /* set to push-pull configuration */ + port->OSPEEDR |= (3 << (2 * pin)); /* set to high speed */ + port->PUPDR &= ~(3 << (2 * pin)); /* configure push-pull resistors */ + port->PUPDR |= (pushpull << (2 * pin)); + port->ODR &= ~(1 << pin); /* set pin to low signal */ + + return 0; /* all OK */ +} + +int gpio_init_in(gpio_t dev, gpio_pp_t pushpull) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + GPIO_0_CLKEN(); + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#if GPIO_1_EN + case GPIO_1: + GPIO_1_CLKEN(); + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#if GPIO_2_EN + case GPIO_2: + GPIO_2_CLKEN(); + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#if GPIO_3_EN + case GPIO_3: + GPIO_3_CLKEN(); + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#if GPIO_4_EN + case GPIO_4: + GPIO_4_CLKEN(); + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#if GPIO_5_EN + case GPIO_5: + GPIO_5_CLKEN(); + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#if GPIO_6_EN + case GPIO_6: + GPIO_6_CLKEN(); + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#if GPIO_7_EN + case GPIO_7: + GPIO_7_CLKEN(); + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#if GPIO_8_EN + case GPIO_8: + GPIO_8_CLKEN(); + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#if GPIO_9_EN + case GPIO_9: + GPIO_9_CLKEN(); + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#if GPIO_10_EN + case GPIO_10: + GPIO_10_CLKEN(); + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#if GPIO_11_EN + case GPIO_11: + GPIO_11_CLKEN(); + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + port->MODER &= ~(3 << (2 * pin)); /* configure pin as input */ + port->PUPDR &= ~(3 << (2 * pin)); /* configure push-pull resistors */ + port->PUPDR |= (pushpull << (2 * pin)); + + return 0; /* everything alright here */ +} + +int gpio_init_int(gpio_t dev, gpio_pp_t pushpull, gpio_flank_t flank, void (*cb)(void)) +{ + int res; + uint32_t pin; + + res = gpio_init_in(dev, pushpull); + if (res < 0) { + return res; + } + + /* enable the SYSCFG clock */ + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; + + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + pin = GPIO_0_PIN; + GPIO_0_EXTI_CFG(); + NVIC_SetPriority(GPIO_0_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_0_IRQ); + break; +#endif +#if GPIO_1_EN + case GPIO_1: + pin = GPIO_1_PIN; + GPIO_1_EXTI_CFG(); + NVIC_SetPriority(GPIO_1_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_1_IRQ); + break; +#endif +#if GPIO_2_EN + case GPIO_2: + pin = GPIO_2_PIN; + GPIO_2_EXTI_CFG(); + NVIC_SetPriority(GPIO_2_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_2_IRQ); + break; +#endif +#if GPIO_3_EN + case GPIO_3: + pin = GPIO_3_PIN; + GPIO_3_EXTI_CFG(); + NVIC_SetPriority(GPIO_3_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_3_IRQ); + break; +#endif +#if GPIO_4_EN + case GPIO_4: + pin = GPIO_4_PIN; + GPIO_4_EXTI_CFG(); + NVIC_SetPriority(GPIO_4_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_4_IRQ); + break; +#endif +#if GPIO_5_EN + case GPIO_5: + pin = GPIO_5_PIN; + GPIO_5_EXTI_CFG(); + NVIC_SetPriority(GPIO_5_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_5_IRQ); + break; +#endif +#if GPIO_6_EN + case GPIO_6: + pin = GPIO_6_PIN; + GPIO_6_EXTI_CFG(); + NVIC_SetPriority(GPIO_6_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_6_IRQ); + break; +#endif +#if GPIO_7_EN + case GPIO_7: + pin = GPIO_7_PIN; + GPIO_7_EXTI_CFG(); + NVIC_SetPriority(GPIO_7_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_7_IRQ); + break; +#endif +#if GPIO_8_EN + case GPIO_8: + pin = GPIO_8_PIN; + GPIO_8_EXTI_CFG(); + NVIC_SetPriority(GPIO_8_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_8_IRQ); + break; +#endif +#if GPIO_9_EN + case GPIO_9: + pin = GPIO_9_PIN; + GPIO_9_EXTI_CFG(); + NVIC_SetPriority(GPIO_9_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_9_IRQ); + break; +#endif +#if GPIO_10_EN + case GPIO_10: + pin = GPIO_10_PIN; + GPIO_10_EXTI_CFG(); + NVIC_SetPriority(GPIO_10_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_10_IRQ); + break; +#endif +#if GPIO_11_EN + case GPIO_11: + pin = GPIO_11_PIN; + GPIO_11_EXTI_CFG(); + NVIC_SetPriority(GPIO_11_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_11_IRQ); + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + /* set callback */ + config[dev].cb = cb; + + /* configure the active edges */ + switch (flank) { + case GPIO_RISING: + EXTI->RTSR |= (1 << pin); + EXTI->FTSR &= ~(1 << pin); + break; + case GPIO_FALLING: + EXTI->RTSR &= ~(1 << pin); + EXTI->FTSR |= (1 << pin); + break; + case GPIO_BOTH: + EXTI->RTSR |= (1 << pin); + EXTI->FTSR |= (1 << pin); + break; + } + + /* enable interrupt for EXTI line */ + EXTI->IMR |= (1 << pin); + + return 0; +} + +int gpio_read(gpio_t dev) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#if GPIO_1_EN + case GPIO_1: + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#if GPIO_2_EN + case GPIO_2: + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#if GPIO_3_EN + case GPIO_3: + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#if GPIO_4_EN + case GPIO_4: + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#if GPIO_5_EN + case GPIO_5: + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#if GPIO_6_EN + case GPIO_6: + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#if GPIO_7_EN + case GPIO_7: + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#if GPIO_8_EN + case GPIO_8: + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#if GPIO_9_EN + case GPIO_9: + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#if GPIO_10_EN + case GPIO_10: + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#if GPIO_11_EN + case GPIO_11: + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + if (port->MODER & (3 << (pin * 2))) { /* if configured as output */ + return port->ODR & (1 << pin); /* read output data register */ + } else { + return port->IDR & (1 << pin); /* else read input data register */ + } +} + +int gpio_set(gpio_t dev) +{ + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + GPIO_0_PORT->ODR |= (1 << GPIO_0_PIN); + break; +#endif +#if GPIO_1_EN + case GPIO_1: + GPIO_1_PORT->ODR |= (1 << GPIO_1_PIN); + break; +#endif +#if GPIO_2_EN + case GPIO_2: + GPIO_2_PORT->ODR |= (1 << GPIO_2_PIN); + break; +#endif +#if GPIO_3_EN + case GPIO_3: + GPIO_3_PORT->ODR |= (1 << GPIO_3_PIN); + break; +#endif +#if GPIO_4_EN + case GPIO_4: + GPIO_4_PORT->ODR |= (1 << GPIO_4_PIN); + break; +#endif +#if GPIO_5_EN + case GPIO_5: + GPIO_5_PORT->ODR |= (1 << GPIO_5_PIN); + break; +#endif +#if GPIO_6_EN + case GPIO_6: + GPIO_6_PORT->ODR |= (1 << GPIO_6_PIN); + break; +#endif +#if GPIO_7_EN + case GPIO_7: + GPIO_7_PORT->ODR |= (1 << GPIO_7_PIN); + break; +#endif +#if GPIO_8_EN + case GPIO_8: + GPIO_8_PORT->ODR |= (1 << GPIO_8_PIN); + break; +#endif +#if GPIO_9_EN + case GPIO_9: + GPIO_9_PORT->ODR |= (1 << GPIO_9_PIN); + break; +#endif +#if GPIO_10_EN + case GPIO_10: + GPIO_10_PORT->ODR |= (1 << GPIO_10_PIN); + break; +#endif +#if GPIO_11_EN + case GPIO_11: + GPIO_11_PORT->ODR |= (1 << GPIO_11_PIN); +#endif + break; + case GPIO_UNDEFINED: + default: + return -1; + } + return 0; +} + +int gpio_clear(gpio_t dev) +{ + switch (dev) { +#if GPIO_0_EN + case GPIO_0: + GPIO_0_PORT->ODR &= ~(1 << GPIO_0_PIN); + break; +#endif +#if GPIO_1_EN + case GPIO_1: + GPIO_1_PORT->ODR &= ~(1 << GPIO_1_PIN); + break; +#endif +#if GPIO_2_EN + case GPIO_2: + GPIO_2_PORT->ODR &= ~(1 << GPIO_2_PIN); + break; +#endif +#if GPIO_3_EN + case GPIO_3: + GPIO_3_PORT->ODR &= ~(1 << GPIO_3_PIN); + break; +#endif +#if GPIO_4_EN + case GPIO_4: + GPIO_4_PORT->ODR &= ~(1 << GPIO_4_PIN); + break; +#endif +#if GPIO_5_EN + case GPIO_5: + GPIO_5_PORT->ODR &= ~(1 << GPIO_5_PIN); + break; +#endif +#if GPIO_6_EN + case GPIO_6: + GPIO_6_PORT->ODR &= ~(1 << GPIO_6_PIN); + break; +#endif +#if GPIO_7_EN + case GPIO_7: + GPIO_7_PORT->ODR &= ~(1 << GPIO_7_PIN); + break; +#endif +#if GPIO_8_EN + case GPIO_8: + GPIO_8_PORT->ODR &= ~(1 << GPIO_8_PIN); + break; +#endif +#if GPIO_9_EN + case GPIO_9: + GPIO_9_PORT->ODR &= ~(1 << GPIO_9_PIN); + break; +#endif +#if GPIO_10_EN + case GPIO_10: + GPIO_10_PORT->ODR &= ~(1 << GPIO_10_PIN); + break; +#endif +#if GPIO_11_EN + case GPIO_11: + GPIO_11_PORT->ODR &= ~(1 << GPIO_11_PIN); + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + return 0; +} + +int gpio_toggle(gpio_t dev) +{ + if (gpio_read(dev)) { + return gpio_clear(dev); + } else { + return gpio_set(dev); + } +} + +int gpio_write(gpio_t dev, int value) +{ + if (value) { + return gpio_set(dev); + } else { + return gpio_clear(dev); + } +} + +static inline void irq_handler(gpio_t dev) +{ + config[dev].cb(); + if (sched_context_switch_request) { + thread_yield(); + } +} + +__attribute__((naked)) +void isr_exti0(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR0) { + EXTI->PR |= EXTI_PR_PR0; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_0); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti1(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR1) { + EXTI->PR |= EXTI_PR_PR1; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_1); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti2(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR2) { + EXTI->PR |= EXTI_PR_PR2; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_2); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti3(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR3) { + EXTI->PR |= EXTI_PR_PR3; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_3); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti4(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR4) { + EXTI->PR |= EXTI_PR_PR4; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_4); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti9_5(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR5) { + EXTI->PR |= EXTI_PR_PR5; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_5); + } + if (EXTI->PR & EXTI_PR_PR6) { + EXTI->PR |= EXTI_PR_PR6; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_6); + } + if (EXTI->PR & EXTI_PR_PR7) { + EXTI->PR |= EXTI_PR_PR7; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_7); + } + if (EXTI->PR & EXTI_PR_PR8) { + EXTI->PR |= EXTI_PR_PR8; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_8); + } + if (EXTI->PR & EXTI_PR_PR9) { + EXTI->PR |= EXTI_PR_PR9; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_9); + } + ISR_EXIT(); +} + +__attribute__((naked)) +void isr_exti15_10(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR10) { + EXTI->PR |= EXTI_PR_PR10; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_10); + } + if (EXTI->PR & EXTI_PR_PR11) { + EXTI->PR |= EXTI_PR_PR11; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_11); + } + if (EXTI->PR & EXTI_PR_PR12) { + EXTI->PR |= EXTI_PR_PR12; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_12); + } + if (EXTI->PR & EXTI_PR_PR13) { + EXTI->PR |= EXTI_PR_PR13; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_13); + } + if (EXTI->PR & EXTI_PR_PR14) { + EXTI->PR |= EXTI_PR_PR14; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_14); + } + if (EXTI->PR & EXTI_PR_PR15) { + EXTI->PR |= EXTI_PR_PR15; /* clear status bit by writing a 1 to it */ + irq_handler(GPIO_IRQ_15); + } + ISR_EXIT(); +} diff --git a/cpu/stm32f4/periph/timer.c b/cpu/stm32f4/periph/timer.c new file mode 100644 index 000000000..559417087 --- /dev/null +++ b/cpu/stm32f4/periph/timer.c @@ -0,0 +1,335 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Low-level timer driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "cpu.h" +#include "board.h" +#include "sched.h" +#include "thread.h" +#include "periph_conf.h" +#include "periph/timer.h" + +/** Unified IRQ handler for all timers */ +static inline void irq_handler(tim_t timer, TIM_TypeDef *dev); + +/** Type for timer state */ +typedef struct { + void (*cb)(int); +} timer_conf_t; + +/** Timer state memory */ +timer_conf_t config[TIMER_NUMOF]; + + +int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int)) +{ + TIM_TypeDef *timer; + + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + /* enable timer peripheral clock */ + TIMER_0_CLKEN(); + /* set timer's IRQ priority */ + NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_IRQ_PRIO); + /* select timer */ + timer = TIMER_0_DEV; + timer->PSC = TIMER_0_PRESCALER * ticks_per_us; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + /* enable timer peripheral clock */ + TIMER_1_CLKEN(); + /* set timer's IRQ priority */ + NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_IRQ_PRIO); + /* select timer */ + timer = TIMER_1_DEV; + timer->PSC = TIMER_0_PRESCALER * ticks_per_us; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + + /* set callback function */ + config[dev].cb = callback; + + /* set timer to run in counter mode */ + timer->CR1 = 0; + timer->CR2 = 0; + + /* set auto-reload and prescaler values and load new values */ + timer->EGR |= TIM_EGR_UG; + + /* enable the timer's interrupt */ + timer_irq_enable(dev); + + /* start the timer */ + timer_start(dev); + + return 0; +} + +int timer_set(tim_t dev, int channel, unsigned int timeout) +{ + int now = timer_read(dev); + return timer_set_absolute(dev, channel, now + timeout - 1); +} + +int timer_set_absolute(tim_t dev, int channel, unsigned int value) +{ + TIM_TypeDef *timer; + + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + timer = TIMER_0_DEV; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + timer = TIMER_1_DEV; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + + switch (channel) { + case 0: + timer->CCR1 = value; + timer->SR &= ~TIM_SR_CC1IF; + timer->DIER |= TIM_DIER_CC1IE; + break; + case 1: + timer->CCR2 = value; + timer->SR &= ~TIM_SR_CC2IF; + timer->DIER |= TIM_DIER_CC2IE; + break; + case 2: + timer->CCR3 = value; + timer->SR &= ~TIM_SR_CC3IF; + timer->DIER |= TIM_DIER_CC3IE; + break; + case 3: + timer->CCR4 = value; + timer->SR &= ~TIM_SR_CC4IF; + timer->DIER |= TIM_DIER_CC4IE; + break; + default: + return -1; + } + + return 0; +} + +int timer_clear(tim_t dev, int channel) +{ + TIM_TypeDef *timer; + + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + timer = TIMER_0_DEV; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + timer = TIMER_1_DEV; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + + switch (channel) { + case 0: + timer->DIER &= ~TIM_DIER_CC1IE; + break; + case 1: + timer->DIER &= ~TIM_DIER_CC2IE; + break; + case 2: + timer->DIER &= ~TIM_DIER_CC3IE; + break; + case 3: + timer->DIER &= ~TIM_DIER_CC4IE; + break; + default: + return -1; + } + + return 0; +} + +unsigned int timer_read(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + return TIMER_0_DEV->CNT; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + return TIMER_1_DEV->CNT; + break; +#endif + case TIMER_UNDEFINED: + default: + return 0; + } +} + +void timer_start(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CR1 |= TIM_CR1_CEN; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CR1 |= TIM_CR1_CEN; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_stop(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CR1 &= ~TIM_CR1_CEN; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CR1 &= ~TIM_CR1_CEN; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_irq_enable(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + NVIC_EnableIRQ(TIMER_0_IRQ_CHAN); + break; +#endif +#if TIMER_1_EN + case TIMER_1: + NVIC_EnableIRQ(TIMER_1_IRQ_CHAN); + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_irq_disable(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + NVIC_DisableIRQ(TIMER_0_IRQ_CHAN); + break; +#endif +#if TIMER_1_EN + case TIMER_1: + NVIC_DisableIRQ(TIMER_1_IRQ_CHAN); + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_reset(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CNT = 0; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CNT = 0; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +__attribute__ ((naked)) void TIMER_0_ISR(void) +{ + ISR_ENTER(); + irq_handler(TIMER_0, TIMER_0_DEV); + ISR_EXIT(); +} + +__attribute__ ((naked)) void TIMER_1_ISR(void) +{ + ISR_ENTER(); + irq_handler(TIMER_1, TIMER_1_DEV); + ISR_EXIT(); +} + +static inline void irq_handler(tim_t timer, TIM_TypeDef *dev) +{ + if (dev->SR & TIM_SR_CC1IF) { + dev->DIER &= ~TIM_DIER_CC1IE; + dev->SR &= ~TIM_SR_CC1IF; + config[timer].cb(0); + } + else if (dev->SR & TIM_SR_CC2IF) { + dev->DIER &= ~TIM_DIER_CC2IE; + dev->SR &= ~TIM_SR_CC2IF; + config[timer].cb(1); + } + else if (dev->SR & TIM_SR_CC3IF) { + dev->DIER &= ~TIM_DIER_CC3IE; + dev->SR &= ~TIM_SR_CC3IF; + config[timer].cb(2); + } + else if (dev->SR & TIM_SR_CC4IF) { + dev->DIER &= ~TIM_DIER_CC4IE; + dev->SR &= ~TIM_SR_CC4IF; + config[timer].cb(3); + } + if (sched_context_switch_request) { + thread_yield(); + } +} diff --git a/cpu/stm32f4/periph/uart.c b/cpu/stm32f4/periph/uart.c new file mode 100644 index 000000000..2c97f2b7f --- /dev/null +++ b/cpu/stm32f4/periph/uart.c @@ -0,0 +1,313 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Low-level UART driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "cpu.h" +#include "thread.h" +#include "sched.h" +#include "periph_conf.h" +#include "periph/uart.h" + + +/** + * @brief Each UART device has to store two callbacks. + */ +typedef struct { + void (*rx_cb)(char); + void (*tx_cb)(void); +} uart_conf_t; + +/** + * @brief Unified interrupt handler for all UART devices + * + * @param uartnum the number of the UART that triggered the ISR + * @param uart the UART device that triggered the ISR + */ +static inline void irq_handler(uart_t uartnum, USART_TypeDef *uart); + +/** + * @brief Allocate memory to store the callback functions. + */ +static uart_conf_t config[UART_NUMOF]; + +int uart_init(uart_t uart, uint32_t baudrate, void (*rx_cb)(char), void (*tx_cb)(void)) +{ + /* do basic initialization */ + int res = uart_init_blocking(uart, baudrate); + if (res < 0) { + return res; + } + + /* remember callback addresses */ + config[uart].rx_cb = rx_cb; + config[uart].tx_cb = tx_cb; + + /* enable receive interrupt */ + switch (uart) { +#if UART_0_EN + case UART_0: + NVIC_SetPriority(UART_0_IRQ_CHAN, UART_IRQ_PRIO); + NVIC_EnableIRQ(UART_0_IRQ_CHAN); + UART_0_DEV->CR1 |= USART_CR1_RXNEIE; + break; +#endif +#if UART_1_EN + case UART_1: + NVIC_SetPriority(UART_1_IRQ_CHAN, UART_IRQ_PRIO); + NVIC_EnableIRQ(UART_1_IRQ_CHAN); + UART_1_DEV->CR1 |= USART_CR1_RXNEIE; + break; +#endif + case UART_UNDEFINED: + default: + return -2; + break; + } + + return 0; +} + +int uart_init_blocking(uart_t uart, uint32_t baudrate) +{ + USART_TypeDef *dev; + GPIO_TypeDef *port; + uint32_t tx_pin; + uint32_t rx_pin; + uint8_t af; + float clk; + float divider; + uint16_t mantissa; + uint8_t fraction; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + port = UART_0_PORT; + clk = UART_0_CLK; + tx_pin = UART_0_TX_PIN; + rx_pin = UART_0_RX_PIN; + af = UART_0_AF; + UART_0_CLKEN(); + UART_0_PORT_CLKEN(); + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + port = UART_1_PORT; + clk = UART_1_CLK; + tx_pin = UART_1_TX_PIN; + rx_pin = UART_1_RX_PIN; + af = UART_1_AF; + UART_1_CLKEN(); + UART_1_PORT_CLKEN(); + break; +#endif + case UART_UNDEFINED: + default: + return -1; + } + + /* configure RX and TX pins, set pin to use alternative function mode */ + port->MODER &= ~(3 << (rx_pin * 2) | 3 << (tx_pin * 2)); + port->MODER |= 2 << (rx_pin * 2) | 2 << (tx_pin * 2); + /* and assign alternative function */ + if (rx_pin < 8) { + port->AFR[0] &= ~(0xf << (rx_pin * 4)); + port->AFR[0] |= af << (rx_pin * 4); + } + else { + port->AFR[1] &= ~(0xf << ((rx_pin - 8) * 4)); + port->AFR[1] |= af << ((rx_pin - 8) * 4); + } + if (tx_pin < 8) { + port->AFR[0] &= ~(0xf << (tx_pin * 4)); + port->AFR[0] |= af << (tx_pin * 4); + } + else { + port->AFR[1] &= ~(0xf << ((tx_pin - 8) * 4)); + port->AFR[1] |= af << ((tx_pin - 8) * 4); + } + + /* configure UART to mode 8N1 with given baudrate */ + divider = clk / (16 * baudrate); + mantissa = (uint16_t)divider; + fraction = (uint8_t)((divider - mantissa) * 16); + dev->BRR = ((mantissa & 0x0fff) << 4) | (0x0f & fraction); + + /* enable receive and transmit mode */ + dev->CR3 = 0; + dev->CR2 = 0; + dev->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; + + return 0; +} + +void uart_tx_begin(uart_t uart) +{ + switch (uart) { +#if UART_0_EN + case UART_0: + UART_0_DEV->CR1 |= USART_CR1_TXEIE; + break; +#endif +#if UART_1_EN + case UART_1: + UART_1_DEV->CR1 |= USART_CR1_TXEIE; + break; +#endif + case UART_UNDEFINED: + default: + break; + } +} + +void uart_tx_end(uart_t uart) +{ + switch (uart) { +#if UART_0_EN + case UART_0: + UART_0_DEV->CR1 &= ~USART_CR1_TXEIE; + break; +#endif +#if UART_1_EN + case UART_1: + UART_1_DEV->CR1 &= ~USART_CR1_TXEIE; + break; +#endif + case UART_UNDEFINED: + default: + break; + } +} + +int uart_write(uart_t uart, char data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -2; + break; + } + + if (dev->SR & USART_SR_TXE) { + dev->DR = (uint8_t)data; + } + + return 0; +} + +int uart_read_blocking(uart_t uart, char *data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -2; + break; + } + + while (!(dev->SR & USART_SR_RXNE)); + *data = (char)dev->DR; + + return 1; +} + +int uart_write_blocking(uart_t uart, char data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -2; + break; + } + + while (!(dev->SR & USART_SR_TXE)); + dev->DR = (uint8_t)data; + + return 1; +} + +__attribute__((naked)) +void UART_0_ISR(void) +{ + ISR_ENTER(); + irq_handler(UART_0, UART_0_DEV); + ISR_EXIT(); +} + +__attribute__((naked)) +void UART_1_ISR(void) +{ + ISR_ENTER(); + irq_handler(UART_1, UART_1_DEV); + ISR_EXIT(); +} + +static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev) +{ + if (dev->SR & USART_SR_RXNE) { + char data = (char)dev->DR; + config[uartnum].rx_cb(data); + } + else if (dev->SR & USART_SR_TXE) { + config[uartnum].tx_cb(); + } + if (sched_context_switch_request) { + thread_yield(); + } +} diff --git a/cpu/stm32f4/reboot_arch.c b/cpu/stm32f4/reboot_arch.c new file mode 100644 index 000000000..4ce60cb5c --- /dev/null +++ b/cpu/stm32f4/reboot_arch.c @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Implementation of the kernels reboot interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "arch/reboot_arch.h" +#include "cpu.h" + + +int reboot_arch(int mode) +{ + printf("Going into reboot, mode %i\n", mode); + + NVIC_SystemReset(); + + return 0; +} diff --git a/cpu/stm32f4/startup.c b/cpu/stm32f4/startup.c new file mode 100644 index 000000000..36c62e9fb --- /dev/null +++ b/cpu/stm32f4/startup.c @@ -0,0 +1,307 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Startup code and interrupt vector definition + * + * @author Hauke Petersen + * + * @} + */ + +#include + +/** + * memory markers as defined in the linker script + */ +extern uint32_t _sfixed; +extern uint32_t _efixed; +extern uint32_t _etext; +extern uint32_t _srelocate; +extern uint32_t _erelocate; +extern uint32_t _szero; +extern uint32_t _ezero; +extern uint32_t _sstack; +extern uint32_t _estack; + +/** + * @brief functions for initializing the board, std-lib and kernel + */ +extern void board_init(void); +extern void kernel_init(void); +extern void __libc_init_array(void); + +/** + * @brief This function is the entry point after a system reset + * + * After a system reset, the following steps are necessary and carried out: + * 1. load data section from flash to ram + * 2. overwrite uninitialized data section (BSS) with zeros + * 3. initialize the newlib + * 4. initialize the board (sync clock, setup std-IO) + * 5. initialize and start RIOTs kernel + */ +void reset_handler(void) +{ + uint32_t *dst; + uint32_t *src = &_etext; + + /* load data section from flash to ram */ + for (dst = &_srelocate; dst < &_erelocate; ) { + *(dst++) = *(src++); + } + + /* default bss section to zero */ + for (dst = &_szero; dst < &_ezero; ) { + *(dst++) = 0; + } + + /* initialize the board and startup the kernel */ + board_init(); + /* initialize std-c library (this should be done after board_init) */ + __libc_init_array(); + /* startup the kernel */ + kernel_init(); +} + +/** + * @brief Default handler is called in case no interrupt handler was defined + */ +void dummy_handler(void) +{ + while (1) {asm ("nop");} +} + +void isr_nmi(void) +{ + while (1) {asm ("nop");} +} + +void isr_mem_manage(void) +{ + while (1) {asm ("nop");} +} + +void isr_debug_mon(void) +{ + while (1) {asm ("nop");} +} + +void isr_hard_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_bus_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_usage_fault(void) +{ + while (1) {asm ("nop");} +} + +/* Cortex-M specific interrupt vectors */ +void isr_svc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_systick(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* STM32F4 specific interrupt vector */ +void isr_wwdg(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pvd(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tamp_stamp(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc_wkup(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_flash(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rcc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream6(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_adc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can1_tx(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can1_rx0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can1_rx1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can1_sce(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti9_5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_brk_tim9(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_up_tim10(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_trg_com_tim11(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_cc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c1_ev(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c1_er(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c2_ev(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c2_er(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti15_10(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc_alarm(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_fs_wkup(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim8_brk_tim12(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim8_up_tim13(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim8_trg_com_tim14(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim8_cc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_stream7(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_fsmc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_sdio(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_uart5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim6_dac(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim7(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream4(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_eth(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_eth_wkup(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can2_tx(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can2_rx0(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can2_rx1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_can2_sce(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_fs(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream6(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma2_stream7(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart6(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c3_ev(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c3_er(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_hs_ep1_out(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_hs_ep1_in(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_hs_wkup(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_otg_hs(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dcmi(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_cryp(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_hash_rng(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_fpu(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* interrupt vector table */ +__attribute__ ((section(".vectors"))) +const void *interrupt_vector[] = { + /* Stack pointer */ + (void*) (&_estack), /* pointer to the top of the empty stack */ + /* Cortex-M4 handlers */ + (void*) reset_handler, /* entry point of the program */ + (void*) isr_nmi, /* non maskable interrupt handler */ + (void*) isr_hard_fault, /* if you end up here its not good */ + (void*) isr_mem_manage, /* memory controller interrupt */ + (void*) isr_bus_fault, /* also not good to end up here */ + (void*) isr_usage_fault, /* autsch */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) (0UL), /* Reserved */ + (void*) isr_svc, /* system call interrupt */ + (void*) isr_debug_mon, /* debug interrupt */ + (void*) (0UL), /* Reserved */ + (void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */ + (void*) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* STM specific peripheral handlers */ + (void*) isr_wwdg, /* Window WatchDog */ + (void*) isr_pvd, /* PVD through EXTI Line detection */ + (void*) isr_tamp_stamp, /* Tamper and TimeStamps through the EXTI line */ + (void*) isr_rtc_wkup, /* RTC Wakeup through the EXTI line */ + (void*) isr_flash, /* FLASH */ + (void*) isr_rcc, /* RCC */ + (void*) isr_exti0, /* EXTI Line0 */ + (void*) isr_exti1, /* EXTI Line1 */ + (void*) isr_exti2, /* EXTI Line2 */ + (void*) isr_exti3, /* EXTI Line3 */ + (void*) isr_exti4, /* EXTI Line4 */ + (void*) isr_dma1_stream0, /* DMA1 Stream 0 */ + (void*) isr_dma1_stream1, /* DMA1 Stream 1 */ + (void*) isr_dma1_stream2, /* DMA1 Stream 2 */ + (void*) isr_dma1_stream3, /* DMA1 Stream 3 */ + (void*) isr_dma1_stream4, /* DMA1 Stream 4 */ + (void*) isr_dma1_stream5, /* DMA1 Stream 5 */ + (void*) isr_dma1_stream6, /* DMA1 Stream 6 */ + (void*) isr_adc, /* ADC1, ADC2 and ADC3s */ + (void*) isr_can1_tx, /* CAN1 TX */ + (void*) isr_can1_rx0, /* CAN1 RX0 */ + (void*) isr_can1_rx1, /* CAN1 RX1 */ + (void*) isr_can1_sce, /* CAN1 SCE */ + (void*) isr_exti9_5, /* External Line[9:5]s */ + (void*) isr_tim1_brk_tim9, /* TIM1 Break and TIM9 */ + (void*) isr_tim1_up_tim10, /* TIM1 Update and TIM10 */ + (void*) isr_tim1_trg_com_tim11, /* TIM1 Trigger and Commutation and TIM11 */ + (void*) isr_tim1_cc, /* TIM1 Capture Compare */ + (void*) isr_tim2, /* TIM2 */ + (void*) isr_tim3, /* TIM3 */ + (void*) isr_tim4, /* TIM4 */ + (void*) isr_i2c1_ev, /* I2C1 Event */ + (void*) isr_i2c1_er, /* I2C1 Error */ + (void*) isr_i2c2_ev, /* I2C2 Event */ + (void*) isr_i2c2_er, /* I2C2 Error */ + (void*) isr_spi1, /* SPI1 */ + (void*) isr_spi2, /* SPI2 */ + (void*) isr_usart1, /* USART1 */ + (void*) isr_usart2, /* USART2 */ + (void*) isr_usart3, /* USART3 */ + (void*) isr_exti15_10, /* External Line[15:10]s */ + (void*) isr_rtc_alarm, /* RTC Alarm (A and B) through EXTI Line */ + (void*) isr_otg_fs_wkup, /* USB OTG FS Wakeup through EXTI line */ + (void*) isr_tim8_brk_tim12, /* TIM8 Break and TIM12 */ + (void*) isr_tim8_up_tim13, /* TIM8 Update and TIM13 */ + (void*) isr_tim8_trg_com_tim14, /* TIM8 Trigger and Commutation and TIM14 */ + (void*) isr_tim8_cc, /* TIM8 Capture Compare */ + (void*) isr_dma1_stream7, /* DMA1 Stream7 */ + (void*) isr_fsmc, /* FSMC */ + (void*) isr_sdio, /* SDIO */ + (void*) isr_tim5, /* TIM5 */ + (void*) isr_spi3, /* SPI3 */ + (void*) isr_uart4, /* UART4 */ + (void*) isr_uart5, /* UART5 */ + (void*) isr_tim6_dac, /* TIM6 and DAC1&2 underrun errors */ + (void*) isr_tim7, /* TIM7 */ + (void*) isr_dma2_stream0, /* DMA2 Stream 0 */ + (void*) isr_dma2_stream1, /* DMA2 Stream 1 */ + (void*) isr_dma2_stream2, /* DMA2 Stream 2 */ + (void*) isr_dma2_stream3, /* DMA2 Stream 3 */ + (void*) isr_dma2_stream4, /* DMA2 Stream 4 */ + (void*) isr_eth, /* Ethernet */ + (void*) isr_eth_wkup, /* Ethernet Wakeup through EXTI line */ + (void*) isr_can2_tx, /* CAN2 TX */ + (void*) isr_can2_rx0, /* CAN2 RX0 */ + (void*) isr_can2_rx1, /* CAN2 RX1 */ + (void*) isr_can2_sce, /* CAN2 SCE */ + (void*) isr_otg_fs, /* USB OTG FS */ + (void*) isr_dma2_stream5, /* DMA2 Stream 5 */ + (void*) isr_dma2_stream6, /* DMA2 Stream 6 */ + (void*) isr_dma2_stream7, /* DMA2 Stream 7 */ + (void*) isr_usart6, /* USART6 */ + (void*) isr_i2c3_ev, /* I2C3 event */ + (void*) isr_i2c3_er, /* I2C3 error */ + (void*) isr_otg_hs_ep1_out, /* USB OTG HS End Point 1 Out */ + (void*) isr_otg_hs_ep1_in, /* USB OTG HS End Point 1 In */ + (void*) isr_otg_hs_wkup, /* USB OTG HS Wakeup through EXTI */ + (void*) isr_otg_hs, /* USB OTG HS */ + (void*) isr_dcmi, /* DCMI */ + (void*) isr_cryp, /* CRYP crypto */ + (void*) isr_hash_rng, /* Hash and Rng */ + (void*) isr_fpu, /* FPU */ +}; diff --git a/cpu/stm32f4/stm32f407vg_linkerscript.ld b/cpu/stm32f4/stm32f407vg_linkerscript.ld new file mode 100644 index 000000000..551774547 --- /dev/null +++ b/cpu/stm32f4/stm32f407vg_linkerscript.ld @@ -0,0 +1,144 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL 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. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + ccmram (rwx): ORIGIN = 0x10000000, LENGTH = 64K +} + +/* The stack size used by the application. NOTE: you need to adjust */ +STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x2000 ; + + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(8); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} diff --git a/cpu/stm32f4/syscalls.c b/cpu/stm32f4/syscalls.c new file mode 100644 index 000000000..b368f247e --- /dev/null +++ b/cpu/stm32f4/syscalls.c @@ -0,0 +1,271 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief NewLib system call implementations for STM32F4 + * + * @author Michael Baar + * @author Stefan Pfeiffer + * @author Hauke Petersen + * + * @} + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "board.h" +#include "thread.h" +#include "kernel.h" +#include "irq.h" +#include "periph/uart.h" + +/** + * manage the heap + */ +extern uint32_t _end; /* address of last used memory cell */ +caddr_t heap_top = (caddr_t)&_end + 4; + +/** + * @brief Initialize NewLib, called by __libc_init_array() from the startup script + */ +void _init(void) +{ + uart_init_blocking(STDIO, STDIO_BAUDRATE); +} + +/** + * @brief Free resources on NewLib de-initialization, not used for RIOT + */ +void _fini(void) +{ + /* nothing to do here */ +} + +/** + * @brief Exit a program without cleaning up files + * + * If your system doesn't provide this, it is best to avoid linking with subroutines that + * require it (exit, system). + * + * @param n the exit code, 0 for all OK, >0 for not OK + */ +void _exit(int n) +{ + printf("#! exit %i: resetting\n", n); + NVIC_SystemReset(); + while(1); +} + +/** + * @brief Allocate memory from the heap. + * + * The current heap implementation is very rudimentary, it is only able to allocate + * memory. But it does not + * - check if the returned address is valid (no check if the memory very exists) + * - have any means to free memory again + * + * TODO: check if the requested memory is really available + * + * @return [description] + */ +caddr_t _sbrk_r(struct _reent *r, size_t incr) +{ + unsigned int state = disableIRQ(); + caddr_t res = heap_top; + heap_top += incr; + restoreIRQ(state); + return res; +} + +/** + * @brief Get the process-ID of the current thread + * + * @return the process ID of the current thread + */ +int _getpid(void) +{ + return sched_active_thread->pid; +} + +/** + * @brief Send a signal to a given thread + * + * @param r TODO + * @param pid TODO + * @param sig TODO + * + * @return TODO + */ +int _kill_r(struct _reent *r, int pid, int sig) +{ + r->_errno = ESRCH; /* not implemented yet */ + return -1; +} + +/** + * @brief Open a file + * + * @param r TODO + * @param name TODO + * @param mode TODO + * + * @return TODO + */ +int _open_r(struct _reent *r, const char *name, int mode) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Read from a file + * + * All input is read from UART_0. The function will block until a byte is actually read. + * + * Note: the read function does not buffer - data will be lost if the function is not + * called fast enough. + * + * TODO: implement more sophisticated read call. + * + * @param r TODO + * @param fd TODO + * @param buffer TODO + * @param int TODO + * + * @return TODO + */ +int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count) +{ + char c; + char *buff = (char*)buffer; + uart_read_blocking(STDIO, &c); + buff[0] = c; + return 1; +} + +/** + * @brief Write characters to a file + * + * All output is currently directed to UART_0, independent of the given file descriptor. + * The write call will further block until the byte is actually written to the UART. + * + * TODO: implement more sophisticated write call. + * + * @param r TODO + * @param fd TODO + * @param data TODO + * @param int TODO + * + * @return TODO + */ +int _write_r(struct _reent *r, int fd, const void *data, unsigned int count) +{ + char *c = (char*)data; + for (int i = 0; i < count; i++) { + uart_write_blocking(STDIO, c[i]); + } + return count; +} + +/** + * @brief Close a file + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _close_r(struct _reent *r, int fd) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Set position in a file + * + * @param r TODO + * @param fd TODO + * @param pos TODO + * @param dir TODO + * + * @return TODO + */ +_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of an open file + * + * @param r TODO + * @param fd TODO + * @param stat TODO + * + * @return TODO + */ +int _fstat_r(struct _reent *r, int fd, struct stat * st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of a file (by name) + * + * @param r TODO + * @param name TODO + * @param stat TODO + * + * @return TODO + */ +int _stat_r(struct _reent *r, char *name, struct stat *st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Query whether output stream is a terminal + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _isatty_r(struct _reent *r, int fd) +{ + r->_errno = 0; + return -1; +} + +/** + * @brief Remove a file's directory entry + * + * @param r TODO + * @param path TODO + * + * @return TODO + */ +int _unlink_r(struct _reent *r, char* path) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +}