diff --git a/boards/nucleo-f302/Makefile b/boards/nucleo-f302/Makefile new file mode 100755 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/nucleo-f302/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/nucleo-f302/Makefile.dep b/boards/nucleo-f302/Makefile.dep new file mode 100644 index 0000000000..76e2dc17b4 --- /dev/null +++ b/boards/nucleo-f302/Makefile.dep @@ -0,0 +1 @@ +include $(RIOTBOARD)/nucleo-common/Makefile.dep diff --git a/boards/nucleo-f302/Makefile.features b/boards/nucleo-f302/Makefile.features new file mode 100755 index 0000000000..d9943201de --- /dev/null +++ b/boards/nucleo-f302/Makefile.features @@ -0,0 +1,14 @@ +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_cpuid +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_i2c +FEATURES_PROVIDED += periph_pwm +FEATURES_PROVIDED += periph_spi +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart + +# load the common Makefile.features for Nucleo boards +include $(RIOTBOARD)/nucleo-common/Makefile.features + +# The board MPU family (used for grouping by the CI system) +FEATURES_MCU_GROUP = cortex_m4_2 diff --git a/boards/nucleo-f302/Makefile.include b/boards/nucleo-f302/Makefile.include new file mode 100755 index 0000000000..2495336993 --- /dev/null +++ b/boards/nucleo-f302/Makefile.include @@ -0,0 +1,6 @@ +# the cpu to build for +export CPU = stm32f3 +export CPU_MODEL = stm32f302r8 + +# load the common Makefile.include for Nucleo boards +include $(RIOTBOARD)/nucleo-common/Makefile.include diff --git a/boards/nucleo-f302/board.c b/boards/nucleo-f302/board.c new file mode 100755 index 0000000000..d291b0e2a3 --- /dev/null +++ b/boards/nucleo-f302/board.c @@ -0,0 +1,31 @@ +/* + * 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 "periph/gpio.h" + +void board_init(void) +{ + /* initialize the CPU */ + cpu_init(); + + /* initialize the boards LEDs */ + gpio_init(LED0_PIN, GPIO_OUT); +} diff --git a/boards/nucleo-f302/dist/openocd.cfg b/boards/nucleo-f302/dist/openocd.cfg new file mode 100755 index 0000000000..2489007535 --- /dev/null +++ b/boards/nucleo-f302/dist/openocd.cfg @@ -0,0 +1 @@ +source [find board/st_nucleo_f3.cfg] diff --git a/boards/nucleo-f302/include/board.h b/boards/nucleo-f302/include/board.h new file mode 100755 index 0000000000..2fde66d2d6 --- /dev/null +++ b/boards/nucleo-f302/include/board.h @@ -0,0 +1,62 @@ +/* + * Copyright (C) 2017 Inria + * 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-f302 Nucleo-F302 + * @ingroup boards + * @brief Board specific files for the nucleo-f302 board + * @{ + * + * @file + * @brief Board specific definitions for the nucleo-f302 board + * + * @author Alexandre Abadie + * @author Hauke Petersen + * @author Katja Kirstein + */ + +#ifndef BOARD_H +#define BOARD_H + +#include "cpu.h" +#include "periph_conf.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LED pin definitions and handlers + * @{ + */ +#define LED0_PIN GPIO_PIN(PORT_B, 13) +#define LED0_MASK (1 << 13) + +#define LED0_ON (GPIOB->BSRR = LED0_MASK) +#define LED0_OFF (GPIOB->BSRR = (LED0_MASK << 16)) +#define LED0_TOGGLE (GPIOB->ODR ^= LED0_MASK) +/** @} */ + +/** + * @brief User button + */ +#define BTN_B1_PIN GPIO_PIN(PORT_C, 13) + +/** + * @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-f302/include/periph_conf.h b/boards/nucleo-f302/include/periph_conf.h new file mode 100755 index 0000000000..2eef01dd34 --- /dev/null +++ b/boards/nucleo-f302/include/periph_conf.h @@ -0,0 +1,240 @@ +/* + * Copyright (C) 2017 Inria + * 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-f302 Nucleo-F302 + * @{ + * + * @file + * @brief Peripheral MCU configuration for the nucleo-f302 board + * + * @author Alexandre Abadie + * @author Hauke Petersen + * @author Katja Kirstein + */ + +#ifndef PERIPH_CONF_H +#define PERIPH_CONF_H + +#include "periph_cpu.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 + +/* bus clocks for simplified peripheral initialization, UPDATE MANUALLY! */ +#define CLOCK_AHB (CLOCK_CORECLOCK / 1) +#define CLOCK_APB2 (CLOCK_CORECLOCK / 1) +#define CLOCK_APB1 (CLOCK_CORECLOCK / 2) +/** @} */ + +/** + * @name ADC configuration + * @{ + */ +#define ADC_NUMOF (0) +/** @} */ + +/** + * @name DAC configuration + * @{ + */ +#define DAC_NUMOF (0) +/** @} */ + +/** + * @name Timer configuration + * @{ + */ +static const timer_conf_t timer_config[] = { + { + .dev = TIM2, + .max = 0xffffffff, + .rcc_mask = RCC_APB1ENR_TIM2EN, + .bus = APB1, + .irqn = TIM2_IRQn + } +}; + +#define TIMER_0_ISR isr_tim2 + +#define TIMER_NUMOF (sizeof(timer_config) / sizeof(timer_config[0])) +/** @} */ + +/** + * @name UART configuration + * @{ + */ +static const uart_conf_t uart_config[] = { + { + .dev = USART2, + .rcc_mask = RCC_APB1ENR_USART2EN, + .rx_pin = GPIO_PIN(PORT_A, 3), + .tx_pin = GPIO_PIN(PORT_A, 2), + .rx_af = GPIO_AF7, + .tx_af = GPIO_AF7, + .bus = APB1, + .irqn = USART2_IRQn + }, + { + .dev = USART1, + .rcc_mask = RCC_APB2ENR_USART1EN, + .rx_pin = GPIO_PIN(PORT_A, 10), + .tx_pin = GPIO_PIN(PORT_A, 9), + .rx_af = GPIO_AF7, + .tx_af = GPIO_AF7, + .bus = APB2, + .irqn = USART1_IRQn + }, + { + .dev = USART3, + .rcc_mask = RCC_APB1ENR_USART3EN, + .rx_pin = GPIO_PIN(PORT_C, 11), + .tx_pin = GPIO_PIN(PORT_C, 10), + .rx_af = GPIO_AF7, + .tx_af = GPIO_AF7, + .bus = APB1, + .irqn = USART3_IRQn + } +}; + +#define UART_0_ISR (isr_usart2) +#define UART_1_ISR (isr_usart1) +#define UART_2_ISR (isr_usart3) + +#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0])) +/** @} */ + +/** + * @name PWM configuration + * @{ + */ +static const pwm_conf_t pwm_config[] = { + { + .dev = TIM16, + .rcc_mask = RCC_APB2ENR_TIM16EN, + .chan = { { .pin = GPIO_PIN(PORT_B, 4) /* D5 */, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 }, + { .pin = GPIO_UNDEF, .cc_chan = 0 } }, + .af = GPIO_AF1, + .bus = APB2 + } +}; + +#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0])) +/** @} */ + +/** + * @name SPI configuration + * + * @note The spi_divtable is auto-generated from + * `cpu/stm32_common/dist/spi_divtable/spi_divtable.c` + * @{ + */ +static const uint8_t spi_divtable[2][5] = { + { /* for APB1 @ 36000000Hz */ + 7, /* -> 140625Hz */ + 6, /* -> 281250Hz */ + 4, /* -> 1125000Hz */ + 2, /* -> 4500000Hz */ + 1 /* -> 9000000Hz */ + }, + { /* for APB2 @ 72000000Hz */ + 7, /* -> 281250Hz */ + 7, /* -> 281250Hz */ + 5, /* -> 1125000Hz */ + 3, /* -> 4500000Hz */ + 2 /* -> 9000000Hz */ + } +}; + +static const spi_conf_t spi_config[] = { + { + .dev = SPI2, + .mosi_pin = GPIO_PIN(PORT_B, 15), + .miso_pin = GPIO_PIN(PORT_B, 14), + .sclk_pin = GPIO_PIN(PORT_B, 13), + .cs_pin = GPIO_PIN(PORT_B, 12), + .af = GPIO_AF5, + .rccmask = RCC_APB1ENR_SPI2EN, + .apbbus = APB1 + } +}; + +#define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0])) +/** @} */ + +/** + * @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() (periph_clk_en(APB1, RCC_APB1ENR_I2C1EN)) +#define I2C_0_CLKDIS() (periph_clk_dis(APB1, 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() (periph_clk_en(AHB, 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() (periph_clk_en(AHB, RCC_AHBENR_GPIOBEN)) + +/* I2C 1 device configuration */ +#define I2C_1_DEV I2C3 +#define I2C_1_CLKEN() (periph_clk_en(APB1, RCC_APB1ENR_I2C3EN)) +#define I2C_1_CLKDIS() (periph_clk_dis(APB1, 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() (periph_clk_en(AHB, 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() (periph_clk_en(AHB, RCC_AHBENR_GPIOBEN)) +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H */ diff --git a/cpu/stm32f3/include/cpu_conf.h b/cpu/stm32f3/include/cpu_conf.h index 0f86d475b6..cf59fb03b3 100644 --- a/cpu/stm32f3/include/cpu_conf.h +++ b/cpu/stm32f3/include/cpu_conf.h @@ -36,6 +36,9 @@ #ifdef CPU_MODEL_STM32F303K8 #include "vendor/stm32f303x8.h" #endif +#ifdef CPU_MODEL_STM32F302R8 +#include "vendor/stm32f302x8.h" +#endif #ifdef __cplusplus extern "C" { #endif diff --git a/cpu/stm32f3/include/vendor/stm32f302x8.h b/cpu/stm32f3/include/vendor/stm32f302x8.h new file mode 100644 index 0000000000..42b97307fa --- /dev/null +++ b/cpu/stm32f3/include/vendor/stm32f302x8.h @@ -0,0 +1,12296 @@ +/** + ****************************************************************************** + * @file stm32f302x8.h + * @author MCD Application Team + * @version V2.3.0 + * @date 29-April-2015 + * @brief CMSIS STM32F302x8 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) 2016 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 stm32f302x8 + * @{ + */ + +#ifndef __STM32F302x8_H +#define __STM32F302x8_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 0x0001U /*!< Core revision r0p1 */ +#define __MPU_PRESENT 0U /*!< STM32F302x8 devices do not provide an MPU */ +#define __NVIC_PRIO_BITS 4U /*!< STM32F302x8 devices use 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1U /*!< STM32F302x8 devices provide an FPU */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F302x8 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 */ + HardFault_IRQn = -13, /*!< 3 Cortex-M4 Hard Fault 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_IRQn = 18, /*!< ADC1 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 */ + 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 */ + 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 */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC underrun error Interrupt */ + COMP2_IRQn = 64, /*!< COMP2 global Interrupt via EXTI Line22 */ + COMP4_6_IRQn = 65, /*!< COMP4 and COMP6 global Interrupt via EXTI Line30 and 32 */ + I2C3_EV_IRQn = 72, /*!< I2C3 Event Interrupt & EXTI Line27 Interrupt (I2C3 wakeup) */ + I2C3_ER_IRQn = 73, /*!< I2C3 Error Interrupt */ + USB_HP_IRQn = 74, /*!< USB High Priority global Interrupt */ + USB_LP_IRQn = 75, /*!< USB Low Priority global Interrupt */ + USBWakeUp_RMP_IRQn = 76, /*!< USB Wakeup Interrupt remap */ + FPU_IRQn = 81, /*!< Floating point Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ + +/** @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; /*!< COMP control and status register, Address offset: 0x00 */ +} COMP_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ +} COMP_Common_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 RESERVED0; /*!< Reserved, 0x14 */ + __IO uint32_t RESERVED1; /*!< Reserved, 0x18 */ + __IO uint32_t RESERVED2; /*!< Reserved, 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 RESERVED3; /*!< Reserved, 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 flag clear register, Address offset: 0x04 */ +} DMA_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*! + * + * @} + */ + +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K + cpuid (r) : ORIGIN = 0x1ffff7ac, LENGTH = 12 +} + +_cpuid_address = ORIGIN(cpuid); + +INCLUDE cortexm_base.ld diff --git a/examples/dtls-echo/Makefile b/examples/dtls-echo/Makefile index db3cd4268f..eb16354eba 100644 --- a/examples/dtls-echo/Makefile +++ b/examples/dtls-echo/Makefile @@ -15,9 +15,9 @@ BOARD_BLACKLIST := arduino-duemilanove arduino-mega2560 arduino-uno chronos \ BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk maple-mini \ microbit nrf51dongle nrf6310 nucleo32-f031 \ - nucleo32-f042 nucleo32-f303 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f103 nucleo-f334 nucleo-l053 \ - nucleo-l073 nucleo32-l031 opencm904 pca10000 pca10005 \ + nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ + nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f302 nucleo-f334 \ + nucleo-l053 nucleo-l073 opencm904 pca10000 pca10005 \ spark-core stm32f0discovery weio yunjia-nrf51822 # Include packages that pull up and auto-init the link layer. diff --git a/examples/emcute/Makefile b/examples/emcute/Makefile index a2ab0a5ccc..5d187d2cda 100644 --- a/examples/emcute/Makefile +++ b/examples/emcute/Makefile @@ -10,8 +10,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := arduino-duemilanove arduino-mega2560 arduino-uno \ chronos msb-430 msb-430h nucleo32-f031 nucleo32-f042 \ nucleo32-f303 nucleo32-l031 nucleo-f030 nucleo-f070 \ - nucleo-f072 nucleo-f334 nucleo-l053 stm32f0discovery \ - telosb waspmote-pro weio wsn430-v1_3b wsn430-v1_4 z1 + nucleo-f072 nucleo-f302 nucleo-f334 nucleo-l053 \ + stm32f0discovery telosb waspmote-pro weio wsn430-v1_3b \ + wsn430-v1_4 z1 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/gnrc_border_router/Makefile b/examples/gnrc_border_router/Makefile index 060175adcb..693078d58f 100644 --- a/examples/gnrc_border_router/Makefile +++ b/examples/gnrc_border_router/Makefile @@ -10,9 +10,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk maple-mini \ microbit msb-430 msb-430h nrf51dongle nrf6310 \ nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo32-l031 \ - nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ - nucleo-l053 nucleo-l073 opencm904 pca10000 pca10005 \ - spark-core stm32f0discovery telosb weio wsn430-v1_3b \ + nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f302 \ + nucleo-f334 nucleo-l053 nucleo-l073 opencm904 pca10000 \ + pca10005 spark-core stm32f0discovery telosb weio wsn430-v1_3b \ wsn430-v1_4 yunjia-nrf51822 z1 BOARD_BLACKLIST += mips-malta # No UART available. diff --git a/examples/gnrc_networking/Makefile b/examples/gnrc_networking/Makefile index 9c2b85e453..871dace296 100644 --- a/examples/gnrc_networking/Makefile +++ b/examples/gnrc_networking/Makefile @@ -9,9 +9,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := calliope-mini chronos microbit msb-430 msb-430h \ nucleo32-f031 nucleo32-f042 nucleo32-f303 nucleo32-l031 \ - nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 \ - nucleo-l053 spark-core stm32f0discovery telosb weio \ - wsn430-v1_3b wsn430-v1_4 z1 + nucleo-f030 nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f302 \ + nucleo-f334 nucleo-l053 spark-core stm32f0discovery telosb \ + weio wsn430-v1_3b wsn430-v1_4 z1 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/examples/gnrc_tftp/Makefile b/examples/gnrc_tftp/Makefile index 4003de289a..6930b807b9 100644 --- a/examples/gnrc_tftp/Makefile +++ b/examples/gnrc_tftp/Makefile @@ -10,9 +10,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f334 nucleo-l053 \ - pca10000 pca10005 spark-core stm32f0discovery telosb \ - weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + nucleo-f070 nucleo-f072 nucleo-f103 nucleo-f302 nucleo-f334 \ + nucleo-l053 pca10000 pca10005 spark-core stm32f0discovery \ + telosb weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # Include packages that pull up and auto-init the link layer. # NOTE: 6LoWPAN will be included if IEEE802.15.4 devices are present diff --git a/tests/gnrc_tcp_client/Makefile b/tests/gnrc_tcp_client/Makefile index cf47660442..3b444f1fcd 100644 --- a/tests/gnrc_tcp_client/Makefile +++ b/tests/gnrc_tcp_client/Makefile @@ -14,9 +14,9 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ arduino-uno calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f334 nucleo-l053 pca10000 \ - pca10005 sb-430 sb-430h stm32f0discovery telosb weio \ - wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + nucleo-f070 nucleo-f072 nucleo-f302 nucleo-f334 nucleo-l053 \ + pca10000 pca10005 sb-430 sb-430h stm32f0discovery telosb \ + weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # This has to be the absolute path to the RIOT base directory: RIOTBASE ?= $(CURDIR)/../.. diff --git a/tests/gnrc_tcp_server/Makefile b/tests/gnrc_tcp_server/Makefile index b7c893c97c..9b5bbcd458 100644 --- a/tests/gnrc_tcp_server/Makefile +++ b/tests/gnrc_tcp_server/Makefile @@ -12,9 +12,9 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ arduino-uno calliope-mini chronos microbit msb-430 \ msb-430h nrf51dongle nrf6310 nucleo32-f031 \ nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f334 nucleo-l053 pca10000 \ - pca10005 sb-430 sb-430h stm32f0discovery telosb weio \ - wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + nucleo-f070 nucleo-f072 nucleo-f302 nucleo-f334 nucleo-l053 \ + pca10000 pca10005 sb-430 sb-430h stm32f0discovery telosb \ + weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 # This has to be the absolute path to the RIOT base directory: RIOTBASE ?= $(CURDIR)/../.. diff --git a/tests/lwip/Makefile b/tests/lwip/Makefile index 7a8dc63709..e49964e3e5 100644 --- a/tests/lwip/Makefile +++ b/tests/lwip/Makefile @@ -8,9 +8,9 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_BLACKLIST := arduino-mega2560 msb-430h telosb waspmote-pro z1 arduino-uno \ arduino-duemilanove msb-430 wsn430-v1_4 wsn430-v1_3b BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-mega2560 msb-430h nrf6310 \ - nucleo32-f031 nucleo-f030 nucleo-f072 nucleo-f334 \ - nucleo-l053 pca10005 stm32f0discovery telosb weio \ - yunjia-nrf51822 z1 + nucleo32-f031 nucleo-f030 nucleo-f072 nucleo-f302 \ + nucleo-f334 nucleo-l053 pca10005 stm32f0discovery \ + telosb weio yunjia-nrf51822 z1 # including lwip_ipv6_mld would currently break this test on at86rf2xx radios USEMODULE += lwip lwip_ipv6_autoconfig lwip_conn_ip lwip_netdev diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index ec8944ddb0..3bef4324bf 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -5,8 +5,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon calliope-mini cc2650stk chronos maple- mbed_lpc1768 microbit msb-430 msb-430h nrf51dongle \ nrf6310 nucleo32-f031 nucleo32-f042 nucleo32-f303 \ nucleo32-l031 nucleo-f030 nucleo-f070 nucleo-f072 \ - nucleo-f103 nucleo-f334 nucleo-l053 nucleo-l073 opencm904 \ - pca10000 pca10005 spark-core stm32f0discovery weio \ + nucleo-f103 nucleo-f302 nucleo-f334 nucleo-l053 nucleo-l073 \ + opencm904 pca10000 pca10005 spark-core stm32f0discovery weio \ yunjia-nrf51822 DISABLE_MODULE += auto_init diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index 6119fe7835..4e5a94697a 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -6,8 +6,8 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon arduino-duemilanove arduino-mega2560 \ chronos ek-lm4f120xl limifrog-v1 maple-mini microbit \ msb-430 msb-430h nrf51dongle nrf6310 nucleo32-f031 \ nucleo32-f042 nucleo32-f303 nucleo32-l031 nucleo-f030 \ - nucleo-f070 nucleo-f072 nucleo-f091 nucleo-f103 nucleo-f334 \ - nucleo-f410 nucleo-l053 nucleo-l073 opencm904 \ + nucleo-f070 nucleo-f072 nucleo-f091 nucleo-f103 nucleo-f302 \ + nucleo-f334 nucleo-f410 nucleo-l053 nucleo-l073 opencm904 \ pba-d-01-kw2x pca10000 pca10005 remote-pa remote-reva \ remote-revb saml21-xpro samr21-xpro seeeduino_arch-pro \ slwstk6220a sodaq-autonomo spark-core stm32f0discovery \ @@ -28,7 +28,7 @@ DISABLE_TEST_FOR_ARM7 := tests-relic ARM_CORTEX_M_BOARDS := airfy-beacon arduino-due arduino-zero cc2538dk ek-lm4f120xl \ f4vi1 fox frdm-k64f iotlab-m3 limifrog-v1 mbed_lpc1768 msbiot \ mulle nrf51dongle nrf6310 nucleo32-f031 nucleo32-f303 nucleo32-l031 \ - nucleo-f030 nucleo-f070 nucleo-f091 nucleo-f303 nucleo-f334 \ + nucleo-f030 nucleo-f070 nucleo-f091 nucleo-f302 nucleo-f303 nucleo-f334 \ nucleo-f401 nucleo-f410 nucleo-f411 nucleo-l053 nucleo-l073 \ nucleo-l1 opencm904 openmote-cc2538 pba-d-01-kw2x pca10000 \ pca10005 remote saml21-xpro samr21-xpro slwstk6220a sodaq-autonomo \