From 292f4bc1ee31b920b01817220d9ba470a297f608 Mon Sep 17 00:00:00 2001
From: Cedric Adjih <cedric.adjih@inria.fr>
Date: Fri, 18 Mar 2016 18:33:53 +0100
Subject: [PATCH] boards/iotlab-a8-m3: initial implementation

---
 boards/iotlab-a8-m3/Makefile                  |   5 +
 boards/iotlab-a8-m3/Makefile.dep              |   1 +
 boards/iotlab-a8-m3/Makefile.features         |   1 +
 boards/iotlab-a8-m3/Makefile.include          |   7 +
 boards/iotlab-a8-m3/dist/openocd.cfg          |   8 +
 boards/iotlab-a8-m3/include/board.h           |  60 +++++++
 boards/iotlab-a8-m3/include/periph_conf.h     |  53 ++++++
 boards/iotlab-common/Makefile                 |   3 +
 boards/iotlab-common/Makefile.dep             |   9 +
 boards/iotlab-common/Makefile.features        |  14 ++
 boards/iotlab-common/Makefile.include         |  17 ++
 .../board.c => iotlab-common/board_init.c}    |   0
 boards/iotlab-common/include/board_common.h   | 106 +++++++++++
 .../include/gpio_params.h                     |   0
 .../include/l3g4200d_params.h                 |   0
 .../include/lsm303dlhc_params.h               |   0
 .../include/periph_conf_common.h              | 165 ++++++++++++++++++
 boards/iotlab-m3/Makefile                     |   2 +
 boards/iotlab-m3/Makefile.dep                 |   7 +-
 boards/iotlab-m3/Makefile.features            |  15 +-
 boards/iotlab-m3/Makefile.include             |  20 +--
 boards/iotlab-m3/include/board.h              |  65 +------
 boards/iotlab-m3/include/periph_conf.h        | 132 +-------------
 examples/default/Makefile                     |   2 +-
 24 files changed, 461 insertions(+), 231 deletions(-)
 create mode 100644 boards/iotlab-a8-m3/Makefile
 create mode 100644 boards/iotlab-a8-m3/Makefile.dep
 create mode 100644 boards/iotlab-a8-m3/Makefile.features
 create mode 100644 boards/iotlab-a8-m3/Makefile.include
 create mode 100644 boards/iotlab-a8-m3/dist/openocd.cfg
 create mode 100644 boards/iotlab-a8-m3/include/board.h
 create mode 100644 boards/iotlab-a8-m3/include/periph_conf.h
 create mode 100644 boards/iotlab-common/Makefile
 create mode 100644 boards/iotlab-common/Makefile.dep
 create mode 100644 boards/iotlab-common/Makefile.features
 create mode 100644 boards/iotlab-common/Makefile.include
 rename boards/{iotlab-m3/board.c => iotlab-common/board_init.c} (100%)
 create mode 100644 boards/iotlab-common/include/board_common.h
 rename boards/{iotlab-m3 => iotlab-common}/include/gpio_params.h (100%)
 rename boards/{iotlab-m3 => iotlab-common}/include/l3g4200d_params.h (100%)
 rename boards/{iotlab-m3 => iotlab-common}/include/lsm303dlhc_params.h (100%)
 create mode 100644 boards/iotlab-common/include/periph_conf_common.h

diff --git a/boards/iotlab-a8-m3/Makefile b/boards/iotlab-a8-m3/Makefile
new file mode 100644
index 0000000000..1e46aa27d7
--- /dev/null
+++ b/boards/iotlab-a8-m3/Makefile
@@ -0,0 +1,5 @@
+MODULE = board
+
+DIRS = $(RIOTBOARD)/iotlab-common
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/iotlab-a8-m3/Makefile.dep b/boards/iotlab-a8-m3/Makefile.dep
new file mode 100644
index 0000000000..784ed5a001
--- /dev/null
+++ b/boards/iotlab-a8-m3/Makefile.dep
@@ -0,0 +1 @@
+include $(RIOTBOARD)/iotlab-common/Makefile.dep
diff --git a/boards/iotlab-a8-m3/Makefile.features b/boards/iotlab-a8-m3/Makefile.features
new file mode 100644
index 0000000000..8ae0feee2c
--- /dev/null
+++ b/boards/iotlab-a8-m3/Makefile.features
@@ -0,0 +1 @@
+include $(RIOTBOARD)/iotlab-common/Makefile.features
diff --git a/boards/iotlab-a8-m3/Makefile.include b/boards/iotlab-a8-m3/Makefile.include
new file mode 100644
index 0000000000..1b7b02f02d
--- /dev/null
+++ b/boards/iotlab-a8-m3/Makefile.include
@@ -0,0 +1,7 @@
+USEMODULE += iotlab-common
+
+include $(RIOTBOARD)/iotlab-common/Makefile.include
+include $(RIOTBOARD)/$(BOARD)/Makefile.dep
+
+# add iotlab-a8-m3 include path
+INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include
diff --git a/boards/iotlab-a8-m3/dist/openocd.cfg b/boards/iotlab-a8-m3/dist/openocd.cfg
new file mode 100644
index 0000000000..efd4f0c325
--- /dev/null
+++ b/boards/iotlab-a8-m3/dist/openocd.cfg
@@ -0,0 +1,8 @@
+interface ftdi
+ftdi_vid_pid 0x0403 0x6010
+
+ftdi_layout_init 0x0c08 0x0c2b
+ftdi_layout_signal nTRST -data 0x0800
+ftdi_layout_signal nSRST -data 0x0400
+
+source [find target/stm32f1x.cfg]
diff --git a/boards/iotlab-a8-m3/include/board.h b/boards/iotlab-a8-m3/include/board.h
new file mode 100644
index 0000000000..6f93d3c70c
--- /dev/null
+++ b/boards/iotlab-a8-m3/include/board.h
@@ -0,0 +1,60 @@
+/*
+ * Copyright (C) 2014-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_iotlab-m3 IoT-LAB M3 open node
+ * @ingroup     boards
+ * @brief       Board specific files for the iotlab-m3 board.
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the iotlab-m3 board.
+ *
+ */
+
+#ifndef BOARD_H_
+#define BOARD_H_
+
+#include <stdint.h>
+
+#include "cpu.h"
+#include "periph_conf.h"
+#include "board_common.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name Define the interface for the L3G4200D gyroscope
+ * @{
+ */
+#define L3G4200D_I2C        I2C_0
+#define L3G4200D_ADDR       0x68
+#define L3G4200D_DRDY       GPIO_PIN(PORT_C,9)
+#define L3G4200D_INT        GPIO_PIN(PORT_C,6)
+/** @} */
+
+/**
+ * @name Define the interface to the LSM303DLHC accelerometer and magnetometer
+ * @{
+ */
+#define LSM303DLHC_I2C      I2C_0
+#define LSM303DLHC_ACC_ADDR (0x19)
+#define LSM303DLHC_MAG_ADDR (0x1e)
+#define LSM303DLHC_INT1     GPIO_PIN(PORT_B,12)
+#define LSM303DLHC_INT2     GPIO_PIN(PORT_B,2)
+#define LSM303DLHC_DRDY     GPIO_PIN(PORT_A,11)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* BOARD_H_ */
+/** @} */
diff --git a/boards/iotlab-a8-m3/include/periph_conf.h b/boards/iotlab-a8-m3/include/periph_conf.h
new file mode 100644
index 0000000000..1a83e2b23f
--- /dev/null
+++ b/boards/iotlab-a8-m3/include/periph_conf.h
@@ -0,0 +1,53 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser General
+ * Public License v2.1. See the file LICENSE in the top level directory for more
+ * details.
+ */
+
+/**
+ * @ingroup     boards_iotlab-m3
+ * @{
+ *
+ * @file
+ * @brief       Peripheral MCU configuration for the iotlab-m3 board
+ *
+ * @author      Thomas Eichinger <thomas.eichinger@fu-berlin.de>
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef PERIPH_CONF_H_
+#define PERIPH_CONF_H_
+
+#include "periph_cpu.h"
+#include "periph_conf_common.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief SPI configuration
+ * @{
+ */
+#define SPI_NUMOF           (1U)
+#define SPI_0_EN            1
+
+/* SPI 0 device configuration */
+#define SPI_0_DEV           SPI2
+#define SPI_0_CLKEN()       (RCC->APB1ENR |= RCC_APB1ENR_SPI2EN)
+#define SPI_0_CLKDIS()      (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN))
+#define SPI_0_BUS_DIV       1   /* 1 -> SPI runs with full CPU clock, 0 -> half CPU clock */
+/* SPI 0 pin configuration */
+#define SPI_0_CLK_PIN       GPIO_PIN(PORT_B,13)
+#define SPI_0_MISO_PIN      GPIO_PIN(PORT_B,14)
+#define SPI_0_MOSI_PIN      GPIO_PIN(PORT_B,15)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PERIPH_CONF_H_ */
+/** @} */
diff --git a/boards/iotlab-common/Makefile b/boards/iotlab-common/Makefile
new file mode 100644
index 0000000000..1e821e6765
--- /dev/null
+++ b/boards/iotlab-common/Makefile
@@ -0,0 +1,3 @@
+MODULE = iotlab-common
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/iotlab-common/Makefile.dep b/boards/iotlab-common/Makefile.dep
new file mode 100644
index 0000000000..3f827af989
--- /dev/null
+++ b/boards/iotlab-common/Makefile.dep
@@ -0,0 +1,9 @@
+ifneq (,$(filter netdev_default gnrc_netdev_default,$(USEMODULE)))
+  USEMODULE += at86rf231
+endif
+
+ifneq (,$(filter saul_default,$(USEMODULE)))
+  USEMODULE += saul_gpio
+  USEMODULE += l3g4200d
+  USEMODULE += lsm303dlhc
+endif
diff --git a/boards/iotlab-common/Makefile.features b/boards/iotlab-common/Makefile.features
new file mode 100644
index 0000000000..7bd04a87ff
--- /dev/null
+++ b/boards/iotlab-common/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_rtt
+FEATURES_PROVIDED += periph_spi
+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_m3_1
diff --git a/boards/iotlab-common/Makefile.include b/boards/iotlab-common/Makefile.include
new file mode 100644
index 0000000000..5bdf07243f
--- /dev/null
+++ b/boards/iotlab-common/Makefile.include
@@ -0,0 +1,17 @@
+# the cpu to build for
+export CPU = stm32f1
+export CPU_MODEL = stm32f103re
+
+# define the default port depending on the host OS
+PORT_LINUX ?= /dev/ttyUSB1
+PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbserial*)))
+
+# setup serial terminal
+export BAUD = 500000
+include $(RIOTBOARD)/Makefile.include.serial
+
+# this board uses openocd
+include $(RIOTBOARD)/Makefile.include.openocd
+
+# add the common header files to the include path
+INCLUDES += -I$(RIOTBOARD)/iotlab-common/include
diff --git a/boards/iotlab-m3/board.c b/boards/iotlab-common/board_init.c
similarity index 100%
rename from boards/iotlab-m3/board.c
rename to boards/iotlab-common/board_init.c
diff --git a/boards/iotlab-common/include/board_common.h b/boards/iotlab-common/include/board_common.h
new file mode 100644
index 0000000000..29babc2b96
--- /dev/null
+++ b/boards/iotlab-common/include/board_common.h
@@ -0,0 +1,106 @@
+/*
+ * Copyright (C) 2014-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_iotlab-m3 IoT-LAB M3 open node
+ * @ingroup     boards
+ * @brief       Board specific files for the iotlab-m3 board.
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the iotlab-m3 board.
+ *
+ * @author      Alaeddine Weslati <alaeddine.weslati@inria.fr>
+ * @author      Thomas Eichinger <thomas.eichinger@fu-berlin.de>
+ * @author      Oliver Hahm <oliver.hahm@inria.fr>
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef BOARD_COMMON_H_
+#define BOARD_COMMON_H_
+
+#include <stdint.h>
+
+#include "cpu.h"
+#include "periph_conf.h"
+#include "periph_conf_common.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name Set the default baudrate to 500K for this board
+ * @{
+ */
+#ifndef UART_STDIO_BAUDRATE
+#   define UART_STDIO_BAUDRATE (500000U)
+#endif
+/** @} */
+
+/**
+ * @name Tell the xtimer that we use a 16-bit peripheral timer
+ */
+#define XTIMER_MASK         (0xffff0000)
+
+/**
+ * @name Define the interface to the AT86RF231 radio
+ *
+ * {spi bus, spi speed, cs pin, int pin, reset pin, sleep pin}
+ */
+#define AT86RF2XX_PARAMS_BOARD      {.spi = SPI_0, \
+                                     .spi_speed = SPI_SPEED_5MHZ, \
+                                     .cs_pin = GPIO_PIN(PORT_A, 4), \
+                                     .int_pin = GPIO_PIN(PORT_C, 4), \
+                                     .sleep_pin = GPIO_PIN(PORT_A, 2), \
+                                     .reset_pin = GPIO_PIN(PORT_C, 1)}
+
+/**
+ * @brief   LED pin definitions and handlers
+ * @{
+ */
+#define LED0_PIN            GPIO_PIN(PORT_D, 2)
+#define LED1_PIN            GPIO_PIN(PORT_B, 5)
+#define LED2_PIN            GPIO_PIN(PORT_C, 10)
+
+#define LED0_MASK           (1 << 2)
+#define LED1_MASK           (1 << 5)
+#define LED2_MASK           (1 << 10)
+
+#define LED0_ON             (GPIOD->ODR &= ~LED0_MASK)
+#define LED0_OFF            (GPIOD->ODR |=  LED0_MASK)
+#define LED0_TOGGLE         (GPIOD->ODR ^=  LED0_MASK)
+
+#define LED1_ON             (GPIOB->ODR &= ~LED1_MASK)
+#define LED1_OFF            (GPIOB->ODR |=  LED1_MASK)
+#define LED1_TOGGLE         (GPIOB->ODR ^=  LED1_MASK)
+
+#define LED2_ON             (GPIOC->ODR &= ~LED2_MASK)
+#define LED2_OFF            (GPIOC->ODR |=  LED2_MASK)
+#define LED2_TOGGLE         (GPIOC->ODR ^=  LED2_MASK)
+/** @} */
+
+/**
+ * @name xtimer tuning values
+ * @{
+ */
+#define XTIMER_OVERHEAD     6
+#define XTIMER_SHOOT_EARLY  3
+/** @} */
+
+/**
+ * @brief Initialize board specific hardware, including clock, LEDs and std-IO
+ */
+void board_init(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* BOARD_COMMON_H_ */
+/** @} */
diff --git a/boards/iotlab-m3/include/gpio_params.h b/boards/iotlab-common/include/gpio_params.h
similarity index 100%
rename from boards/iotlab-m3/include/gpio_params.h
rename to boards/iotlab-common/include/gpio_params.h
diff --git a/boards/iotlab-m3/include/l3g4200d_params.h b/boards/iotlab-common/include/l3g4200d_params.h
similarity index 100%
rename from boards/iotlab-m3/include/l3g4200d_params.h
rename to boards/iotlab-common/include/l3g4200d_params.h
diff --git a/boards/iotlab-m3/include/lsm303dlhc_params.h b/boards/iotlab-common/include/lsm303dlhc_params.h
similarity index 100%
rename from boards/iotlab-m3/include/lsm303dlhc_params.h
rename to boards/iotlab-common/include/lsm303dlhc_params.h
diff --git a/boards/iotlab-common/include/periph_conf_common.h b/boards/iotlab-common/include/periph_conf_common.h
new file mode 100644
index 0000000000..0a24e4b39c
--- /dev/null
+++ b/boards/iotlab-common/include/periph_conf_common.h
@@ -0,0 +1,165 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser General
+ * Public License v2.1. See the file LICENSE in the top level directory for more
+ * details.
+ */
+
+/**
+ * @ingroup     boards_iotlab-m3
+ * @{
+ *
+ * @file
+ * @brief       Peripheral MCU configuration for the iotlab-m3 board
+ *
+ * @author      Thomas Eichinger <thomas.eichinger@fu-berlin.de>
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef PERIPH_CONF_COMMON_H_
+#define PERIPH_CONF_COMMON_H_
+
+#include "periph_cpu.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name Clock system configuration
+ * @{
+ **/
+#define CLOCK_HSE           (16000000U)             /* frequency of external oscillator */
+#define CLOCK_CORECLOCK     (72000000U)             /* targeted core clock frequency */
+/* configuration of PLL prescaler and multiply values */
+/* CORECLOCK := CLOCK_SOURCE / PLL_DIV * PLL_MUL */
+#define CLOCK_PLL_DIV       (2)
+#define CLOCK_PLL_MUL       (9)
+/* configuration of peripheral bus clock prescalers */
+#define CLOCK_AHB_DIV       RCC_CFGR_HPRE_DIV1      /* AHB clock -> 72MHz */
+#define CLOCK_APB2_DIV      RCC_CFGR_PPRE2_DIV1     /* APB2 clock -> 72MHz */
+#define CLOCK_APB1_DIV      RCC_CFGR_PPRE1_DIV2     /* APB1 clock -> 36MHz */
+/* resulting bus clocks */
+#define CLOCK_APB1          (CLOCK_CORECLOCK / 2)
+#define CLOCK_APB2          (CLOCK_CORECLOCK)
+/* configuration of flash access cycles */
+#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY_2
+/** @} */
+
+/**
+ * @name ADC configuration
+ * @{
+ */
+#define ADC_CONFIG          {       \
+    { GPIO_PIN(PORT_A,3), 0, 3  },  \
+    { GPIO_UNDEF        , 0, 16 },  \
+    { GPIO_UNDEF        , 0, 17 } }
+
+#define ADC_NUMOF           (3)
+/** @} */
+
+/**
+ * @brief   Timer configuration
+ * @{
+ */
+static const timer_conf_t timer_config[] = {
+    {
+        .dev      = TIM2,
+        .rcc_mask = RCC_APB1ENR_TIM2EN,
+        .bus      = APB1,
+        .irqn     = TIM2_IRQn
+    },
+    {
+        .dev      = TIM3,
+        .rcc_mask = RCC_APB1ENR_TIM3EN,
+        .bus      = APB1,
+        .irqn     = TIM3_IRQn
+    }
+};
+
+#define TIMER_0_ISR         isr_tim2
+#define TIMER_1_ISR         isr_tim3
+
+#define TIMER_NUMOF         (sizeof(timer_config) / sizeof(timer_config[0]))
+/** @} */
+
+/**
+ * @brief   UART configuration
+ * @{
+ */
+static const uart_conf_t uart_config[] = {
+    {
+        .dev     = USART1,
+        .rx_pin  = GPIO_PIN(PORT_A, 10),
+        .tx_pin  = GPIO_PIN(PORT_A, 9),
+        .rcc_pin = RCC_APB2ENR_USART1EN,
+        .bus     = APB2,
+        .irqn    = USART1_IRQn
+    },
+    {
+        .dev     = USART2,
+        .rx_pin  = GPIO_PIN(PORT_A, 3),
+        .tx_pin  = GPIO_PIN(PORT_A, 2),
+        .rcc_pin = RCC_APB1ENR_USART2EN,
+        .bus     = APB1,
+        .irqn    = USART2_IRQn
+    }
+};
+
+#define UART_0_ISR          isr_usart1
+#define UART_1_ISR          isr_usart2
+
+#define UART_NUMOF          (sizeof(uart_config) / sizeof(uart_config[0]))
+/** @} */
+
+/**
+ * @brief   DAC configuration
+ * @{
+ */
+#define DAC_NUMOF           (0)
+/** @} */
+
+/**
+ * @name Real time counter configuration
+ * @{
+ */
+#define RTT_NUMOF           (1U)
+#define RTT_IRQ_PRIO        1
+
+#define RTT_DEV             RTC
+#define RTT_IRQ             RTC_IRQn
+#define RTT_ISR             isr_rtc
+#define RTT_MAX_VALUE       (0xffffffff)
+#define RTT_FREQUENCY       (1)             /* in Hz */
+#define RTT_PRESCALER       (0x7fff)        /* run with 1 Hz */
+/** @} */
+
+/**
+ * @name I2C configuration
+  * @{
+ */
+#define I2C_NUMOF           (1U)
+#define I2C_0_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_PIN       GPIO_PIN(PORT_B,6)
+#define I2C_0_SDA_PIN       GPIO_PIN(PORT_B,7)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PERIPH_CONF_COMMON_H_ */
+/** @} */
diff --git a/boards/iotlab-m3/Makefile b/boards/iotlab-m3/Makefile
index f8fcbb53a0..1e46aa27d7 100644
--- a/boards/iotlab-m3/Makefile
+++ b/boards/iotlab-m3/Makefile
@@ -1,3 +1,5 @@
 MODULE = board
 
+DIRS = $(RIOTBOARD)/iotlab-common
+
 include $(RIOTBASE)/Makefile.base
diff --git a/boards/iotlab-m3/Makefile.dep b/boards/iotlab-m3/Makefile.dep
index dda6d2ea73..4475ce73cc 100644
--- a/boards/iotlab-m3/Makefile.dep
+++ b/boards/iotlab-m3/Makefile.dep
@@ -1,11 +1,6 @@
-ifneq (,$(filter netdev_default gnrc_netdev_default,$(USEMODULE)))
-  USEMODULE += at86rf231
-endif
+include $(RIOTBOARD)/iotlab-common/Makefile.dep
 
 ifneq (,$(filter saul_default,$(USEMODULE)))
-  USEMODULE += saul_gpio
   USEMODULE += isl29020
   USEMODULE += lps331ap
-  USEMODULE += l3g4200d
-  USEMODULE += lsm303dlhc
 endif
diff --git a/boards/iotlab-m3/Makefile.features b/boards/iotlab-m3/Makefile.features
index 7bd04a87ff..8ae0feee2c 100644
--- a/boards/iotlab-m3/Makefile.features
+++ b/boards/iotlab-m3/Makefile.features
@@ -1,14 +1 @@
-# Put defined MCU peripherals here (in alphabetical order)
-FEATURES_PROVIDED += periph_cpuid
-FEATURES_PROVIDED += periph_gpio
-FEATURES_PROVIDED += periph_i2c
-FEATURES_PROVIDED += periph_rtt
-FEATURES_PROVIDED += periph_spi
-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_m3_1
+include $(RIOTBOARD)/iotlab-common/Makefile.features
diff --git a/boards/iotlab-m3/Makefile.include b/boards/iotlab-m3/Makefile.include
index b0a76057cb..0b59abcd7d 100644
--- a/boards/iotlab-m3/Makefile.include
+++ b/boards/iotlab-m3/Makefile.include
@@ -1,17 +1,7 @@
-# the cpu to build for
-export CPU = stm32f1
-export CPU_MODEL = stm32f103re
+USEMODULE += iotlab-common
 
-# define the default port depending on the host OS
-PORT_LINUX ?= /dev/ttyUSB1
-PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbserial*)))
-
-# setup serial terminal
-export BAUD = 500000
-include $(RIOTBOARD)/Makefile.include.serial
-
-# this board uses openocd
-include $(RIOTBOARD)/Makefile.include.openocd
-
-# include board dependencies
+include $(RIOTBOARD)/iotlab-common/Makefile.include
 include $(RIOTBOARD)/$(BOARD)/Makefile.dep
+
+# add iotlab-m3 include path
+INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include
diff --git a/boards/iotlab-m3/include/board.h b/boards/iotlab-m3/include/board.h
index 2580c83577..8669222805 100644
--- a/boards/iotlab-m3/include/board.h
+++ b/boards/iotlab-m3/include/board.h
@@ -28,37 +28,12 @@
 
 #include "cpu.h"
 #include "periph_conf.h"
+#include "board_common.h"
 
 #ifdef __cplusplus
 extern "C" {
 #endif
 
-/**
- * @name Set the default baudrate to 500K for this board
- * @{
- */
-#ifndef UART_STDIO_BAUDRATE
-#   define UART_STDIO_BAUDRATE (500000U)
-#endif
-/** @} */
-
-/**
- * @name Tell the xtimer that we use a 16-bit peripheral timer
- */
-#define XTIMER_MASK         (0xffff0000)
-
-/**
- * @name Define the interface to the AT86RF231 radio
- *
- * {spi bus, spi speed, cs pin, int pin, reset pin, sleep pin}
- */
-#define AT86RF2XX_PARAMS_BOARD      {.spi = SPI_0, \
-                                     .spi_speed = SPI_SPEED_5MHZ, \
-                                     .cs_pin = GPIO_PIN(PORT_A, 4), \
-                                     .int_pin = GPIO_PIN(PORT_C, 4), \
-                                     .sleep_pin = GPIO_PIN(PORT_A, 2), \
-                                     .reset_pin = GPIO_PIN(PORT_C, 1)}
-
 /**
  * @name Define the interface for the connected flash memory
  * @{
@@ -107,44 +82,6 @@ extern "C" {
 #define LSM303DLHC_DRDY     GPIO_PIN(PORT_B,2)
 /** @} */
 
-/**
- * @brief   LED pin definitions and handlers
- * @{
- */
-#define LED0_PIN            GPIO_PIN(PORT_D, 2)
-#define LED1_PIN            GPIO_PIN(PORT_B, 5)
-#define LED2_PIN            GPIO_PIN(PORT_C, 10)
-
-#define LED0_MASK           (1 << 2)
-#define LED1_MASK           (1 << 5)
-#define LED2_MASK           (1 << 10)
-
-#define LED0_ON             (GPIOD->ODR &= ~LED0_MASK)
-#define LED0_OFF            (GPIOD->ODR |=  LED0_MASK)
-#define LED0_TOGGLE         (GPIOD->ODR ^=  LED0_MASK)
-
-#define LED1_ON             (GPIOB->ODR &= ~LED1_MASK)
-#define LED1_OFF            (GPIOB->ODR |=  LED1_MASK)
-#define LED1_TOGGLE         (GPIOB->ODR ^=  LED1_MASK)
-
-#define LED2_ON             (GPIOC->ODR &= ~LED2_MASK)
-#define LED2_OFF            (GPIOC->ODR |=  LED2_MASK)
-#define LED2_TOGGLE         (GPIOC->ODR ^=  LED2_MASK)
-/** @} */
-
-/**
- * @name xtimer tuning values
- * @{
- */
-#define XTIMER_OVERHEAD     6
-#define XTIMER_SHOOT_EARLY  3
-/** @} */
-
-/**
- * @brief Initialize board specific hardware, including clock, LEDs and std-IO
- */
-void board_init(void);
-
 #ifdef __cplusplus
 }
 #endif
diff --git a/boards/iotlab-m3/include/periph_conf.h b/boards/iotlab-m3/include/periph_conf.h
index a858456a03..979df0d5e1 100644
--- a/boards/iotlab-m3/include/periph_conf.h
+++ b/boards/iotlab-m3/include/periph_conf.h
@@ -21,98 +21,12 @@
 #define PERIPH_CONF_H_
 
 #include "periph_cpu.h"
+#include "periph_conf_common.h"
 
 #ifdef __cplusplus
 extern "C" {
 #endif
 
-/**
- * @name Clock system configuration
- * @{
- **/
-#define CLOCK_HSE           (16000000U)             /* frequency of external oscillator */
-#define CLOCK_CORECLOCK     (72000000U)             /* targeted core clock frequency */
-/* configuration of PLL prescaler and multiply values */
-/* CORECLOCK := CLOCK_SOURCE / PLL_DIV * PLL_MUL */
-#define CLOCK_PLL_DIV       (2)
-#define CLOCK_PLL_MUL       (9)
-/* configuration of peripheral bus clock prescalers */
-#define CLOCK_AHB_DIV       RCC_CFGR_HPRE_DIV1      /* AHB clock -> 72MHz */
-#define CLOCK_APB2_DIV      RCC_CFGR_PPRE2_DIV1     /* APB2 clock -> 72MHz */
-#define CLOCK_APB1_DIV      RCC_CFGR_PPRE1_DIV2     /* APB1 clock -> 36MHz */
-/* resulting bus clocks */
-#define CLOCK_APB1          (CLOCK_CORECLOCK / 2)
-#define CLOCK_APB2          (CLOCK_CORECLOCK)
-/* configuration of flash access cycles */
-#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY_2
-/** @} */
-
-/**
- * @name ADC configuration
- * @{
- */
-#define ADC_CONFIG          {       \
-    { GPIO_PIN(PORT_A,3), 0, 3  },  \
-    { GPIO_UNDEF        , 0, 16 },  \
-    { GPIO_UNDEF        , 0, 17 } }
-
-#define ADC_NUMOF           (3)
-/** @} */
-
-/**
- * @brief   Timer configuration
- * @{
- */
-static const timer_conf_t timer_config[] = {
-    {
-        .dev      = TIM2,
-        .rcc_mask = RCC_APB1ENR_TIM2EN,
-        .bus      = APB1,
-        .irqn     = TIM2_IRQn
-    },
-    {
-        .dev      = TIM3,
-        .rcc_mask = RCC_APB1ENR_TIM3EN,
-        .bus      = APB1,
-        .irqn     = TIM3_IRQn
-    }
-};
-
-#define TIMER_0_ISR         isr_tim2
-#define TIMER_1_ISR         isr_tim3
-
-#define TIMER_NUMOF         (sizeof(timer_config) / sizeof(timer_config[0]))
-/** @} */
-
-/**
- * @brief   UART configuration
- * @{
- */
-static const uart_conf_t uart_config[] = {
-    {
-        .dev     = USART1,
-        .rx_pin  = GPIO_PIN(PORT_A, 10),
-        .tx_pin  = GPIO_PIN(PORT_A, 9),
-        .rcc_pin = RCC_APB2ENR_USART1EN,
-        .bus     = APB2,
-        .irqn    = USART1_IRQn
-    },
-    {
-        .dev     = USART2,
-        .rx_pin  = GPIO_PIN(PORT_A, 3),
-        .tx_pin  = GPIO_PIN(PORT_A, 2),
-        .rcc_pin = RCC_APB1ENR_USART2EN,
-        .bus     = APB1,
-        .irqn    = USART2_IRQn
-    }
-};
-
-#define UART_0_ISR          isr_usart1
-#define UART_1_ISR          isr_usart2
-
-#define UART_NUMOF          (sizeof(uart_config) / sizeof(uart_config[0]))
-/** @} */
-
 /**
  * @brief SPI configuration
  * @{
@@ -131,50 +45,6 @@ static const uart_conf_t uart_config[] = {
 #define SPI_0_MISO_PIN      GPIO_PIN(PORT_A,6)
 /** @} */
 
-/**
- * @brief   DAC configuration
- * @{
- */
-#define DAC_NUMOF           (0)
-/** @} */
-
-/**
- * @name Real time counter configuration
- * @{
- */
-#define RTT_NUMOF           (1U)
-#define RTT_IRQ_PRIO        1
-
-#define RTT_DEV             RTC
-#define RTT_IRQ             RTC_IRQn
-#define RTT_ISR             isr_rtc
-#define RTT_MAX_VALUE       (0xffffffff)
-#define RTT_FREQUENCY       (1)             /* in Hz */
-#define RTT_PRESCALER       (0x7fff)        /* run with 1 Hz */
-/** @} */
-
-/**
- * @name I2C configuration
-  * @{
- */
-#define I2C_NUMOF           (1U)
-#define I2C_0_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_PIN       GPIO_PIN(PORT_B,6)
-#define I2C_0_SDA_PIN       GPIO_PIN(PORT_B,7)
-/** @} */
-
 #ifdef __cplusplus
 }
 #endif
diff --git a/examples/default/Makefile b/examples/default/Makefile
index 9d5206cbd6..ec34ee23ca 100644
--- a/examples/default/Makefile
+++ b/examples/default/Makefile
@@ -37,7 +37,7 @@ USEMODULE += saul_reg
 USEMODULE += saul_default
 USEMODULE += auto_init_saul
 
-BOARD_PROVIDES_NETIF := airfy-beacon fox iotlab-m3 mulle native nrf51dongle \
+BOARD_PROVIDES_NETIF := airfy-beacon fox iotlab-m3 iotlab-a8-m3 mulle native nrf51dongle \
 	nrf6310 pba-d-01-kw2x pca10000 pca10005 saml21-xpro samr21-xpro spark-core \
 	yunjia-nrf51822
 
-- 
GitLab