diff --git a/boards/opencm9-04/Makefile b/boards/opencm9-04/Makefile
new file mode 100755
index 0000000000000000000000000000000000000000..f8fcbb53a06595771dae356338a7bf2c0673734d
--- /dev/null
+++ b/boards/opencm9-04/Makefile
@@ -0,0 +1,3 @@
+MODULE = board
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/opencm9-04/Makefile.features b/boards/opencm9-04/Makefile.features
new file mode 100755
index 0000000000000000000000000000000000000000..9c388d7b4b742ae46d9c78010b3346271fdf052a
--- /dev/null
+++ b/boards/opencm9-04/Makefile.features
@@ -0,0 +1,11 @@
+# Put defined MCU peripherals here (in alphabetical order)
+FEATURES_PROVIDED += periph_cpuid
+FEATURES_PROVIDED += periph_gpio
+FEATURES_PROVIDED += periph_timer
+FEATURES_PROVIDED += periph_uart
+
+# Various common features of Nucleo boards
+FEATURES_PROVIDED += cpp
+
+# The board MPU family (used for grouping by the CI system)
+FEATURES_MCU_GROUP = cortex_m3_1
diff --git a/boards/opencm9-04/Makefile.include b/boards/opencm9-04/Makefile.include
new file mode 100755
index 0000000000000000000000000000000000000000..49dd53ef4d4d2cd293b92094947060325b59f359
--- /dev/null
+++ b/boards/opencm9-04/Makefile.include
@@ -0,0 +1,23 @@
+# the cpu to build for
+export CPU = stm32f1
+export CPU_MODEL = stm32f103cb
+
+# custom linkerscript
+export LINKER_SCRIPT = stm32f103cb_opencm9-04.ld
+
+# custom flasher to use with the bootloader
+export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/robotis-loader.py
+export DEBUGGER =
+export DEBUGSERVER =
+
+export OFLAGS = -O binary
+export HEXFILE = $(ELFFILE:.elf=.bin)
+export FFLAGS =
+export DEBUGGER_FLAGS =
+
+# define the default port depending on the host OS
+PORT_LINUX ?= /dev/ttyACM0
+PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*)))
+
+# setup serial terminal
+include $(RIOTBOARD)/Makefile.include.serial
diff --git a/boards/opencm9-04/board.c b/boards/opencm9-04/board.c
new file mode 100644
index 0000000000000000000000000000000000000000..3e73deabbe28510af67e1eec7a762e22d3ee7e3a
--- /dev/null
+++ b/boards/opencm9-04/board.c
@@ -0,0 +1,39 @@
+/*
+ * Copyright (C) 2017 INRIA
+ *
+ * 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_opencm9-04
+ * @{
+ *
+ * @file
+ * @brief       Board specific implementations for the OpenCM9.04 board
+ *
+ * @author      Loïc Dauphin <loic.dauphin@inria.fr>
+ *
+ * @}
+ */
+
+#include "board.h"
+#include "periph/gpio.h"
+#include "log.h"
+
+void board_init(void)
+{
+    /* initialize the CPU */
+    cpu_init();
+
+    /* initialize the board's LED */
+    gpio_init(LED0_PIN, GPIO_OUT);
+    LED0_OFF;
+
+    /* disable bootloader's USB */
+    RCC->APB1ENR &= ~RCC_APB1ENR_USBEN;
+
+    /* configure the RIOT vector table location to internal flash + bootloader offset */
+    SCB->VTOR = LOCATION_VTABLE;
+}
diff --git a/boards/opencm9-04/dist/robotis-loader.py b/boards/opencm9-04/dist/robotis-loader.py
new file mode 100755
index 0000000000000000000000000000000000000000..e67892331ee28c2e10ac1bb6b6ea7ae741f4930b
--- /dev/null
+++ b/boards/opencm9-04/dist/robotis-loader.py
@@ -0,0 +1,146 @@
+#!/usr/bin/env python
+
+'''
+MIT License
+
+Copyright (c) 2014 Gregoire Passault
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+'''
+
+# This script sends a program on a robotis board (OpenCM9.04 or CM900)
+# using the robotis bootloader (used in OpenCM IDE)
+#
+# Usage:
+# python robotis-loader.py <serial port> <binary>
+#
+# Example:
+# python robotis-loader.py /dev/ttyACM0 firmware.bin
+#
+# https://github.com/Gregwar/robotis-loader
+
+import serial
+import sys
+import os
+import time
+
+print('~~ Robotis loader ~~')
+print('')
+print('Please, make sure to connect the USB cable WHILE holding down the "USER SW" button.')
+print('Status LED should stay lit and the board should be able to load the program.')
+print('')
+
+
+# Helper function for bytes conversion
+if sys.version_info[:1][0] == 3:
+    def to_ord(val):
+        return ord(chr(val))
+else:
+    def to_ord(val):
+        return ord(val)
+
+
+# Reading command line
+#if len(sys.argv) != 3:
+#    exit('! Usage: robotis-loader.py <serial-port> <binary>')
+#pgm, port, binary = sys.argv
+
+pgm = sys.argv[0]
+port = os.environ["PORT"]
+binary = os.environ["HEXFILE"]
+
+
+def progressBar(percent, precision=65):
+    """Prints a progress bar."""
+
+    threshold = precision*percent / 100.0
+    sys.stdout.write('[ ')
+    for x in range(precision):
+        if x < threshold:
+            sys.stdout.write('#')
+        else:
+            sys.stdout.write(' ')
+    sys.stdout.write(' ] ')
+    sys.stdout.flush()
+
+
+# Opening the firmware file
+try:
+    stat = os.stat(binary)
+    size = stat.st_size
+    firmware = open(binary, 'rb')
+    print('* Opening %s, size=%d' % (binary, size))
+except:
+    exit('! Unable to open file %s' % binary)
+
+# Opening serial port
+try:
+    s = serial.Serial(port, baudrate=115200)
+except:
+    exit('! Unable to open serial port %s' % port)
+
+print('* Resetting the board')
+s.setRTS(True)
+s.setDTR(False)
+time.sleep(0.1)
+s.setRTS(False)
+s.write(b'CM9X')
+s.close()
+time.sleep(1.0);
+
+print('* Connecting...')
+s = serial.Serial(port, baudrate=115200)
+s.write(b'AT&LD')
+print('* Download signal transmitted, waiting...')
+
+# Entering bootloader sequence
+while True:
+    line = s.readline().strip()
+    if line.endswith(b'Ready..'):
+        print('* Board ready, sending data')
+        cs = 0
+        pos = 0
+        while True:
+            c = firmware.read(2048)
+            if len(c):
+                pos += len(c)
+                sys.stdout.write("\r")
+                progressBar(100 * float(pos) / float(size))
+                s.write(c)
+                for k in range(0, len(c)):
+                    cs = (cs + to_ord(c[k])) % 256
+            else:
+                firmware.close()
+                break
+        print('')
+        s.setDTR(True)
+        print('* Checksum: %d' % (cs))
+        import struct
+        s.write(struct.pack('B', cs))
+        # s.write('{0}'.format(chr(cs)).encode('ascii'))
+        print('* Firmware was sent')
+    else:
+        if line == b'Success..':
+            print('* Success, running the code')
+            print('')
+            s.write(b'AT&RST')
+            s.close()
+            exit()
+        else:
+            print('Board -> {}'.format(line))
diff --git a/boards/opencm9-04/include/board.h b/boards/opencm9-04/include/board.h
new file mode 100755
index 0000000000000000000000000000000000000000..ee419d6134f3fb495e561e7628925435b9ffae5e
--- /dev/null
+++ b/boards/opencm9-04/include/board.h
@@ -0,0 +1,77 @@
+/*
+ * Copyright (C) 2017 INRIA
+ *
+ * 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_opencm9-04 OpenCM9.04
+ * @ingroup     boards
+ * @brief       Board specific files for the OpenCM9.04 board
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the OpenCM9.04 board
+ *
+ * @author      Loïc Dauphin <loic.dauphin@inria.fr>
+ */
+
+#ifndef BOARD_H
+#define BOARD_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name Define the location of the RIOT image in flash
+ * @{
+ */
+#define LOCATION_VTABLE     (0x08003000)
+/** @} */
+
+/**
+ * @name xtimer configuration
+ * @{
+ */
+#define XTIMER_WIDTH        (16)
+#define XTIMER_BACKOFF      5
+/** @} */
+
+/**
+ * @name Macros for controlling the on-board LED.
+ * @{
+ */
+#define LED0_PIN            GPIO_PIN(PORT_B, 9)
+
+#define LED_PORT            GPIOB
+#define LED0_MASK           (1 << 9)
+
+#define LED0_ON             (LED_PORT->BRR = LED0_MASK)
+#define LED0_OFF            (LED_PORT->BSRR  = LED0_MASK)
+#define LED0_TOGGLE         (LED_PORT->ODR ^= LED0_MASK)
+/** @} */
+
+/**
+ * @brief   User button
+ */
+#define BTN_B1_PIN          GPIO_PIN(PORT_C, 15)
+
+/**
+ * @brief Use the USART2 for STDIO on this board
+ */
+#define UART_STDIO_DEV      UART_DEV(0)
+
+/**
+ * @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/opencm9-04/include/periph_conf.h b/boards/opencm9-04/include/periph_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..4a24abdf2e1b93d3c5a05fc122b85449c03fce63
--- /dev/null
+++ b/boards/opencm9-04/include/periph_conf.h
@@ -0,0 +1,149 @@
+/*
+ * Copyright (C) 2017 INRIA
+ *
+ * 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_opencm9-04
+ * @{
+ *
+ * @file
+ * @brief       Peripheral MCU configuration for the opencm9-04 board
+ *
+ * @author      Loïc Dauphin <loic.dauphin@inria.fr>
+ */
+
+#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_DIV       (1)
+#define CLOCK_PLL_MUL       CLOCK_CORECLOCK / CLOCK_HSE
+
+/* AHB, APB1, APB2 dividers */
+#define CLOCK_AHB_DIV       RCC_CFGR_HPRE_DIV1
+#define CLOCK_APB2_DIV      RCC_CFGR_PPRE2_DIV1
+#define CLOCK_APB1_DIV      RCC_CFGR_PPRE1_DIV2
+
+/* Bus clocks */
+#define CLOCK_APB1          (CLOCK_CORECLOCK / 2)
+#define CLOCK_APB2          (CLOCK_CORECLOCK)
+
+/* Flash latency */
+#define CLOCK_FLASH_LATENCY FLASH_ACR_LATENCY_2    /* for >= 72 MHz */
+/** @} */
+
+/**
+ * @name ADC configuration
+ * @{
+ */
+#define ADC_NUMOF           (0)
+/** @} */
+
+/**
+ * @brief   DAC configuration
+ * @{
+ */
+#define DAC_NUMOF           (0)
+/** @} */
+
+/**
+ * @brief   Timer configuration
+ * @{
+ */
+static const timer_conf_t timer_config[] = {
+    {
+        .dev      = TIM2,
+        .max      = 0x0000ffff,
+        .rcc_mask = RCC_APB1ENR_TIM2EN,
+        .bus      = APB1,
+        .irqn     = TIM2_IRQn
+    },
+    {
+        .dev      = TIM3,
+        .max      = 0x0000ffff,
+        .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        = USART2,
+        .rcc_mask   = RCC_APB1ENR_USART2EN,
+        .rx_pin     = GPIO_PIN(PORT_A, 3),
+        .tx_pin     = GPIO_PIN(PORT_A, 2),
+        .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),
+        .bus        = APB2,
+        .irqn       = USART1_IRQn
+    },
+    {
+        .dev        = USART3,
+        .rcc_mask   = RCC_APB1ENR_USART3EN,
+        .rx_pin     = GPIO_PIN(PORT_B, 11),
+        .tx_pin     = GPIO_PIN(PORT_B, 10),
+        .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 I2C configuration
+ * @{
+ */
+#define I2C_NUMOF           (0)
+/** @} */
+
+/**
+ * @name SPI configuration
+ * @{
+ */
+#define SPI_NUMOF           (0)
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PERIPH_CONF_H */
diff --git a/cpu/stm32f1/ldscripts/stm32f103cb_opencm9-04.ld b/cpu/stm32f1/ldscripts/stm32f103cb_opencm9-04.ld
new file mode 100644
index 0000000000000000000000000000000000000000..53d3b1119f66be7818462dd42059a17070d83520
--- /dev/null
+++ b/cpu/stm32f1/ldscripts/stm32f103cb_opencm9-04.ld
@@ -0,0 +1,30 @@
+/*
+ * Copyright (C) 2017 INRIA
+ *
+ * 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.
+ */
+
+/**
+ * @addtogroup      cpu_stm32f1
+ * @{
+ *
+ * @file
+ * @brief           OpenCM9.04 specific definitions for the STM32F103CB
+ *
+ * @author          Loïc Dauphin <loic.dauphin@inria.fr>
+ *
+ * @}
+ */
+
+MEMORY
+{
+    rom (rx)    : ORIGIN = 0x08003000, LENGTH = 128K-0x3000
+    ram (xrw)   : ORIGIN = 0x20000000, LENGTH = 20K
+    cpuid (r)   : ORIGIN = 0x1ffff7e8, LENGTH = 12
+}
+
+_cpuid_address = ORIGIN(cpuid);
+
+INCLUDE cortexm_base.ld
diff --git a/examples/dtls-echo/Makefile b/examples/dtls-echo/Makefile
index d80c863b4b5483377a685c683bf085c4e003126b..d020886f1406de6cfecfe7c19442b01c4accf107 100644
--- a/examples/dtls-echo/Makefile
+++ b/examples/dtls-echo/Makefile
@@ -17,7 +17,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon nrf51dongle nrf6310 nucleo-f103 \
                              nucleo-f334 pca10000 pca10005 spark-core \
                              stm32f0discovery weio yunjia-nrf51822 nucleo-f072 \
                              cc2650stk nucleo-f030 nucleo-f070 microbit \
-                             calliope-mini nucleo32-f042 nucleo32-f303
+                             calliope-mini nucleo32-f042 nucleo32-f303 opencm9-04
 
 # 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 b05803d1ce948f930f602d7266bb020889a46725..578f129a85a830c62122b02e510e2c39c15dc23f 100644
--- a/examples/gnrc_border_router/Makefile
+++ b/examples/gnrc_border_router/Makefile
@@ -12,7 +12,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk msb-430 msb-430h pca10000 pc
                              spark-core stm32f0discovery telosb \
                              weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 \
                              nucleo-f030 nucleo-f070 microbit calliope-mini \
-                             nucleo32-f042 nucleo32-f303
+                             nucleo32-f042 nucleo32-f303 opencm9-04
 
 # use ethos (ethernet over serial) for network communication and stdio over
 # UART, but not on native, as native has a tap interface towards the host.
diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile
index b3c51caa3a7686380e01d8a6917d1d078da6a777..1d4e85e64df113f364936f89c29ad67c83b6d2ad 100644
--- a/tests/thread_cooperation/Makefile
+++ b/tests/thread_cooperation/Makefile
@@ -6,7 +6,7 @@ BOARD_INSUFFICIENT_MEMORY := cc2650stk chronos msb-430 msb-430h mbed_lpc1768 \
                           yunjia-nrf51822 spark-core airfy-beacon nucleo-f103 \
                           nucleo-f334 nrf51dongle nrf6310 weio nucleo-f072 \
                           nucleo-f030 nucleo-f070 microbit calliope-mini \
-                          nucleo32-f042 nucleo32-f303
+                          nucleo32-f042 nucleo32-f303 opencm9-04
 
 DISABLE_MODULE += auto_init
 
diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile
index 090f2193d67337ac7ec7528e720a62b862e408bf..117d2ce0c46652d55d2cc71a371d41efe397855f 100644
--- a/tests/unittests/Makefile
+++ b/tests/unittests/Makefile
@@ -12,7 +12,7 @@ BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk chronos ek-lm4f120xl \
                           nucleo-f030 nucleo-f070 nucleo-f091 pba-d-01-kw2x \
                           saml21-xpro microbit calliope-mini limifrog-v1 \
                           slwstk6220a ek-lm4f120xl stm32f3discovery \
-                          slwstk6220a nucleo32-f042 nucleo32-f303
+                          slwstk6220a nucleo32-f042 nucleo32-f303 opencm9-04
 
 USEMODULE += embunit
 
@@ -31,7 +31,7 @@ ARM_CORTEX_M_BOARDS := airfy-beacon arduino-due cc2538dk ek-lm4f120xl f4vi1 fox
                        pba-d-01-kw2x pca10000 pca10005 remote saml21-xpro samr21-xpro slwstk6220a \
                        spark-core stm32f0discovery stm32f3discovery stm32f4discovery udoo weio \
                        yunjia-nrf51822 sodaq-autonomo arduino-zero nucleo-f030 nucleo-f070 \
-                       nucleo32-f303
+                       nucleo32-f303 opencm9-04
 
 DISABLE_TEST_FOR_ARM_CORTEX_M := tests-relic