diff --git a/boards/nucleo-f072/Makefile b/boards/nucleo-f072/Makefile new file mode 100644 index 000000000000..f8fcbb53a065 --- /dev/null +++ b/boards/nucleo-f072/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/nucleo-f072/Makefile.features b/boards/nucleo-f072/Makefile.features new file mode 100644 index 000000000000..c7f508057a7c --- /dev/null +++ b/boards/nucleo-f072/Makefile.features @@ -0,0 +1,12 @@ +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_cpuid +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_rtc +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart + +# Various other features (if any) +FEATURES_PROVIDED += cpp + +# The board MPU family (used for grouping by the CI system) +FEATURES_MCU_GROUP = cortex_m0_1 diff --git a/boards/nucleo-f072/Makefile.include b/boards/nucleo-f072/Makefile.include new file mode 100644 index 000000000000..8dbbd486270b --- /dev/null +++ b/boards/nucleo-f072/Makefile.include @@ -0,0 +1,15 @@ +## the cpu to build for +export CPU = stm32f0 +export CPU_MODEL = stm32f072rb + +#define the default port depending on the host OS +PORT_LINUX ?= /dev/ttyACM0 +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 $(RIOTBOARD)/nucleo-common/Makefile.include diff --git a/boards/nucleo-f072/board.c b/boards/nucleo-f072/board.c new file mode 100644 index 000000000000..9737786a8a22 --- /dev/null +++ b/boards/nucleo-f072/board.c @@ -0,0 +1,33 @@ +/* + * 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-f072 + * @{ + * + * @file + * @brief Board specific implementations for the nucleo-f072 board + * + * @author Hauke Petersen + * @author José Alamos + * + * @} + */ + +#include "board.h" +#include "periph/gpio.h" + + +void board_init(void) +{ + /* initialize the boards LED */ + gpio_init(LED0_PIN, GPIO_OUT); + + /* initialize the CPU */ + cpu_init(); +} diff --git a/boards/nucleo-f072/dist/openocd.cfg b/boards/nucleo-f072/dist/openocd.cfg new file mode 100644 index 000000000000..4f0cfb3a023b --- /dev/null +++ b/boards/nucleo-f072/dist/openocd.cfg @@ -0,0 +1 @@ +source [find board/st_nucleo_f0.cfg] diff --git a/boards/nucleo-f072/include/board.h b/boards/nucleo-f072/include/board.h new file mode 100644 index 000000000000..5caf4ded0236 --- /dev/null +++ b/boards/nucleo-f072/include/board.h @@ -0,0 +1,47 @@ +/* + * 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. + */ + +/** + * @defgroup boards_nucleo-f072 Nucleo-F072 + * @ingroup boards + * @brief Board specific files for the nucleo-f072 board + * @{ + * + * @file + * @brief Board specific definitions for the nucleo-f072 board + * + * @author Hauke Petersen + * @author Mohmmad Ayman + * @author José Alamos + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#include +#include "board_common.h" + +#include "cpu.h" +#include "periph_conf.h" + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @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-f072/include/periph_conf.h b/boards/nucleo-f072/include/periph_conf.h new file mode 100644 index 000000000000..46bd5826670a --- /dev/null +++ b/boards/nucleo-f072/include/periph_conf.h @@ -0,0 +1,135 @@ +/* + * 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-f072 + * @{ + * + * @file + * @brief Peripheral MCU configuration for the nucleo-f072 board + * + * @author Hauke Petersen + * @author José Ignacio Alamos + */ + +#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 (48000000U) /* desired core clock frequency */ + +/* the actual PLL values are automatically generated */ +#define CLOCK_PLL_MUL (CLOCK_CORECLOCK / CLOCK_HSE) +/** @} */ + +/** + * @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_FREQ (CLOCK_CORECLOCK) +#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 (2U) +#define UART_0_EN 1 +#define UART_1_EN 1 +#define UART_IRQ_PRIO 1 + +/* UART 0 device configuration */ +#define UART_0_DEV USART2 +#define UART_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_USART2EN) +#define UART_0_CLKDIS() (RCC->APB1ENR &= (~RCC_APB1ENR_USART2EN)) +#define UART_0_IRQ USART2_IRQn +#define UART_0_ISR isr_usart2 +/* UART 0 pin configuration */ +#define UART_0_PORT GPIOA +#define UART_0_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOAEN) +#define UART_0_RX_PIN 3 +#define UART_0_TX_PIN 2 +#define UART_0_AF 1 + +/* UART 1 device configuration */ +#define UART_1_DEV USART1 +#define UART_1_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_USART1EN) +#define UART_1_CLKDIS() (RCC->APB2ENR &= (~RCC_APB2ENR_USART1EN)) +#define UART_1_IRQ USART1_IRQn +#define UART_1_ISR isr_usart1 +/* UART 1 pin configuration */ +#define UART_1_PORT GPIOB +#define UART_1_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOBEN) +#define UART_1_RX_PIN 7 +#define UART_1_TX_PIN 6 +#define UART_1_AF 0 +/** @} */ + + +/** + * @brief ADC configuration + * @{ + */ +#define ADC_CONFIG { \ + { GPIO_PIN(PORT_A, 0), 0 },\ + { GPIO_PIN(PORT_A, 1), 1 },\ + { GPIO_PIN(PORT_A, 4), 4 },\ + { GPIO_PIN(PORT_B, 0), 8 },\ + { GPIO_PIN(PORT_C, 1), 11 },\ + { GPIO_PIN(PORT_C, 0), 10 } \ +} + +#define ADC_NUMOF (6) + +/** @} */ + + +/** + * @brief DAC configuration + * @{ + */ +#define DAC_NUMOF (0) +/** @} */ + +/** + * @name RTC configuration + * @{ + */ +/** + * Nucleos with MB1136 C-02 or MB1136 C-03 -sticker on it have the required LSE + * oscillator provided on the X2 slot. + * See Nucleo User Manual UM1724 section 5.6.2. + */ +#define RTC_NUMOF (1U) +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H_ */ +/** @} */ diff --git a/cpu/stm32f0/include/cpu_conf.h b/cpu/stm32f0/include/cpu_conf.h index b12c10397147..9bc269bb12ea 100644 --- a/cpu/stm32f0/include/cpu_conf.h +++ b/cpu/stm32f0/include/cpu_conf.h @@ -29,6 +29,9 @@ #ifdef CPU_MODEL_STM32F091RC #include "stm32f091xc.h" #endif +#ifdef CPU_MODEL_STM32F072RB +#include "stm32f072xb.h" +#endif #ifdef __cplusplus extern "C" { diff --git a/cpu/stm32f0/include/stm32f072xb.h b/cpu/stm32f0/include/stm32f072xb.h new file mode 100755 index 000000000000..ac8dabcfd2b6 --- /dev/null +++ b/cpu/stm32f0/include/stm32f072xb.h @@ -0,0 +1,5990 @@ +/** + ****************************************************************************** + * @file stm32f072xb.h + * @author MCD Application Team + * @version V2.2.3 + * @date 29-January-2016 + * @brief CMSIS Cortex-M0 Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for STM32F0xx devices. + * + * 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 + * @{ + */ + +/** @addtogroup stm32f072xb + * @{ + */ + +#ifndef __STM32F072xB_H +#define __STM32F072xB_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + + /** @addtogroup Configuration_section_for_CMSIS + * @{ + */ +/** + * @brief Configuration of the Cortex-M0 Processor and Core Peripherals + */ +#define __CM0_REV 0 /*!< Core Revision r0p0 */ +#define __MPU_PRESENT 0 /*!< STM32F0xx do not provide MPU */ +#define __NVIC_PRIO_BITS 2 /*!< STM32F0xx uses 2 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F0xx Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ + + /*!< Interrupt Number Definition */ +typedef enum +{ +/****** Cortex-M0 Processor Exceptions Numbers **************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M0 Hard Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M0 System Tick Interrupt */ + +/****** STM32F0 specific Interrupt Numbers ******************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_VDDIO2_IRQn = 1, /*!< PVD & VDDIO2 Interrupt through EXTI Lines 16 and 31 */ + RTC_IRQn = 2, /*!< RTC Interrupt through EXTI Lines 17, 19 and 20 */ + FLASH_IRQn = 3, /*!< FLASH global Interrupt */ + RCC_CRS_IRQn = 4, /*!< RCC & CRS global Interrupt */ + EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupt */ + EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupt */ + EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupt */ + TSC_IRQn = 8, /*!< Touch Sensing Controller Interrupts */ + DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupt */ + DMA1_Channel4_5_6_7_IRQn = 11, /*!< DMA1 Channel 4 to Channel 7 Interrupt */ + ADC1_COMP_IRQn = 12, /*!< ADC1 and COMP interrupts (ADC interrupt combined with EXTI Lines 21 and 22 */ + TIM1_BRK_UP_TRG_COM_IRQn = 13, /*!< TIM1 Break, Update, Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 14, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 15, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 16, /*!< TIM3 global Interrupt */ + TIM6_DAC_IRQn = 17, /*!< TIM6 global and DAC channel underrun error Interrupt */ + TIM7_IRQn = 18, /*!< TIM7 global Interrupt */ + TIM14_IRQn = 19, /*!< TIM14 global Interrupt */ + TIM15_IRQn = 20, /*!< TIM15 global Interrupt */ + TIM16_IRQn = 21, /*!< TIM16 global Interrupt */ + TIM17_IRQn = 22, /*!< TIM17 global Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Event Interrupt & EXTI Line23 Interrupt (I2C1 wakeup) */ + I2C2_IRQn = 24, /*!< I2C2 Event Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 26, /*!< SPI2 global Interrupt */ + USART1_IRQn = 27, /*!< USART1 global Interrupt & EXTI Line25 Interrupt (USART1 wakeup) */ + USART2_IRQn = 28, /*!< USART2 global Interrupt & EXTI Line26 Interrupt (USART2 wakeup) */ + USART3_4_IRQn = 29, /*!< USART3 and USART4 global Interrupt */ + CEC_CAN_IRQn = 30, /*!< CEC and CAN global Interrupts & EXTI Line27 Interrupt */ + USB_IRQn = 31 /*!< USB global Interrupt & EXTI Line18 Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm0.h" /* Cortex-M0 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 CFGR1; /*!< ADC configuration register 1, Address offset: 0x0C */ + __IO uint32_t CFGR2; /*!< ADC configuration register 2, Address offset: 0x10 */ + __IO uint32_t SMPR; /*!< ADC sampling time register, Address offset: 0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t TR; /*!< ADC analog watchdog 1 threshold register, Address offset: 0x20 */ + uint32_t RESERVED3; /*!< Reserved, 0x24 */ + __IO uint32_t CHSELR; /*!< ADC group regular sequencer register, Address offset: 0x28 */ + uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */ + __IO uint32_t DR; /*!< ADC group regular data register, Address offset: 0x40 */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; /*!< ADC common configuration register, 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 HDMI-CEC + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ + __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ + __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ + __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ + __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ + __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ +}CEC_TypeDef; + +/** + * @brief Comparator + */ + +typedef struct +{ + __IO uint16_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; + +/* Legacy defines */ +typedef struct +{ + __IO uint32_t CSR; /*!< Kept for legacy purpose. Use structure 'COMP_Common_TypeDef'. */ +}COMP1_2_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 Clock Recovery System + */ +typedef struct +{ +__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ +__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ +__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ +__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ +}CRS_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 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 = 128K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K + cpuid (r) : ORIGIN = 0x1ffff7ac, LENGTH = 12 +} + +_cpuid_address = ORIGIN(cpuid); + +INCLUDE cortexm_base.ld diff --git a/examples/gnrc_border_router/Makefile b/examples/gnrc_border_router/Makefile index 1dde2b2a1304..b4e1b4f343f5 100644 --- a/examples/gnrc_border_router/Makefile +++ b/examples/gnrc_border_router/Makefile @@ -10,7 +10,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon msb-430 msb-430h pca10000 pca10005 \ nrf51dongle nrf6310 nucleo-f103 nucleo-f334 \ spark-core stm32f0discovery telosb \ - weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 ifeq (,$(SLIP_UART)) # set default (last available UART) diff --git a/examples/gnrc_networking/Makefile b/examples/gnrc_networking/Makefile index b5b534e9267e..ce2441c12b46 100644 --- a/examples/gnrc_networking/Makefile +++ b/examples/gnrc_networking/Makefile @@ -10,7 +10,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle \ nrf6310 nucleo-f103 nucleo-f334 pca10000 pca10005 spark-core \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ - yunjia-nrf51822 z1 + yunjia-nrf51822 z1 nucleo-f072 # 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 bad532d2851d..c4d50fc6e10d 100644 --- a/examples/gnrc_tftp/Makefile +++ b/examples/gnrc_tftp/Makefile @@ -10,7 +10,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle \ nrf6310 nucleo-f103 nucleo-f334 pca10000 pca10005 \ spark-core stm32f0discovery telosb weio wsn430-v1_3b \ - wsn430-v1_4 yunjia-nrf51822 z1 + wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 # 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/microcoap_server/Makefile b/examples/microcoap_server/Makefile index 74de95f902e8..a8e51b5e7242 100644 --- a/examples/microcoap_server/Makefile +++ b/examples/microcoap_server/Makefile @@ -10,7 +10,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle \ nrf6310 pca10000 pca10005 spark-core \ stm32f0discovery telosb weio wsn430-v1_3b wsn430-v1_4 \ - yunjia-nrf51822 z1 + yunjia-nrf51822 z1 nucleo-f072 # 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/posix_sockets/Makefile b/examples/posix_sockets/Makefile index a4d77e515d95..641f419f883e 100644 --- a/examples/posix_sockets/Makefile +++ b/examples/posix_sockets/Makefile @@ -9,7 +9,7 @@ RIOTBASE ?= $(CURDIR)/../.. BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h nrf51dongle nrf6310 \ nucleo-f334 pca10000 pca10005 stm32f0discovery telosb weio \ - wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 + wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 # 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/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index 0fcdce844a10..e88fec965bb0 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -4,7 +4,7 @@ include ../Makefile.tests_common BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h mbed_lpc1768 \ stm32f0discovery pca10000 pca10005 \ yunjia-nrf51822 spark-core airfy-beacon nucleo-f103 \ - nucleo-f334 nrf51dongle nrf6310 weio + nucleo-f334 nrf51dongle nrf6310 weio nucleo-f072 DISABLE_MODULE += auto_init diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index 59e86f643b8c..ac0b1dba0e6e 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -5,7 +5,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h pca10000 \ pca10005 spark-core stm32f0discovery \ telosb wsn430-v1_3b wsn430-v1_4 z1 nucleo-f103 \ nucleo-f334 yunjia-nrf51822 samr21-xpro \ - arduino-mega2560 airfy-beacon nrf51dongle nrf6310 weio + arduino-mega2560 airfy-beacon nrf51dongle nrf6310 weio nucleo-f072 USEMODULE += embunit