From 7ccf184cd1d65a3e35952a1bbe7800cfa8131cfc Mon Sep 17 00:00:00 2001
From: Hauke Petersen <hauke.petersen@fu-berlin.de>
Date: Fri, 13 Mar 2015 10:18:00 +0100
Subject: [PATCH] boards: added support for nucleo-f091

---
 boards/nucleo-f091/Makefile              |   3 +
 boards/nucleo-f091/Makefile.features     |   6 +
 boards/nucleo-f091/Makefile.include      |  59 ++++++++
 boards/nucleo-f091/board.c               |  58 ++++++++
 boards/nucleo-f091/dist/openocd.cfg      |   1 +
 boards/nucleo-f091/include/board.h       |  93 +++++++++++++
 boards/nucleo-f091/include/periph_conf.h | 165 +++++++++++++++++++++++
 7 files changed, 385 insertions(+)
 create mode 100644 boards/nucleo-f091/Makefile
 create mode 100644 boards/nucleo-f091/Makefile.features
 create mode 100644 boards/nucleo-f091/Makefile.include
 create mode 100644 boards/nucleo-f091/board.c
 create mode 100644 boards/nucleo-f091/dist/openocd.cfg
 create mode 100644 boards/nucleo-f091/include/board.h
 create mode 100644 boards/nucleo-f091/include/periph_conf.h

diff --git a/boards/nucleo-f091/Makefile b/boards/nucleo-f091/Makefile
new file mode 100644
index 0000000000..ff5489888b
--- /dev/null
+++ b/boards/nucleo-f091/Makefile
@@ -0,0 +1,3 @@
+MODULE =$(BOARD)_base
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/nucleo-f091/Makefile.features b/boards/nucleo-f091/Makefile.features
new file mode 100644
index 0000000000..5a9d649a95
--- /dev/null
+++ b/boards/nucleo-f091/Makefile.features
@@ -0,0 +1,6 @@
+FEATURES_PROVIDED += cpp
+FEATURES_PROVIDED += periph_cpuid
+FEATURES_PROVIDED += periph_gpio
+FEATURES_PROVIDED += periph_uart
+
+FEATURES_MCU_GROUP = cortex_m0
diff --git a/boards/nucleo-f091/Makefile.include b/boards/nucleo-f091/Makefile.include
new file mode 100644
index 0000000000..98ad057435
--- /dev/null
+++ b/boards/nucleo-f091/Makefile.include
@@ -0,0 +1,59 @@
+## the cpu to build for
+export CPU = stm32f0
+export CPU_MODEL = stm32f091rc
+
+#define the default port depending on the host OS
+OS := $(shell uname)
+ifeq ($(OS),Linux)
+  PORT ?= /dev/ttyACM0
+else ifeq ($(OS),Darwin)
+  PORT ?= $(shell ls -1 /dev/tty.usbmodem* | head -n 1)
+else
+  $(info CAUTION: No flash tool for your host system found!)
+  # TODO: add support for windows as host platform
+endif
+export PORT
+
+# define tools used for building the project
+export PREFIX = arm-none-eabi-
+export CC = $(PREFIX)gcc
+export CXX = $(PREFIX)g++
+export AR = $(PREFIX)ar
+export AS = $(PREFIX)as
+export LINK = $(PREFIX)gcc
+export SIZE = $(PREFIX)size
+export OBJCOPY = $(PREFIX)objcopy
+export DBG = $(PREFIX)gdb
+export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm
+export FLASHER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
+export DEBUGGER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
+export DEBUGSERVER = $(RIOTBASE)/dist/tools/openocd/openocd.sh
+export RESET = $(RIOTBASE)/dist/tools/openocd/openocd.sh
+
+# unwanted (CXXUWFLAGS) and extra (CXXEXFLAGS) flags for c++
+export CXXUWFLAGS +=
+export CXXEXFLAGS +=
+
+# define build specific options
+export CPU_USAGE = -mcpu=cortex-m0
+export FPU_USAGE =
+export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -mthumb -mno-thumb-interwork -nostartfiles
+export CFLAGS += -ffunction-sections -fdata-sections -fno-builtin
+export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian
+export LINKFLAGS += -ggdb -g3 -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -static -lgcc -mthumb -mno-thumb-interwork -nostartfiles
+# $(LINKERSCRIPT) is specified in cpu/Makefile.include
+export LINKFLAGS += -T$(LINKERSCRIPT)
+export OFLAGS = -O ihex
+export TERMFLAGS += -p "$(PORT)"
+export FFLAGS = flash
+export DEBUGGER_FLAGS = debug
+export DEBUGSERVER_FLAGS = debug-server
+export RESET_FLAGS = reset
+
+# use the nano-specs of the NewLib when available
+#ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null </dev/null ; echo $$?),0)
+export LINKFLAGS += -specs=nano.specs -lc -lnosys
+#endif
+
+# export board specific includes to the global includes-listing
+export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include/
diff --git a/boards/nucleo-f091/board.c b/boards/nucleo-f091/board.c
new file mode 100644
index 0000000000..74cb8797af
--- /dev/null
+++ b/boards/nucleo-f091/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-f091
+ * @{
+ *
+ * @file
+ * @brief       Board specific implementations for the nucleo-f091 board
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ *
+ * @}
+ */
+
+#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-f091/dist/openocd.cfg b/boards/nucleo-f091/dist/openocd.cfg
new file mode 100644
index 0000000000..4f0cfb3a02
--- /dev/null
+++ b/boards/nucleo-f091/dist/openocd.cfg
@@ -0,0 +1 @@
+source [find board/st_nucleo_f0.cfg]
diff --git a/boards/nucleo-f091/include/board.h b/boards/nucleo-f091/include/board.h
new file mode 100644
index 0000000000..f328de05a9
--- /dev/null
+++ b/boards/nucleo-f091/include/board.h
@@ -0,0 +1,93 @@
+/*
+ * 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-f091 Nucleo-F091
+ * @ingroup     boards
+ * @brief       Board specific files for the nucleo-f091 board
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the nucleo-f091 board
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef BOARD_H_
+#define BOARD_H_
+
+#include <stdint.h>
+
+#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-f091/include/periph_conf.h b/boards/nucleo-f091/include/periph_conf.h
new file mode 100644
index 0000000000..f059424907
--- /dev/null
+++ b/boards/nucleo-f091/include/periph_conf.h
@@ -0,0 +1,165 @@
+/*
+ * 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-f091
+ * @{
+ *
+ * @file
+ * @brief       Peripheral MCU configuration for the nucleo-f091 board
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#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_PRESCALER   (47U)
+#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
+/** @} */
+
+/**
+ * @name GPIO configuration
+ * @{
+ */
+#define GPIO_NUMOF          (6U)
+#define GPIO_0_EN           1
+#define GPIO_1_EN           1
+#define GPIO_2_EN           1
+#define GPIO_3_EN           1
+#define GPIO_4_EN           1
+#define GPIO_5_EN           1
+#define GPIO_IRQ_PRIO       1
+
+/* IRQ config */
+#define GPIO_IRQ_0          -1                      /* not configured */
+#define GPIO_IRQ_1          -1                      /* not configured */
+#define GPIO_IRQ_2          -1                      /* not configured */
+#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         GPIO_0
+#define GPIO_IRQ_11         GPIO_1
+#define GPIO_IRQ_12         GPIO_2
+#define GPIO_IRQ_13         GPIO_3
+#define GPIO_IRQ_14         GPIO_4
+#define GPIO_IRQ_15         GPIO_5
+
+/* GPIO channel 0 config */
+#define GPIO_0_PORT         GPIOC
+#define GPIO_0_PIN          10
+#define GPIO_0_CLK          19
+#define GPIO_0_EXTI_CFG()   (SYSCFG->EXTICR[2] |= SYSCFG_EXTICR3_EXTI10_PC)
+#define GPIO_0_IRQ          EXTI4_15_IRQn
+/* GPIO channel 1 config */
+#define GPIO_1_PORT         GPIOC
+#define GPIO_1_PIN          11
+#define GPIO_1_CLK          19
+#define GPIO_1_EXTI_CFG()   (SYSCFG->EXTICR[2] |= SYSCFG_EXTICR3_EXTI11_PC)
+#define GPIO_1_IRQ          EXTI4_15_IRQn
+/* GPIO channel 2 config */
+#define GPIO_2_PORT         GPIOC
+#define GPIO_2_PIN          12
+#define GPIO_2_CLK          19
+#define GPIO_2_EXTI_CFG()   (SYSCFG->EXTICR[3] |= SYSCFG_EXTICR4_EXTI12_PC)
+#define GPIO_2_IRQ          EXTI4_15_IRQn
+/* GPIO channel 3 config */
+#define GPIO_3_PORT         GPIOC
+#define GPIO_3_PIN          13                   /* Used for user button 1 */
+#define GPIO_3_CLK          19
+#define GPIO_3_EXTI_CFG()   (SYSCFG->EXTICR[3] |= SYSCFG_EXTICR4_EXTI13_PC)
+#define GPIO_3_IRQ          EXTI4_15_IRQn
+/* GPIO channel 4 config */
+#define GPIO_4_PORT         GPIOC
+#define GPIO_4_PIN          14
+#define GPIO_4_CLK          19
+#define GPIO_4_EXTI_CFG()   (SYSCFG->EXTICR[3] |= SYSCFG_EXTICR4_EXTI14_PC)
+#define GPIO_4_IRQ          EXTI4_15_IRQn
+/* GPIO channel 5 config */
+#define GPIO_5_PORT         GPIOC
+#define GPIO_5_PIN          15
+#define GPIO_5_CLK          19
+#define GPIO_5_EXTI_CFG()   (SYSCFG->EXTICR[3] |= SYSCFG_EXTICR4_EXTI15_PC)
+#define GPIO_5_IRQ          EXTI4_15_IRQn
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __PERIPH_CONF_H */
+/** @} */
-- 
GitLab