diff --git a/boards/nucleo-f303/Makefile b/boards/nucleo-f303/Makefile new file mode 100755 index 0000000000..ff5489888b --- /dev/null +++ b/boards/nucleo-f303/Makefile @@ -0,0 +1,3 @@ +MODULE =$(BOARD)_base + +include $(RIOTBASE)/Makefile.base diff --git a/boards/nucleo-f303/Makefile.features b/boards/nucleo-f303/Makefile.features new file mode 100755 index 0000000000..50b9fd29a4 --- /dev/null +++ b/boards/nucleo-f303/Makefile.features @@ -0,0 +1,8 @@ +FEATURES_PROVIDED += cpp +FEATURES_PROVIDED += periph_cpuid +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_pwm +FEATURES_PROVIDED += periph_uart +FEATURES_PROVIDED += periph_i2c +FEATURES_PROVIDED += periph_spi +FEATURES_MCU_GROUP = cortex_m4 diff --git a/boards/nucleo-f303/Makefile.include b/boards/nucleo-f303/Makefile.include new file mode 100755 index 0000000000..abc0f862d9 --- /dev/null +++ b/boards/nucleo-f303/Makefile.include @@ -0,0 +1,16 @@ +## the cpu to build for +export CPU = stm32f3 +export CPU_MODEL = stm32f303re + +#define the default port depending on the host OS +PORT_LINUX ?= /dev/ttyUSB0 +PORT_DARWIN ?= $(shell ls -1 /dev/tty.usbmodem* | head -n 1) + +# setup serial terminal +include $(RIOTBOARD)/Makefile.include.serial + +# this board uses openocd +include $(RIOTBOARD)/Makefile.include.openocd + +# include cortex defaults +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/nucleo-f303/board.c b/boards/nucleo-f303/board.c new file mode 100755 index 0000000000..4490c318b2 --- /dev/null +++ b/boards/nucleo-f303/board.c @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2015 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 boards_nucleo-f303 + * @{ + * + * @file + * @brief Board specific implementations for the nucleo-f303 board + * + * @author Hauke Petersen + * + * @} + */ + +#include "board.h" +#include "cpu.h" + +static void leds_init(void); + +void board_init(void) +{ + /* initialize the boards LEDs */ + leds_init(); + /* initialize the CPU */ + cpu_init(); +} + +/** + * @brief Initialize the boards on-board LEDs + * + * The LED initialization is hard-coded in this function. + * As the LED is soldered onto the board it is fixed to + * its CPU pins. + * + * The green LED is connected to pin PA5 + */ +static void leds_init(void) +{ + /* enable clock for port GPIOA */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN; + /* set output speed to 50MHz */ + LED_GREEN_PORT->OSPEEDR |= 0x00000c00; + /* set output type to push-pull */ + LED_GREEN_PORT->OTYPER &= ~(0x00000020); + /* configure pin as general output */ + LED_GREEN_PORT->MODER &= ~(0x00000c00); + LED_GREEN_PORT->MODER |= 0x00000400; + /* disable pull resistors */ + LED_GREEN_PORT->PUPDR &= ~(0x00000c00); + /* turn all LEDs off */ + LED_GREEN_PORT->BRR = 0x00c0; +} diff --git a/boards/nucleo-f303/dist/openocd.cfg b/boards/nucleo-f303/dist/openocd.cfg new file mode 100755 index 0000000000..2489007535 --- /dev/null +++ b/boards/nucleo-f303/dist/openocd.cfg @@ -0,0 +1 @@ +source [find board/st_nucleo_f3.cfg] diff --git a/boards/nucleo-f303/include/board.h b/boards/nucleo-f303/include/board.h new file mode 100755 index 0000000000..484f62a8c2 --- /dev/null +++ b/boards/nucleo-f303/include/board.h @@ -0,0 +1,95 @@ +/* + * Copyright (C) 2015 Freie Universität Berlin + * Copyright (C) 2015 Hamburg University of Applied Sciences + * + * 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 boards_nucleo-f303 Nucleo-F303 + * @ingroup boards + * @brief Board specific files for the nucleo-f303 board + * @{ + * + * @file + * @brief Board specific definitions for the nucleo-f303 board + * + * @author Hauke Petersen + * @author Katja Kirstein + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#include + +#include "cpu.h" +#include "periph_conf.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Define the nominal CPU core clock in this board + */ +#define F_CPU CLOCK_CORECLOCK + +/** + * @name Define the UART to be used as stdio and its baudrate + * @{ + */ +#define STDIO UART_0 +#define STDIO_BAUDRATE (115200U) +#define STDIO_RX_BUFSIZE (64U) +/** @} */ + +/** + * @name Assign the hardware timer + */ +#define HW_TIMER TIMER_0 + +/** + * @name LED pin definitions + * @{ + */ +#define LED_GREEN_PORT (GPIOA) +#define LED_GREEN_PIN (5) +/** @} */ + +/** + * @name Macros for controlling the on-board LEDs. + * @{ + */ +#define LED_RED_ON +#define LED_RED_OFF +#define LED_RED_TOGGLE + +#define LED_GREEN_ON (LED_GREEN_PORT->BSRRL = (1 << LED_GREEN_PIN)) +#define LED_GREEN_OFF (LED_GREEN_PORT->BSRRH = (1 << LED_GREEN_PIN)) +#define LED_GREEN_TOGGLE (LED_GREEN_PORT->ODR ^= (1 << LED_GREEN_PIN)) + +#define LED_ORANGE_ON +#define LED_ORANGE_OFF +#define LED_ORANGE_TOGGLE +/** @} */ + +/** + * @name Define the type for the radio packet length for the transceiver + */ +typedef uint8_t radio_packet_length_t; + +/** + * @brief Initialize board specific hardware, including clock, LEDs and std-IO + */ +void board_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /* BOARD_H_ */ +/** @} */ +/** @} */ diff --git a/boards/nucleo-f303/include/periph_conf.h b/boards/nucleo-f303/include/periph_conf.h new file mode 100755 index 0000000000..9a394d3435 --- /dev/null +++ b/boards/nucleo-f303/include/periph_conf.h @@ -0,0 +1,290 @@ +/* + * Copyright (C) 2015 Freie Universität Berlin + * Copyright (C) 2015 Hamburg University of Applied Sciences + * + * 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 boards_nucleo-f303 Nucleo-F303 + * @{ + * + * @file + * @brief Peripheral MCU configuration for the nucleo-f303 board + * + * @author Hauke Petersen + * @author Katja Kirstein + */ + +#ifndef PERIPH_CONF_H_ +#define PERIPH_CONF_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Clock system configuration + * @{ + */ +#define CLOCK_HSE (8000000U) /* external oscillator */ +#define CLOCK_CORECLOCK (72000000U) /* desired core clock frequency */ + +/* the actual PLL values are automatically generated */ +#define CLOCK_PLL_MUL (CLOCK_CORECLOCK / CLOCK_HSE) +#define CLOCK_AHB_DIV RCC_CFGR_HPRE_DIV1 +#define CLOCK_APB2_DIV RCC_CFGR_PPRE2_DIV1 +#define CLOCK_APB1_DIV RCC_CFGR_PPRE1_DIV2 +#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY_1 +/** @} */ + +/** + * @brief Timer configuration + * @{ + */ +#define TIMER_NUMOF (1U) +#define TIMER_0_EN 1 +#define TIMER_IRQ_PRIO 1 + +/* Timer 0 configuration */ +#define TIMER_0_DEV TIM2 +#define TIMER_0_CHANNELS 4 +#define TIMER_0_PRESCALER (71U) +#define TIMER_0_MAX_VALUE (0xffffffff) +#define TIMER_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM2EN) +#define TIMER_0_IRQ_CHAN TIM2_IRQn +#define TIMER_0_ISR isr_tim2 +/** @} */ + +/** + * @brief UART configuration + * @{ + */ +#define UART_NUMOF (3U) +#define UART_0_EN 1 +#define UART_1_EN 1 +#define UART_2_EN 1 +#define UART_IRQ_PRIO 1 + +/* UART 0 device configuration */ +#define UART_0_DEV USART1 +#define UART_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_USART1EN) +#define UART_0_CLK (CLOCK_CORECLOCK / 1) /* UART clock runs with 72MHz (F_CPU / 1) */ +#define UART_0_IRQ_CHAN USART1_IRQn +#define UART_0_ISR isr_usart1 +/* UART 0 pin configuration */ +#define UART_0_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define UART_0_PORT GPIOA +#define UART_0_TX_PIN 9 +#define UART_0_RX_PIN 10 +#define UART_0_AF 7 + +/* UART 1 device configuration */ +#define UART_1_DEV USART2 +#define UART_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_USART2EN) +#define UART_1_CLK (CLOCK_CORECLOCK / 2) /* UART clock runs with 36MHz (F_CPU / 2) */ +#define UART_1_IRQ_CHAN USART2_IRQn +#define UART_1_ISR isr_usart2 +/* UART 1 pin configuration */ +#define UART_1_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define UART_1_PORT GPIOA +#define UART_1_TX_PIN 2 +#define UART_1_RX_PIN 3 +#define UART_1_AF 7 + +/* UART 2 device configuration */ +#define UART_2_DEV USART3 +#define UART_2_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_USART3EN) +#define UART_2_CLK (CLOCK_CORECLOCK / 2) /* UART clock runs with 36MHz (F_CPU / 2) */ +#define UART_2_IRQ_CHAN USART3_IRQn +#define UART_2_ISR isr_usart3 +/* UART 2 pin configuration */ +#define UART_2_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOBEN) +#define UART_2_PORT GPIOB +#define UART_2_TX_PIN 10 +#define UART_2_RX_PIN 11 +#define UART_2_AF 7 +/** @} */ + +/** + * @brief PWM configuration + * @{ + */ +#define PWM_NUMOF (1U) +#define PWM_0_EN 1 + +#define PWM_MAX_CHANNELS 4 + +/* PWM 0 device configuration */ +#define PWM_0_DEV TIM3 +#define PWM_0_CHANNELS 4 +#define PWM_0_CLK (36000000U) +#define PWM_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM3EN) +#define PWM_0_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) +/* PWM 0 pin configuration */ +#define PWM_0_PORT GPIOC +#define PWM_0_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN) +#define PWM_0_PIN_CH0 6 +#define PWM_0_PIN_CH1 7 +#define PWM_0_PIN_CH2 8 +#define PWM_0_PIN_CH3 9 +#define PWM_0_PIN_AF 2 +/** @} */ + +/** + * @name SPI configuration + * @{ + */ +#define SPI_NUMOF (2U) +#define SPI_0_EN 1 +#define SPI_1_EN 1 +#define SPI_IRQ_PRIO 1 + +/* SPI 0 device config */ +#define SPI_0_DEV SPI1 +#define SPI_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_SPI1EN) +#define SPI_0_CLKDIS() (RCC->APB2ENR &= ~RCC_APB2ENR_SPI1EN) +#define SPI_0_IRQ SPI1_IRQn +#define SPI_0_IRQ_HANDLER isr_spi1 +/* SPI 0 pin configuration */ +#define SPI_0_SCK_PORT GPIOA +#define SPI_0_SCK_PIN 5 +#define SPI_0_SCK_AF 5 +#define SPI_0_SCK_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define SPI_0_MISO_PORT GPIOA +#define SPI_0_MISO_PIN 6 +#define SPI_0_MISO_AF 5 +#define SPI_0_MISO_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define SPI_0_MOSI_PORT GPIOA +#define SPI_0_MOSI_PIN 7 +#define SPI_0_MOSI_AF 5 +#define SPI_0_MOSI_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) + +/* SPI 1 device config */ +#define SPI_1_DEV SPI3 +#define SPI_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_SPI3EN) +#define SPI_1_CLKDIS() (RCC->APB1ENR &= ~RCC_APB1ENR_SPI3EN) +#define SPI_1_IRQ SPI3_IRQn +#define SPI_1_IRQ_HANDLER isr_spi3 +/* SPI 1 pin configuration */ +#define SPI_1_SCK_PORT GPIOC +#define SPI_1_SCK_PIN 10 +#define SPI_1_SCK_AF 6 +#define SPI_1_SCK_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN) +#define SPI_1_MISO_PORT GPIOC +#define SPI_1_MISO_PIN 11 +#define SPI_1_MISO_AF 6 +#define SPI_1_MISO_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN) +#define SPI_1_MOSI_PORT GPIOC +#define SPI_1_MOSI_PIN 12 +#define SPI_1_MOSI_AF 6 +#define SPI_1_MOSI_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN) +/** @} */ + +/** + * @name I2C configuration + * @{ + */ +#define I2C_NUMOF (2U) +#define I2C_0_EN 1 +#define I2C_1_EN 1 +#define I2C_IRQ_PRIO 1 +#define I2C_APBCLK (36000000U) + +/* I2C 0 device configuration */ +#define I2C_0_DEV I2C1 +#define I2C_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_I2C1EN) +#define I2C_0_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN)) +#define I2C_0_EVT_IRQ I2C1_EV_IRQn +#define I2C_0_EVT_ISR isr_i2c1_ev +#define I2C_0_ERR_IRQ I2C1_ER_IRQn +#define I2C_0_ERR_ISR isr_i2c1_er +/* I2C 0 pin configuration */ +#define I2C_0_SCL_PORT GPIOB +#define I2C_0_SCL_PIN 8 +#define I2C_0_SCL_AF 4 +#define I2C_0_SCL_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOBEN) +#define I2C_0_SDA_PORT GPIOB +#define I2C_0_SDA_PIN 9 +#define I2C_0_SDA_AF 4 +#define I2C_0_SDA_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOBEN) + +/* I2C 1 device configuration */ +#define I2C_1_DEV I2C3 +#define I2C_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_I2C3EN) +#define I2C_1_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) +#define I2C_1_EVT_IRQ I2C3_EV_IRQn +#define I2C_1_EVT_ISR isr_i2c3_ev +#define I2C_1_ERR_IRQ I2C3_ER_IRQn +#define I2C_1_ERR_ISR isr_i2c3_er +/* I2C 1 pin configuration */ +#define I2C_1_SCL_PORT GPIOA +#define I2C_1_SCL_PIN 8 +#define I2C_1_SCL_AF 3 +#define I2C_1_SCL_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define I2C_1_SDA_PORT GPIOB +#define I2C_1_SDA_PIN 5 +#define I2C_1_SDA_AF 8 +#define I2C_1_SDA_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOBEN) +/** @} */ + +/** + * @brief GPIO configuration + * @{ + */ +#define GPIO_NUMOF 3 +#define GPIO_0_EN 1 +#define GPIO_1_EN 1 +#define GPIO_2_EN 1 +#define GPIO_IRQ_PRIO 1 + +/* IRQ config */ +#define GPIO_IRQ_0 GPIO_1 +#define GPIO_IRQ_1 (-1) /* not configured */ +#define GPIO_IRQ_2 GPIO_2 +#define GPIO_IRQ_3 (-1) /* not configured */ +#define GPIO_IRQ_4 (-1) /* not configured */ +#define GPIO_IRQ_5 (-1) /* not configured */ +#define GPIO_IRQ_6 (-1) /* not configured */ +#define GPIO_IRQ_7 (-1) /* not configured */ +#define GPIO_IRQ_8 (-1) /* not configured */ +#define GPIO_IRQ_9 (-1) /* not configured */ +#define GPIO_IRQ_10 (-1) /* not configured */ +#define GPIO_IRQ_11 (-1) /* not configured */ +#define GPIO_IRQ_12 (-1) /* not configured */ +#define GPIO_IRQ_13 GPIO_0 +#define GPIO_IRQ_14 (-1) /* not configured */ +#define GPIO_IRQ_15 (-1) /* not configured */ + +/* GPIO channel 0 config */ +#define GPIO_0_PORT GPIOC /* Used for user button 1 */ +#define GPIO_0_PIN 13 +#define GPIO_0_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN) +#define GPIO_0_EXTI_CFG1() (SYSCFG->EXTICR[3] &= ~(SYSCFG_EXTICR4_EXTI13)) +#define GPIO_0_EXTI_CFG2() (SYSCFG->EXTICR[3] |= SYSCFG_EXTICR4_EXTI13_PC) +#define GPIO_0_IRQ EXTI15_10_IRQn + +/* GPIO channel 1 config */ +#define GPIO_1_PORT GPIOA +#define GPIO_1_PIN 0 +#define GPIO_1_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define GPIO_1_EXTI_CFG1() (SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI0)) +#define GPIO_1_EXTI_CFG2() (SYSCFG->EXTICR[0] |= SYSCFG_EXTICR1_EXTI0_PA) +#define GPIO_1_IRQ EXTI0_IRQn + +/* GPIO channel 2 config */ +#define GPIO_2_PORT GPIOD +#define GPIO_2_PIN 2 +#define GPIO_2_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIODEN) +#define GPIO_2_EXTI_CFG1() (SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI2)) +#define GPIO_2_EXTI_CFG2() (SYSCFG->EXTICR[0] |= SYSCFG_EXTICR1_EXTI2_PD) +#define GPIO_2_IRQ EXTI2_TSC_IRQn +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H_ */ diff --git a/cpu/stm32f3/include/cpu_conf.h b/cpu/stm32f3/include/cpu_conf.h index e747e99f51..1a87ba968c 100644 --- a/cpu/stm32f3/include/cpu_conf.h +++ b/cpu/stm32f3/include/cpu_conf.h @@ -16,6 +16,7 @@ * @brief Implementation specific CPU configuration options * * @author Hauke Petersen + * @author Katja Kirstein */ #ifndef __CPU_CONF_H @@ -27,6 +28,9 @@ #ifdef CPU_MODEL_STM32F334R8 #include "stm32f334x8.h" #endif +#ifdef CPU_MODEL_STM32F303RE +#include "stm32f303xe.h" +#endif #ifdef __cplusplus extern "C" { diff --git a/cpu/stm32f3/include/stm32f303xe.h b/cpu/stm32f3/include/stm32f303xe.h new file mode 100644 index 0000000000..84be4571d0 --- /dev/null +++ b/cpu/stm32f3/include/stm32f303xe.h @@ -0,0 +1,8211 @@ +/** + ****************************************************************************** + * @file stm32f303xe.h + * @author MCD Application Team + * @version V2.1.0 + * @date 12-Sept-2014 + * @brief CMSIS STM32F303xE Devices 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_Device + * @{ + */ + +/** @addtogroup stm32f303xe + * @{ + */ + +#ifndef __STM32F303xE_H +#define __STM32F303xE_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 /*!< STM32F303xE devices provide an MPU */ +#define __NVIC_PRIO_BITS 4 /*!< STM32F303xE devices use 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1 /*!< STM32F303xE devices provide an FPU */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F303xE devices 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 19 */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line 20 */ + 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_TSC_IRQn = 8, /*!< EXTI Line2 Interrupt and Touch Sense Controller Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Channel1_IRQn = 11, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_IRQn = 12, /*!< DMA1 Channel 2 Interrupt */ + DMA1_Channel3_IRQn = 13, /*!< DMA1 Channel 3 Interrupt */ + DMA1_Channel4_IRQn = 14, /*!< DMA1 Channel 4 Interrupt */ + DMA1_Channel5_IRQn = 15, /*!< DMA1 Channel 5 Interrupt */ + DMA1_Channel6_IRQn = 16, /*!< DMA1 Channel 6 Interrupt */ + DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 Interrupt */ + ADC1_2_IRQn = 18, /*!< ADC1 & ADC2 Interrupts */ + USB_HP_CAN_TX_IRQn = 19, /*!< USB Device High Priority or CAN TX Interrupts */ + USB_LP_CAN_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN RX0 Interrupts */ + CAN_RX1_IRQn = 21, /*!< CAN RX1 Interrupt */ + CAN_SCE_IRQn = 22, /*!< CAN SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 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 & EXTI Line23 Interrupt (I2C1 wakeup) */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt & EXTI Line24 Interrupt (I2C2 wakeup) */ + 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 & EXTI Line25 Interrupt (USART1 wakeup) */ + USART2_IRQn = 38, /*!< USART2 global Interrupt & EXTI Line26 Interrupt (USART2 wakeup) */ + USART3_IRQn = 39, /*!< USART3 global Interrupt & EXTI Line28 Interrupt (USART3 wakeup) */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line 17 Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Wakeup Interrupt */ + TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ + TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ + TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FMC_IRQn = 48, /*!< FMC global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt & EXTI Line34 Interrupt (UART4 wakeup) */ + UART5_IRQn = 53, /*!< UART5 global Interrupt & EXTI Line35 Interrupt (UART5 wakeup) */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC channel 1&2 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_IRQn = 59, /*!< DMA2 Channel 4 global Interrupt */ + DMA2_Channel5_IRQn = 60, /*!< DMA2 Channel 5 global Interrupt */ + ADC4_IRQn = 61, /*!< ADC4 global Interrupt */ + COMP1_2_3_IRQn = 64, /*!< COMP1, COMP2 and COMP3 global Interrupt via EXTI Line21, 22 and 29*/ + COMP4_5_6_IRQn = 65, /*!< COMP4, COMP5 and COMP6 global Interrupt via EXTI Line30, 31 and 32*/ + COMP7_IRQn = 66, /*!< COMP7 global Interrupt via EXTI Line33 */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + USB_HP_IRQn = 74, /*!< USB High Priority global Interrupt remap */ + USB_LP_IRQn = 75, /*!< USB Low Priority global Interrupt remap */ + USBWakeUp_RMP_IRQn = 76, /*!< USB Wakeup Interrupt remap */ + TIM20_BRK_IRQn = 77, /*!< TIM20 Break Interrupt */ + TIM20_UP_IRQn = 78, /*!< TIM20 Update Interrupt */ + TIM20_TRG_COM_IRQn = 79, /*!< TIM20 Trigger and Commutation Interrupt */ + TIM20_CC_IRQn = 80, /*!< TIM20 Capture Compare Interrupt */ + FPU_IRQn = 81, /*!< Floating point Interrupt */ + SPI4_IRQn = 84, /*!< SPI4 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 ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ + __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ + uint32_t RESERVED0; /*!< Reserved, 0x010 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ + uint32_t RESERVED1; /*!< Reserved, 0x01C */ + __IO uint32_t TR1; /*!< ADC watchdog threshold register 1, Address offset: 0x20 */ + __IO uint32_t TR2; /*!< ADC watchdog threshold register 2, Address offset: 0x24 */ + __IO uint32_t TR3; /*!< ADC watchdog threshold register 3, Address offset: 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x02C */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ + __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ + uint32_t RESERVED3; /*!< Reserved, 0x044 */ + uint32_t RESERVED4; /*!< Reserved, 0x048 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ + uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ + __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ + __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ + __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ + __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ + uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ + uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ + __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ + __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ + uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ + uint32_t RESERVED9; /*!< Reserved, 0x0AC */ + __IO uint32_t DIFSEL; /*!< ADC Differential Mode Selection Register, Address offset: 0xB0 */ + __IO uint32_t CALFACT; /*!< ADC Calibration Factors, Address offset: 0xB4 */ + +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ + uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1/3 base address + 0x30C */ +} 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 Analog Comparators + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< Comparator control Status register, Address offset: 0x00 */ +} COMP_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 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +} 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 DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt clear flag register, Address offset: 0x04 */ +} DMA_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 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ + __IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x24 */ + __IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x28 */ + __IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x2C */ + __IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x30 */ + __IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x34 */ +}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 AR; /*!< FLASH address register, Address offset: 0x14 */ + uint32_t RESERVED; /*!< Reserved, 0x18 */ + __IO uint32_t OBR; /*!< FLASH Option byte register, Address offset: 0x1C */ + __IO uint32_t WRPR; /*!< FLASH Write register, Address offset: 0x20 */ + +} FLASH_TypeDef; + +/** + * @brief Flexible 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 */ +} FMC_Bank1_TypeDef; + +/** + * @brief Flexible Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FMC_Bank1E_TypeDef; + +/** + * @brief Flexible 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 */ +} FMC_Bank2_3_TypeDef; + +/** + * @brief Flexible 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 */ +} FMC_Bank4_TypeDef; + +/** + * @brief Option Bytes Registers + */ +typedef struct +{ + __IO uint16_t RDP; /*! + * @author Katja Kirstein + * + * @} + */ + +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + ccmram (rwx): ORIGIN = 0x10000000, LENGTH = 16K +} + +INCLUDE cortexm_base.ld