From c0628a3058b5805a945adfcd4c5ec03e4b78ee08 Mon Sep 17 00:00:00 2001
From: Johann F <j.fischer@phytec.de>
Date: Tue, 6 Jan 2015 00:19:24 +0100
Subject: [PATCH] cpu/kinetis_common: initial import for kinetis_common

  add peripheral drivers for Freescale Kinetis MCUs:
    adc driver
    cpuid driver
    gpio driver
    hwtimer_arch driver (hwtimer used Low Power Timer)
    i2c driver (master mode only)
    mcg driver
    pwm driver
    random_rnga driver
    random_rngb driver
    rtc driver
    spi driver
    timer driver (timer used Periodic Interrupt Timer)
    uart driver
  add doc.txt (configuration examples)

  random_rnga: Update RNGA driver in preparation for RNGB driver.
  random_rngb: Add RNGB driver.
  spi: refactor SPI to work for multiple CTARS, add spi_acquire, spi_release
  gpio: Add gpio_irq_enable, gpio_irq_disable. Refactor GPIO.
  gpio: Add gpio_irq_enable, gpio_irq_disable.
  gpio: Refactor ISR functions to work with all GPIOs (0-31) and all ports (PORTA-PORTH)
  adc: Refactor ADC, add calibration and scaling.
    Added integer scaling of results in adc_map.
    Handle precision setting in adc_init.
    Set ADC clock divider depending on module clock.
    Add ADC_1 as a possible device.
    Add ADC calibration procedure according to K60 ref manual.
    Handle ADC pins which are not part of the pin function mux.
  Signed-off-by: Joakim Gebart <joakim.gebart@eistec.se>
---
 cpu/kinetis_common/Makefile              |    4 +
 cpu/kinetis_common/Makefile.include      |    2 +
 cpu/kinetis_common/adc.c                 |  426 +++
 cpu/kinetis_common/cpuid.c               |   30 +
 cpu/kinetis_common/doc.txt               |  328 ++
 cpu/kinetis_common/gpio.c                | 3520 ++++++++++++++++++++++
 cpu/kinetis_common/hwtimer_arch.c        |  223 ++
 cpu/kinetis_common/i2c.c                 |  436 +++
 cpu/kinetis_common/include/hwtimer_cpu.h |  113 +
 cpu/kinetis_common/include/mcg.h         |  137 +
 cpu/kinetis_common/mcg.c                 |  484 +++
 cpu/kinetis_common/pwm.c                 |  274 ++
 cpu/kinetis_common/random_rnga.c         |   82 +
 cpu/kinetis_common/random_rngb.c         |   88 +
 cpu/kinetis_common/rtc.c                 |  177 ++
 cpu/kinetis_common/spi.c                 | 1583 ++++++++++
 cpu/kinetis_common/timer.c               |  368 +++
 cpu/kinetis_common/uart.c                |  360 +++
 18 files changed, 8635 insertions(+)
 create mode 100644 cpu/kinetis_common/Makefile
 create mode 100644 cpu/kinetis_common/Makefile.include
 create mode 100644 cpu/kinetis_common/adc.c
 create mode 100644 cpu/kinetis_common/cpuid.c
 create mode 100644 cpu/kinetis_common/doc.txt
 create mode 100644 cpu/kinetis_common/gpio.c
 create mode 100644 cpu/kinetis_common/hwtimer_arch.c
 create mode 100644 cpu/kinetis_common/i2c.c
 create mode 100644 cpu/kinetis_common/include/hwtimer_cpu.h
 create mode 100644 cpu/kinetis_common/include/mcg.h
 create mode 100644 cpu/kinetis_common/mcg.c
 create mode 100644 cpu/kinetis_common/pwm.c
 create mode 100644 cpu/kinetis_common/random_rnga.c
 create mode 100644 cpu/kinetis_common/random_rngb.c
 create mode 100644 cpu/kinetis_common/rtc.c
 create mode 100644 cpu/kinetis_common/spi.c
 create mode 100644 cpu/kinetis_common/timer.c
 create mode 100644 cpu/kinetis_common/uart.c

diff --git a/cpu/kinetis_common/Makefile b/cpu/kinetis_common/Makefile
new file mode 100644
index 0000000000..587f1a4038
--- /dev/null
+++ b/cpu/kinetis_common/Makefile
@@ -0,0 +1,4 @@
+# define the module that is build
+MODULE = kinetis_common
+
+include $(RIOTBASE)/Makefile.base
diff --git a/cpu/kinetis_common/Makefile.include b/cpu/kinetis_common/Makefile.include
new file mode 100644
index 0000000000..e4abf891c1
--- /dev/null
+++ b/cpu/kinetis_common/Makefile.include
@@ -0,0 +1,2 @@
+# include module specific includes
+export INCLUDES += -I$(RIOTCPU)/kinetis_common/include
diff --git a/cpu/kinetis_common/adc.c b/cpu/kinetis_common/adc.c
new file mode 100644
index 0000000000..6a410655f8
--- /dev/null
+++ b/cpu/kinetis_common/adc.c
@@ -0,0 +1,426 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ * Copyright (C) 2015 Eistec AB
+ *
+ * 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     cpu_kinetis_common_adc
+ * @{
+ *
+ * @file
+ * @brief       Low-level ADC driver implementation
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ * @author      Jonas Remmert <j.remmert@phytec.de>
+ * @author      Joakim Gebart <joakim.gebart@eistec.se>
+ *
+ * @}
+ */
+#include <stdio.h>
+
+#include "cpu.h"
+#include "periph/adc.h"
+#include "periph_conf.h"
+
+/* guard in case that no ADC device is defined */
+#if ADC_NUMOF
+
+typedef struct {
+    int max_value;
+    int bits;
+} adc_config_t;
+
+adc_config_t adc_config[ADC_NUMOF];
+
+/**
+ * @brief Perform ADC calibration routine.
+ *
+ * This is a recipe taken straight from the Kinetis K60 reference manual. It has
+ * been tested on MK60DN512VLL10.
+ *
+ * @param[in]  ADC_ptr     Pointer to ADC device to operate on.
+ *
+ * @return 0 on success
+ * @return <0 on errors
+ */
+int kinetis_adc_calibrate(ADC_Type *ADC_ptr)
+{
+    uint16_t cal;
+
+    ADC_ptr->SC3 |= ADC_SC3_CAL_MASK;
+
+    while (ADC_ptr->SC3 & ADC_SC3_CAL_MASK); /* wait for calibration to finish */
+
+    while (!(ADC_ptr->SC1[0] & ADC_SC1_COCO_MASK));
+
+    if (ADC_ptr->SC3 & ADC_SC3_CALF_MASK) {
+        /* calibration failed for some reason, possibly SC2[ADTRG] is 1 ? */
+        return -1;
+    }
+
+    /*
+     * Following the steps in the reference manual:
+     */
+    /* 1. Initialize or clear a 16-bit variable in RAM. */
+    /* 2. Add the plus-side calibration results CLP0, CLP1, CLP2, CLP3, CLP4, and
+     * CLPS to the variable. */
+    cal = ADC_ptr->CLP0 + ADC_ptr->CLP1 + ADC_ptr->CLP2 + ADC_ptr->CLP3 +
+          ADC_ptr->CLP4 + ADC_ptr->CLPS;
+    /* 3. Divide the variable by two. */
+    cal /= 2;
+    /* 4. Set the MSB of the variable. */
+    cal |= (1 << 15);
+    /* (5. The previous two steps can be achieved by setting the carry bit,
+     * rotating to the right through the carry bit on the high byte and again on
+     * the low byte.)
+     * We ignore the above optimization suggestion, we most likely only perform
+     * this calibration on startup and it will only save nanoseconds. */
+    /* 6. Store the value in the plus-side gain calibration register PG. */
+    ADC_ptr->PG = cal;
+
+    /* 7. Repeat the procedure for the minus-side gain calibration value. */
+    cal = ADC_ptr->CLM0 + ADC_ptr->CLM1 + ADC_ptr->CLM2 + ADC_ptr->CLM3 +
+          ADC_ptr->CLM4 + ADC_ptr->CLMS;
+    cal /= 2;
+    cal |= (1 << 15);
+    ADC_ptr->MG = cal;
+
+    return 0;
+}
+
+
+int adc_init(adc_t dev, adc_precision_t precision)
+{
+    ADC_Type *adc = 0;
+    PORT_Type *port[ADC_MAX_CHANNELS];
+    uint8_t pins[ADC_MAX_CHANNELS];
+    uint8_t af[ADC_MAX_CHANNELS];
+    int channels = 0;
+    uint32_t mode = 0;
+    uint32_t div = 0;
+    int i = 0;
+    uint32_t clock = 0;
+
+    adc_poweron(dev);
+
+    switch (dev) {
+#if ADC_0_EN
+
+        case ADC_0:
+            adc = ADC_0_DEV;
+            port[0] = ADC_0_CH0_PORT;
+            port[1] = ADC_0_CH1_PORT;
+            port[2] = ADC_0_CH2_PORT;
+            port[3] = ADC_0_CH3_PORT;
+            port[4] = ADC_0_CH4_PORT;
+            port[5] = ADC_0_CH5_PORT;
+            pins[0] = ADC_0_CH0_PIN;
+            pins[1] = ADC_0_CH1_PIN;
+            pins[2] = ADC_0_CH2_PIN;
+            pins[3] = ADC_0_CH3_PIN;
+            pins[4] = ADC_0_CH4_PIN;
+            pins[5] = ADC_0_CH5_PIN;
+            af[0] = ADC_0_CH0_PIN_AF;
+            af[1] = ADC_0_CH1_PIN_AF;
+            af[2] = ADC_0_CH2_PIN_AF;
+            af[3] = ADC_0_CH3_PIN_AF;
+            af[4] = ADC_0_CH4_PIN_AF;
+            af[5] = ADC_0_CH5_PIN_AF;
+            channels = ADC_0_CHANNELS;
+            clock = ADC_0_MODULE_CLOCK;
+            ADC_0_PORT_CLKEN();
+            break;
+#endif
+#if ADC_1_EN
+
+        case ADC_1:
+            adc = ADC_1_DEV;
+            port[0] = ADC_1_CH0_PORT;
+            port[1] = ADC_1_CH1_PORT;
+            port[2] = ADC_1_CH2_PORT;
+            port[3] = ADC_1_CH3_PORT;
+            port[4] = ADC_1_CH4_PORT;
+            port[5] = ADC_1_CH5_PORT;
+            pins[0] = ADC_1_CH0_PIN;
+            pins[1] = ADC_1_CH1_PIN;
+            pins[2] = ADC_1_CH2_PIN;
+            pins[3] = ADC_1_CH3_PIN;
+            pins[4] = ADC_1_CH4_PIN;
+            pins[5] = ADC_1_CH5_PIN;
+            af[0] = ADC_1_CH0_PIN_AF;
+            af[1] = ADC_1_CH1_PIN_AF;
+            af[2] = ADC_1_CH2_PIN_AF;
+            af[3] = ADC_1_CH3_PIN_AF;
+            af[4] = ADC_1_CH4_PIN_AF;
+            af[5] = ADC_1_CH5_PIN_AF;
+            channels = ADC_1_CHANNELS;
+            clock = ADC_1_MODULE_CLOCK;
+            ADC_1_PORT_CLKEN();
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (channels > ADC_MAX_CHANNELS) {
+        return -1;
+    }
+
+    /* set precision, these numbers are valid for the K60 */
+    switch (precision) {
+        case ADC_RES_6BIT:
+            /* Not supported by hardware, use 8 bit mode. */
+            mode = ADC_CFG1_MODE(0);
+            adc_config[dev].bits = 8;
+            break;
+
+        case ADC_RES_8BIT:
+            mode = ADC_CFG1_MODE(0);
+            adc_config[dev].bits = 8;
+            break;
+
+        case ADC_RES_10BIT:
+            mode = ADC_CFG1_MODE(2);
+            adc_config[dev].bits = 10;
+            break;
+
+        case ADC_RES_12BIT:
+            mode = ADC_CFG1_MODE(1);
+            adc_config[dev].bits = 12;
+            break;
+
+        case ADC_RES_14BIT:
+            /* Not supported by hardware, use 16 bit mode. */
+            mode = ADC_CFG1_MODE(3);
+            adc_config[dev].bits = 16;
+            break;
+
+        case ADC_RES_16BIT:
+            mode = ADC_CFG1_MODE(3);
+            adc_config[dev].bits = 16;
+            break;
+    }
+
+    adc_config[dev].max_value = (1 << adc_config[dev].bits) - 1;
+
+    for (i = 0; i < channels; i++) {
+        /* Check whether we need to set the pin mux for this channel. */
+        if (port[i] != NULL) {
+            port[i]->PCR[pins[i]] = PORT_PCR_MUX(af[i]);
+        }
+    }
+
+    /* The ADC requires at least 2 MHz module clock for full accuracy, and less
+     * than 12 MHz */
+    /* For the calibration it is important that the ADC clock is <= 4 MHz */
+    if (clock > 4000000 * 8) {
+        /* Need to divide by 16, we set the clock input to BusClock/2 and
+         * divide clock by 8 (the maximum divider) */
+        div = ADC_CFG1_ADIV(3) | ADC_CFG1_ADICLK(1);
+    }
+    else if (clock > 4000000 * 4) {
+        /* divide clock by 8 */
+        div = ADC_CFG1_ADIV(3);
+    }
+    else if (clock > 4000000 * 2) {
+        /* divide clock by 4 */
+        div = ADC_CFG1_ADIV(2);
+    }
+    else if (clock > 4000000 * 1) {
+        /* divide clock by 2 */
+        div = ADC_CFG1_ADIV(1);
+    }
+    else {
+        /* no clock divider */
+        div = ADC_CFG1_ADIV(0);
+    }
+
+    /* set configuration register 1: clocking and precision */
+    /* Set long sample time */
+    adc->CFG1 = ADC_CFG1_ADLSMP_MASK | mode | div;
+
+    /* select ADxxb channels, longest sample time (20 extra ADC cycles) */
+    adc->CFG2 = ADC_CFG2_MUXSEL_MASK | ADC_CFG2_ADLSTS(0);
+
+    /* select software trigger, external ref pins */
+    adc->SC2 = ADC_SC2_REFSEL(0);
+
+    /* select hardware average over 32 samples */
+    adc->SC3 = ADC_SC3_AVGE_MASK | ADC_SC3_AVGS(3);
+
+    /* set an (arbitrary) input channel, single-ended mode */
+    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH0);
+    adc->SC1[1] = ADC_SC1_ADCH(ADC_0_CH0);
+
+    /* perform calibration routine */
+    if (kinetis_adc_calibrate(adc) != 0) {
+        return -1;
+    }
+
+    return 0;
+}
+
+int adc_sample(adc_t dev, int channel)
+{
+    ADC_Type *adc = 0;
+
+    switch (dev) {
+#if ADC_0_EN
+
+        case ADC_0:
+            adc = ADC_0_DEV;
+
+            /* start single conversion on corresponding channel */
+            switch (channel) {
+                case 0:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH0);
+                    break;
+
+                case 1:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH1);
+                    break;
+
+                case 2:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH2);
+                    break;
+
+                case 3:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH3);
+                    break;
+
+                case 4:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH4);
+                    break;
+
+                case 5:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_0_CH5);
+                    break;
+
+                default:
+                    return -1;
+            }
+
+            break;
+#endif
+#if ADC_1_EN
+
+        case ADC_1:
+            adc = ADC_1_DEV;
+
+            /* start single conversion on corresponding channel */
+            switch (channel) {
+                case 0:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH0);
+                    break;
+
+                case 1:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH1);
+                    break;
+
+                case 2:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH2);
+                    break;
+
+                case 3:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH3);
+                    break;
+
+                case 4:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH4);
+                    break;
+
+                case 5:
+                    adc->SC1[0] = ADC_SC1_ADCH(ADC_1_CH5);
+                    break;
+
+                default:
+                    return -1;
+            }
+
+            break;
+#endif
+    }
+
+    /* wait until conversion is complete */
+    /* TODO: Use interrupts and yield the thread */
+    while (!(adc->SC1[0] & ADC_SC1_COCO_MASK));
+
+    /* read and return result */
+    return (int)adc->R[0];
+}
+
+void adc_poweron(adc_t dev)
+{
+    switch (dev) {
+#if ADC_0_EN
+
+        case ADC_0:
+            ADC_0_CLKEN();
+            break;
+#endif
+#if ADC_1_EN
+
+        case ADC_1:
+            ADC_1_CLKEN();
+            break;
+#endif
+    }
+}
+
+void adc_poweroff(adc_t dev)
+{
+    switch (dev) {
+#if ADC_0_EN
+
+        case ADC_0:
+            ADC_0_CLKDIS();
+            break;
+#endif
+#if ADC_1_EN
+
+        case ADC_1:
+            ADC_1_CLKDIS();
+            break;
+#endif
+    }
+}
+
+int adc_map(adc_t dev, int value, int min, int max)
+{
+    int scale = max - min;
+
+    /* NB: There is additional room for the multiplication result if using the
+     * actual precision setting of the ADC as the limit in this if statement: */
+    if (scale < (1 << 16)) {
+        /* The ADCs on these CPUs are limited to 16 bits, the result of
+         * value x scale will be 31 bits long or less. We use the upper part
+         * of a 32 bit word when scaling */
+        int32_t tmp = value * scale;
+        /* Divide by ADC range to get the scaled result */
+        return (tmp / (1 << adc_config[dev].bits));
+    }
+    else {
+        /* Target scale is too large to use int32_t as an in between result */
+        int64_t tmp = scale;
+        /* Make sure the compiler does not generate code which will truncate the
+         * result. */
+        tmp *= value;
+        /* Divide by ADC range to get the scaled result */
+        tmp /= (1 << adc_config[dev].bits);
+        return tmp;
+    }
+}
+
+float adc_mapf(adc_t dev, int value, float min, float max)
+{
+    return ((max - min) / ((float)adc_config[dev].max_value)) * value;
+}
+
+#endif /* ADC_NUMOF */
diff --git a/cpu/kinetis_common/cpuid.c b/cpu/kinetis_common/cpuid.c
new file mode 100644
index 0000000000..8084cc3693
--- /dev/null
+++ b/cpu/kinetis_common/cpuid.c
@@ -0,0 +1,30 @@
+/*
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_cpuid
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level CPUID driver implementation
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include <string.h>
+#include "cpu-conf.h"
+
+#include "periph/cpuid.h"
+
+void cpuid_get(void *id)
+{
+    memcpy(id, CPUID_ID_PTR, CPUID_ID_LEN);
+}
diff --git a/cpu/kinetis_common/doc.txt b/cpu/kinetis_common/doc.txt
new file mode 100644
index 0000000000..2bf6fe4853
--- /dev/null
+++ b/cpu/kinetis_common/doc.txt
@@ -0,0 +1,328 @@
+/**
+ * @defgroup    cpu_kinetis_common Freescale Kinetis MCU
+ * @ingroup     cpu
+ * @brief       Common Drivers for Freescale Kinetis MCUs
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_adc Kinetis ADC
+ * @ingroup     cpu_kinetis_common
+ * @brief       ADC driver.
+ *
+ *              ### ADC Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define ADC_NUMOF           (1U)
+ *                  #define ADC_0_EN            1
+ *                  #define ADC_MAX_CHANNELS    1
+ *                  
+ *                  // ADC 0 configuration
+ *                  #define ADC_0_DEV           ADC0
+ *                  #define ADC_0_MODULE_CLOCK  CLOCK_CORECLOCK
+ *                  #define ADC_0_CHANNELS      1
+ *                  #define ADC_0_CLKEN()       (SIM->SCGC6 |= (SIM_SCGC6_ADC0_MASK))
+ *                  #define ADC_0_CLKDIS()      (SIM->SCGC6 &= ~(SIM_SCGC6_ADC0_MASK))
+ *                  #define ADC_0_PORT_CLKEN()  (SIM->SCGC5 |= (SIM_SCGC5_PORTE_MASK))
+ *                  
+ *                  #define ADC_0_CH5           11
+ *                  #define ADC_0_CH5_PIN       1
+ *                  #define ADC_0_CH5_PIN_AF    0
+ *                  #define ADC_0_CH5_PORT      PORTE
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_cpuid Kinetis CPUID
+ * @ingroup     cpu_kinetis_common
+ * @brief       CPUID driver.
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_gpio Kinetis GPIO
+ * @ingroup     cpu_kinetis_common
+ * @brief       GPIO driver.
+ *
+ *              ### GPIO Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define GPIO_NUMOF          1
+ *                  #define GPIO_0_EN           0
+ *                  #define GPIO_IRQ_PRIO       1
+ *                  #define ISR_PORT_D          isr_portd
+ *
+ *                  #define GPIO_22_DEV         GPIOD
+ *                  #define GPIO_22_PORT        PORTD
+ *                  #define GPIO_22_PIN         1
+ *                  #define GPIO_22_CLKEN()     (SIM->SCGC5 |= (SIM_SCGC5_PORTD_MASK))
+ *                  #define GPIO_22_IRQ         PORTD_IRQn
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_i2c Kinetis I2C
+ * @ingroup     cpu_kinetis_common
+ * @brief       I2C driver.
+ *
+ *              ### I2C Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define I2C_NUMOF               (1U)
+ *                  #define I2C_CLK                 (48e6)
+ *                  #define I2C_0_EN                1
+ *                  #define I2C_IRQ_PRIO            1
+ *                  
+ *                  // I2C 0 device configuration
+ *                  #define I2C_0_DEV               I2C1
+ *                  #define I2C_0_CLKEN()           (SIM->SCGC4 |= (SIM_SCGC4_I2C1_MASK))
+ *                  #define I2C_0_CLKDIS()          (SIM->SCGC4 &= ~(SIM_SCGC4_I2C1_MASK))
+ *                  #define I2C_0_IRQ               I2C1_IRQn
+ *                  #define I2C_0_IRQ_HANDLER       isr_i2c1
+ *                  // I2C 0 pin configuration
+ *                  #define I2C_0_PORT              PORTE
+ *                  #define I2C_0_PORT_CLKEN()      (SIM->SCGC5 |= (SIM_SCGC5_PORTE_MASK))
+ *                  #define I2C_0_PIN_AF            6
+ *                  #define I2C_0_SDA_PIN           0
+ *                  #define I2C_0_SCL_PIN           1
+ *                  #define I2C_0_PORT_CFG          (PORT_PCR_MUX(I2C_0_PIN_AF) | PORT_PCR_ODE_MASK)
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_pwm Kinetis PWM
+ * @ingroup     cpu_kinetis_common
+ * @brief       PWM driver.
+ *
+ *              ### PWM Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define PWM_NUMOF           (1U)
+ *                  #define PWM_0_EN            1
+ *                  #define PWM_MAX_CHANNELS    2
+ *                  
+ *                  // PWM 0 device configuration
+ *                  #define PWM_0_DEV           FTM0
+ *                  #define PWM_0_CHANNELS      2
+ *                  #define PWM_0_CLK           (48e6)
+ *                  #define PWM_0_CLKEN()       (SIM->SCGC6 |= (SIM_SCGC6_FTM0_MASK))
+ *                  #define PWM_0_CLKDIS()      (SIM->SCGC6 &= ~(SIM_SCGC6_FTM0_MASK))
+ *                  // PWM 0 pin configuration
+ *                  #define PWM_0_PORT_CLKEN()  (SIM->SCGC5 |= (SIM_SCGC5_PORTD_MASK | SIM_SCGC5_PORTA_MASK))
+ *                  
+ *                  #define PWM_0_PIN_CH0       4
+ *                  #define PWM_0_FTMCHAN_CH0   1
+ *                  #define PWM_0_PORT_CH0      PORTA
+ *                  #define PWM_0_PIN_AF_CH0    3
+ *                  
+ *                  #define PWM_0_PIN_CH1       4
+ *                  #define PWM_0_FTMCHAN_CH1   4
+ *                  #define PWM_0_PORT_CH1      PORTD
+ *                  #define PWM_0_PIN_AF_CH1    4
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_rnga Kinetis RNGA
+ * @ingroup     cpu_kinetis_common
+ * @brief       Driver for Freescale's RNGA module. RNGA generates data that
+ *              looks random. Reference Manual recommends to use the RNGA as entropy
+ *              source.
+ *
+ *              ### RNGA Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define RANDOM_NUMOF         (1U)
+ *                  #define KINETIS_RNGA         RNG
+ *                  #define RANDOM_CLKEN()       (SIM->SCGC6 |= (1 << 9))
+ *                  #define RANDOM_CLKDIS()      (SIM->SCGC6 &= ~(1 << 9))
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_rngb Kinetis RNGB
+ * @ingroup     cpu_kinetis_common
+ * @brief       Low-level random number generator driver implementation.
+ *              Driver for Freescale's RNGB module. RNGB generates data that
+ *              looks random. Reference Manual recommends to use the RNGB as entropy
+ *              source.
+ *
+ *              ### RNGB Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define RANDOM_NUMOF         (1U)
+ *                  #define KINETIS_RNGB         RNG
+ *                  #define RANDOM_CLKEN()       (SIM->SCGC6 |= (1 << 9))
+ *                  #define RANDOM_CLKDIS()      (SIM->SCGC6 &= ~(1 << 9))
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_rtc Kinetis RTC
+ * @ingroup     cpu_kinetis_common
+ * @brief       RTC is clocked by a 32.768 kHz clock.
+ *              Please note the manual of your MCU or SiP for the
+ *              clock setting for the RTC module. After initilization
+ *              Time Seconds Register (TSR) increments once a second.
+ *              The TSR (also TAR) value will be converted to the stuct tm
+ *              and back with the help of stdlib functions that are
+ *              defined in time.h.
+ *              The driver supports alarm, it is stored in the
+ *              Time Alarm Registers (TAR) and the unit is seconds.
+ *
+ *              ### RTC Configuration Example (for periph_conf.h) ###
+ *
+ *                  #define RTC_NUMOF           (1U)
+ *                  #define RTC_DEV             RTC
+ *                  #define RTC_UNLOCK()        (SIM->SCGC6 |= (SIM_SCGC6_RTC_MASK))
+ *
+ *              Optional settings:
+ *
+ *                  #define RTC_LOAD_CAP_BITS   0
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_spi Kinetis SPI
+ * @ingroup     cpu_kinetis_common
+ * @brief       Kinetis SPI driver for MCUs with Cortex-M4 core.
+ *
+ *              If necessary, it is possible to define two RIOT SPI buses for
+ *              each Kinetis hardware SPI module by specifying different CTAS
+ *              (timing register number) for the two buses. It is then possible to
+ *              initialize the two RIOT SPI buses with different baud rates or
+ *              polarity settings.
+ *
+ *              SPI_x_INDEX should be set to the index on the hardware module
+ *              used (SPI0 => 0, SPI1 => 1 etc). spi_acquire and spi_release will
+ *              share the same lock for all SPI buses defined with the same
+ *              SPI_x_INDEX.
+ *
+ *              Finer tuning of timings than the RIOT SPI API is capable of is
+ *              supported by setting macros SPI_0_TCSC_FREQ, SPI_0_TASC_FREQ,
+ *              SPI_0_TDT_FREQ. These macros define the desired maximum frequency
+ *              of the t<SUB>CSC</SUB>, t<SUB>ASC</SUB>, and t<SUB>DT</SUB> SPI
+ *              timings (i.e. reciprocal of time). See the reference manual for
+ *              your Kinetis CPU (Chapter: "SPI module, Functional description,
+ *              Module baud rate and clock delay generation") for a description of
+ *              each delay. Set to 0 or leave unset to default to using the same
+ *              delay timing as the baudrate.
+ *
+ *              ### SPI Configuration Example (for periph_conf.h): ###
+ *
+ *                  // SPI 0 device config
+ *                  #define SPI_0_DEV               SPI0
+ *                  #define SPI_0_INDEX             0
+ *                  #define SPI_0_CTAS              0
+ *                  #define SPI_0_CLKEN()           (SIM->SCGC6 |= (SIM_SCGC6_SPI0_MASK))
+ *                  #define SPI_0_CLKDIS()          (SIM->SCGC6 &= ~(SIM_SCGC6_SPI0_MASK))
+ *                  #define SPI_0_IRQ               SPI0_IRQn
+ *                  #define SPI_0_IRQ_HANDLER       isr_spi0
+ *                  #define SPI_0_FREQ              (48e6)
+ *
+ *                  // SPI 0 pin configuration
+ *                  #define SPI_0_SCK_PORT          PORTC
+ *                  #define SPI_0_SOUT_PORT         PORTC
+ *                  #define SPI_0_SIN_PORT          PORTC
+ *                  #define SPI_0_PCS0_PORT         PORTC
+ *
+ *                  #define SPI_0_SCK_PORT_CLKEN()  (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+ *                  #define SPI_0_SOUT_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+ *                  #define SPI_0_SIN_PORT_CLKEN()  (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+ *                  #define SPI_0_PCS0_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+ *
+ *                  #define SPI_0_SCK_AF            2
+ *                  #define SPI_0_SOUT_AF           2
+ *                  #define SPI_0_SIN_AF            2
+ *                  #define SPI_0_PCS0_AF           2
+ *
+ *                  #define SPI_0_PCS0_PIN          4
+ *                  #define SPI_0_SCK_PIN           5
+ *                  #define SPI_0_SOUT_PIN          6
+ *                  #define SPI_0_SIN_PIN           7
+ *
+ *                  #define SPI_0_PCS0_ACTIVE_LOW   1
+ *
+ *              Alternative Configuration Example:
+ *
+ *                  // SPI 0 device config
+ *                  #define SPI_0_DEV               SPI0
+ *                  #define SPI_0_INDEX             0
+ *                  #define SPI_0_CTAS              0
+ *                  #define SPI_0_CLKEN()           (SIM->SCGC6 |= (SIM_SCGC6_SPI0_MASK))
+ *                  #define SPI_0_CLKDIS()          (SIM->SCGC6 &= ~(SIM_SCGC6_SPI0_MASK))
+ *                  #define SPI_0_IRQ               SPI0_IRQn
+ *                  #define SPI_0_IRQ_HANDLER       isr_spi0
+ *                  #define SPI_0_FREQ              (48e6)
+ *
+ *                  // SPI 0 pin configuration
+ *                  #define SPI_0_PORT              PORTC
+ *                  #define SPI_0_PORT_CLKEN()      (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+ *                  #define SPI_0_AF                2
+ *
+ *                  #define SPI_0_PCS0_PIN          4
+ *                  #define SPI_0_SCK_PIN           5
+ *                  #define SPI_0_SOUT_PIN          6
+ *                  #define SPI_0_SIN_PIN           7
+ *
+ *                  #define SPI_0_PCS0_ACTIVE_LOW   1
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_timer Kinetis Timer
+ * @ingroup     cpu_kinetis_common
+ * @brief       Periodic Interrupt Timer (PIT) driver.
+ *              Implementation of riot-os low level timer interface 
+ *              for the Kinetis Periodic Interrupt Timer.
+ *              The PIT is a count down timer, in order to use it with riot-os
+ *              a count up timer will be simulated. The PIT has four channels,
+ *              each two channels are cascaded. The n-1 channel is a prescaler
+ *              and the n channel a down counter. In standard configuration
+ *              with four channels, two simulated count up timer are possible.
+ *
+ *              ### Timer configuration Example (for periph_conf.h) ###
+ *
+ *                  #define TIMER_NUMOF             (1U)
+ *                  #define TIMER_0_EN              1
+ *                  #define TIMER_1_EN              0
+ *                  #define TIMER_IRQ_PRIO          1
+ *                  #define TIMER_DEV               PIT
+ *                  #define TIMER_MAX_VALUE         (0xffffffff)
+ *                  #define TIMER_CLOCK             CLOCK_CORECLOCK
+ *                  #define TIMER_CLKEN()           (SIM->SCGC6 |= (SIM_SCGC6_PIT_MASK))
+ *                  
+ *                  // Timer 0 configuration 
+ *                  #define TIMER_0_PRESCALER_CH    0
+ *                  #define TIMER_0_COUNTER_CH      1
+ *                  #define TIMER_0_ISR             isr_pit1
+ *                  #define TIMER_0_IRQ_CHAN        PIT1_IRQn
+ *
+ *                  // Timer 1 configuration
+ *                  #define TIMER_1_PRESCALER_CH    2
+ *                  #define TIMER_1_COUNTER_CH      3
+ *                  #define TIMER_1_ISR             isr_pit3
+ *                  #define TIMER_1_IRQ_CHAN        PIT3_IRQn
+ *
+ */
+
+/**
+ * @defgroup    cpu_kinetis_common_uart Kinetis UART
+ * @ingroup     cpu_kinetis_common
+ * @brief       Kinetis UART driver.
+ *              There are different implementations of the UART interface.
+ *              The treatment of interrupts is also slightly different.
+ *              The register UARTx_BDH to UARTx_C4 look almost the same.
+ *              We distinguish the type of the UART
+ *              using the BRFA field in the UART C4 register.
+ *              Currently, only the base functionality is available.
+ *
+ *              ### UART configuration Example (for periph_conf.h) ###
+ *
+ *                  #define UART_NUMOF          (1U)
+ *                  #define UART_0_EN           1
+ *                  #define UART_IRQ_PRIO       1
+ *                  #define UART_CLK            (48e6)
+ *
+ *                  // UART 0 device configuration
+ *                  #define KINETIS_UART        UART0_Type
+ *                  #define UART_0_DEV          UART0
+ *                  #define UART_0_CLKEN()      (SIM->SCGC4 |= (SIM_SCGC4_UART0_MASK))
+ *                  #define UART_0_CLK          UART_CLK
+ *                  #define UART_0_IRQ_CHAN     UART0_IRQn
+ *                  #define UART_0_ISR          isr_uart0
+ *                  // UART 0 pin configuration
+ *                  #define UART_0_PORT_CLKEN() (SIM->SCGC5 |= (SIM_SCGC5_PORTA_MASK))
+ *                  #define UART_0_PORT         PORTA
+ *                  #define UART_0_RX_PIN       1
+ *                  #define UART_0_TX_PIN       2
+ *                  #define UART_0_AF           2
+ *
+ *              Optional settings:
+ *
+ *                  #define KINETIS_UART_ADVANCED    1
+ */
diff --git a/cpu/kinetis_common/gpio.c b/cpu/kinetis_common/gpio.c
new file mode 100644
index 0000000000..88afa226ba
--- /dev/null
+++ b/cpu/kinetis_common/gpio.c
@@ -0,0 +1,3520 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ * Copyright (C) 2014 Eistec AB
+ *
+ * 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     cpu_kinetis_common_gpio
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level GPIO driver implementation
+ *
+ * @author      Hauke Petersen <mail@haukepetersen.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ * @author      Jonas Remmert <j.remmert@phytec.de>
+ * @author      Joakim Gebart <joakim.gebart@eistec.se
+ *
+ * @}
+ */
+
+#include "cpu.h"
+#include "sched.h"
+#include "thread.h"
+#include "periph/gpio.h"
+#include "periph_conf.h"
+
+#if GPIO_NUMOF
+
+#ifndef PIN_MUX_FUNCTION_ANALOG
+#define PIN_MUX_FUNCTION_ANALOG     0
+#endif
+
+#ifndef PIN_MUX_FUNCTION_GPIO
+#define PIN_MUX_FUNCTION_GPIO       1
+#endif
+
+#ifndef PIN_INTERRUPT_RISING
+#define PIN_INTERRUPT_RISING        0x9
+#endif
+
+#ifndef PIN_INTERRUPT_FALLING
+#define PIN_INTERRUPT_FALLING       0xa
+#endif
+
+#ifndef PIN_INTERRUPT_EDGE
+#define PIN_INTERRUPT_EDGE          0xb
+#endif
+
+typedef struct {
+    gpio_cb_t cb;       /**< callback called from GPIO interrupt */
+    void *arg;          /**< argument passed to the callback */
+    uint32_t irqc;      /**< remember interrupt configuration between disable/enable */
+} gpio_state_t;
+
+/**
+ * @brief Unified IRQ handler shared by all interrupt routines
+ *
+ * @param[in] dev   the device that triggered the interrupt
+ */
+static inline void irq_handler(gpio_t dev);
+
+/**
+ * @brief Hold one callback function pointer for each gpio device
+ */
+static gpio_state_t config[GPIO_NUMOF];
+
+int gpio_init_out(gpio_t dev, gpio_pp_t pushpull)
+{
+    PORT_Type *port;
+    GPIO_Type *gpio;
+    uint32_t pin = 0;
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            GPIO_0_CLKEN();
+            port = GPIO_0_PORT;
+            gpio = GPIO_0_DEV;
+            pin = GPIO_0_PIN;
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            GPIO_1_CLKEN();
+            port = GPIO_1_PORT;
+            gpio = GPIO_1_DEV;
+            pin = GPIO_1_PIN;
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            GPIO_2_CLKEN();
+            port = GPIO_2_PORT;
+            gpio = GPIO_2_DEV;
+            pin = GPIO_2_PIN;
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            GPIO_3_CLKEN();
+            port = GPIO_3_PORT;
+            gpio = GPIO_3_DEV;
+            pin = GPIO_3_PIN;
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            GPIO_4_CLKEN();
+            port = GPIO_4_PORT;
+            gpio = GPIO_4_DEV;
+            pin = GPIO_4_PIN;
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            GPIO_5_CLKEN();
+            port = GPIO_5_PORT;
+            gpio = GPIO_5_DEV;
+            pin = GPIO_5_PIN;
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            GPIO_6_CLKEN();
+            port = GPIO_6_PORT;
+            gpio = GPIO_6_DEV;
+            pin = GPIO_6_PIN;
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            GPIO_7_CLKEN();
+            port = GPIO_7_PORT;
+            gpio = GPIO_7_DEV;
+            pin = GPIO_7_PIN;
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            GPIO_8_CLKEN();
+            port = GPIO_8_PORT;
+            gpio = GPIO_8_DEV;
+            pin = GPIO_8_PIN;
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            GPIO_9_CLKEN();
+            port = GPIO_9_PORT;
+            gpio = GPIO_9_DEV;
+            pin = GPIO_9_PIN;
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            GPIO_10_CLKEN();
+            port = GPIO_10_PORT;
+            gpio = GPIO_10_DEV;
+            pin = GPIO_10_PIN;
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            GPIO_11_CLKEN();
+            port = GPIO_11_PORT;
+            gpio = GPIO_11_DEV;
+            pin = GPIO_11_PIN;
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            GPIO_12_CLKEN();
+            port = GPIO_12_PORT;
+            gpio = GPIO_12_DEV;
+            pin = GPIO_12_PIN;
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            GPIO_13_CLKEN();
+            port = GPIO_13_PORT;
+            gpio = GPIO_13_DEV;
+            pin = GPIO_13_PIN;
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            GPIO_14_CLKEN();
+            port = GPIO_14_PORT;
+            gpio = GPIO_14_DEV;
+            pin = GPIO_14_PIN;
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            GPIO_15_CLKEN();
+            port = GPIO_15_PORT;
+            gpio = GPIO_15_DEV;
+            pin = GPIO_15_PIN;
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            GPIO_16_CLKEN();
+            port = GPIO_16_PORT;
+            gpio = GPIO_16_DEV;
+            pin = GPIO_16_PIN;
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            GPIO_17_CLKEN();
+            port = GPIO_17_PORT;
+            gpio = GPIO_17_DEV;
+            pin = GPIO_17_PIN;
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            GPIO_18_CLKEN();
+            port = GPIO_18_PORT;
+            gpio = GPIO_18_DEV;
+            pin = GPIO_18_PIN;
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            GPIO_19_CLKEN();
+            port = GPIO_19_PORT;
+            gpio = GPIO_19_DEV;
+            pin = GPIO_19_PIN;
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            GPIO_20_CLKEN();
+            port = GPIO_20_PORT;
+            gpio = GPIO_20_DEV;
+            pin = GPIO_20_PIN;
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            GPIO_21_CLKEN();
+            port = GPIO_21_PORT;
+            gpio = GPIO_21_DEV;
+            pin = GPIO_21_PIN;
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            GPIO_22_CLKEN();
+            port = GPIO_22_PORT;
+            gpio = GPIO_22_DEV;
+            pin = GPIO_22_PIN;
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            GPIO_23_CLKEN();
+            port = GPIO_23_PORT;
+            gpio = GPIO_23_DEV;
+            pin = GPIO_23_PIN;
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            GPIO_24_CLKEN();
+            port = GPIO_24_PORT;
+            gpio = GPIO_24_DEV;
+            pin = GPIO_24_PIN;
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            GPIO_25_CLKEN();
+            port = GPIO_25_PORT;
+            gpio = GPIO_25_DEV;
+            pin = GPIO_25_PIN;
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            GPIO_26_CLKEN();
+            port = GPIO_26_PORT;
+            gpio = GPIO_26_DEV;
+            pin = GPIO_26_PIN;
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            GPIO_27_CLKEN();
+            port = GPIO_27_PORT;
+            gpio = GPIO_27_DEV;
+            pin = GPIO_27_PIN;
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            GPIO_28_CLKEN();
+            port = GPIO_28_PORT;
+            gpio = GPIO_28_DEV;
+            pin = GPIO_28_PIN;
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            GPIO_29_CLKEN();
+            port = GPIO_29_PORT;
+            gpio = GPIO_29_DEV;
+            pin = GPIO_29_PIN;
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            GPIO_30_CLKEN();
+            port = GPIO_30_PORT;
+            gpio = GPIO_30_DEV;
+            pin = GPIO_30_PIN;
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            GPIO_31_CLKEN();
+            port = GPIO_31_PORT;
+            gpio = GPIO_31_DEV;
+            pin = GPIO_31_PIN;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* Clear interrupt config */
+    config[dev].cb = NULL;
+    config[dev].arg = NULL;
+    config[dev].irqc = 0;
+
+    /* Reset all pin control settings for the pin */
+    /* Switch to analog input function while fiddling with the settings, to be safe. */
+    port->PCR[pin] = PORT_PCR_MUX(PIN_MUX_FUNCTION_ANALOG);
+
+    /* set to push-pull configuration */
+    switch (pushpull) {
+        case GPIO_PULLUP:
+            port->PCR[pin] |= PORT_PCR_PE_MASK | PORT_PCR_PS_MASK; /* Pull enable, pull up */
+            break;
+
+        case GPIO_PULLDOWN:
+            port->PCR[pin] |= PORT_PCR_PE_MASK; /* Pull enable, !pull up */
+            break;
+
+        default:
+            break;
+    }
+
+    gpio->PDDR |= GPIO_PDDR_PDD(1 << pin);     /* set pin to output mode */
+    gpio->PCOR |= GPIO_PCOR_PTCO(1 << pin);    /* set output to low */
+    /* Select GPIO function for the pin */
+    port->PCR[pin] |= PORT_PCR_MUX(PIN_MUX_FUNCTION_GPIO);
+
+    return 0;
+}
+
+int gpio_init_in(gpio_t dev, gpio_pp_t pushpull)
+{
+    PORT_Type *port;
+    GPIO_Type *gpio;
+    uint32_t pin = 0;
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            GPIO_0_CLKEN();
+            port = GPIO_0_PORT;
+            gpio = GPIO_0_DEV;
+            pin = GPIO_0_PIN;
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            GPIO_1_CLKEN();
+            port = GPIO_1_PORT;
+            gpio = GPIO_1_DEV;
+            pin = GPIO_1_PIN;
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            GPIO_2_CLKEN();
+            port = GPIO_2_PORT;
+            gpio = GPIO_2_DEV;
+            pin = GPIO_2_PIN;
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            GPIO_3_CLKEN();
+            port = GPIO_3_PORT;
+            gpio = GPIO_3_DEV;
+            pin = GPIO_3_PIN;
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            GPIO_4_CLKEN();
+            port = GPIO_4_PORT;
+            gpio = GPIO_4_DEV;
+            pin = GPIO_4_PIN;
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            GPIO_5_CLKEN();
+            port = GPIO_5_PORT;
+            gpio = GPIO_5_DEV;
+            pin = GPIO_5_PIN;
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            GPIO_6_CLKEN();
+            port = GPIO_6_PORT;
+            gpio = GPIO_6_DEV;
+            pin = GPIO_6_PIN;
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            GPIO_7_CLKEN();
+            port = GPIO_7_PORT;
+            gpio = GPIO_7_DEV;
+            pin = GPIO_7_PIN;
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            GPIO_8_CLKEN();
+            port = GPIO_8_PORT;
+            gpio = GPIO_8_DEV;
+            pin = GPIO_8_PIN;
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            GPIO_9_CLKEN();
+            port = GPIO_9_PORT;
+            gpio = GPIO_9_DEV;
+            pin = GPIO_9_PIN;
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            GPIO_10_CLKEN();
+            port = GPIO_10_PORT;
+            gpio = GPIO_10_DEV;
+            pin = GPIO_10_PIN;
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            GPIO_11_CLKEN();
+            port = GPIO_11_PORT;
+            gpio = GPIO_11_DEV;
+            pin = GPIO_11_PIN;
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            GPIO_12_CLKEN();
+            port = GPIO_12_PORT;
+            gpio = GPIO_12_DEV;
+            pin = GPIO_12_PIN;
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            GPIO_13_CLKEN();
+            port = GPIO_13_PORT;
+            gpio = GPIO_13_DEV;
+            pin = GPIO_13_PIN;
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            GPIO_14_CLKEN();
+            port = GPIO_14_PORT;
+            gpio = GPIO_14_DEV;
+            pin = GPIO_14_PIN;
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            GPIO_15_CLKEN();
+            port = GPIO_15_PORT;
+            gpio = GPIO_15_DEV;
+            pin = GPIO_15_PIN;
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            GPIO_16_CLKEN();
+            port = GPIO_16_PORT;
+            gpio = GPIO_16_DEV;
+            pin = GPIO_16_PIN;
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            GPIO_17_CLKEN();
+            port = GPIO_17_PORT;
+            gpio = GPIO_17_DEV;
+            pin = GPIO_17_PIN;
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            GPIO_18_CLKEN();
+            port = GPIO_18_PORT;
+            gpio = GPIO_18_DEV;
+            pin = GPIO_18_PIN;
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            GPIO_19_CLKEN();
+            port = GPIO_19_PORT;
+            gpio = GPIO_19_DEV;
+            pin = GPIO_19_PIN;
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            GPIO_20_CLKEN();
+            port = GPIO_20_PORT;
+            gpio = GPIO_20_DEV;
+            pin = GPIO_20_PIN;
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            GPIO_21_CLKEN();
+            port = GPIO_21_PORT;
+            gpio = GPIO_21_DEV;
+            pin = GPIO_21_PIN;
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            GPIO_22_CLKEN();
+            port = GPIO_22_PORT;
+            gpio = GPIO_22_DEV;
+            pin = GPIO_22_PIN;
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            GPIO_23_CLKEN();
+            port = GPIO_23_PORT;
+            gpio = GPIO_23_DEV;
+            pin = GPIO_23_PIN;
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            GPIO_24_CLKEN();
+            port = GPIO_24_PORT;
+            gpio = GPIO_24_DEV;
+            pin = GPIO_24_PIN;
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            GPIO_25_CLKEN();
+            port = GPIO_25_PORT;
+            gpio = GPIO_25_DEV;
+            pin = GPIO_25_PIN;
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            GPIO_26_CLKEN();
+            port = GPIO_26_PORT;
+            gpio = GPIO_26_DEV;
+            pin = GPIO_26_PIN;
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            GPIO_27_CLKEN();
+            port = GPIO_27_PORT;
+            gpio = GPIO_27_DEV;
+            pin = GPIO_27_PIN;
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            GPIO_28_CLKEN();
+            port = GPIO_28_PORT;
+            gpio = GPIO_28_DEV;
+            pin = GPIO_28_PIN;
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            GPIO_29_CLKEN();
+            port = GPIO_29_PORT;
+            gpio = GPIO_29_DEV;
+            pin = GPIO_29_PIN;
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            GPIO_30_CLKEN();
+            port = GPIO_30_PORT;
+            gpio = GPIO_30_DEV;
+            pin = GPIO_30_PIN;
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            GPIO_31_CLKEN();
+            port = GPIO_31_PORT;
+            gpio = GPIO_31_DEV;
+            pin = GPIO_31_PIN;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* Reset all pin control settings for the pin */
+    /* Switch to analog input function while fiddling with the settings, to be safe. */
+    port->PCR[pin] = PORT_PCR_MUX(PIN_MUX_FUNCTION_ANALOG);
+
+    /* set to push-pull configuration */
+    switch (pushpull) {
+        case GPIO_NOPULL:
+            break;
+
+        case GPIO_PULLUP:
+            port->PCR[pin] |= PORT_PCR_PE_MASK | PORT_PCR_PS_MASK; /* Pull enable, pull up */
+            break;
+
+        case GPIO_PULLDOWN:
+            port->PCR[pin] |= PORT_PCR_PE_MASK; /* Pull enable */
+            break;
+
+        default:
+            break;
+    }
+
+    gpio->PDDR &= ~(GPIO_PDDR_PDD(1 << pin));     /* set pin to input mode */
+    /* Select GPIO function for the pin */
+    port->PCR[pin] |= PORT_PCR_MUX(PIN_MUX_FUNCTION_GPIO);
+
+    return 0;
+}
+
+int gpio_init_int(gpio_t dev, gpio_pp_t pushpull, gpio_flank_t flank, gpio_cb_t cb, void *arg)
+{
+    PORT_Type *port;
+    int res;
+    uint32_t pin = 0;
+
+    res = gpio_init_in(dev, pushpull);
+
+    if (res < 0) {
+        return res;
+    }
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            port = GPIO_0_PORT;
+            pin = GPIO_0_PIN;
+            NVIC_SetPriority(GPIO_0_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_0_IRQ);
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            port = GPIO_1_PORT;
+            pin = GPIO_1_PIN;
+            NVIC_SetPriority(GPIO_1_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_1_IRQ);
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            port = GPIO_2_PORT;
+            pin = GPIO_2_PIN;
+            NVIC_SetPriority(GPIO_2_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_2_IRQ);
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            port = GPIO_3_PORT;
+            pin = GPIO_3_PIN;
+            NVIC_SetPriority(GPIO_3_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_3_IRQ);
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            port = GPIO_4_PORT;
+            pin = GPIO_4_PIN;
+            NVIC_SetPriority(GPIO_4_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_4_IRQ);
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            port = GPIO_5_PORT;
+            pin = GPIO_5_PIN;
+            NVIC_SetPriority(GPIO_5_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_5_IRQ);
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            port = GPIO_6_PORT;
+            pin = GPIO_6_PIN;
+            NVIC_SetPriority(GPIO_6_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_6_IRQ);
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            port = GPIO_7_PORT;
+            pin = GPIO_7_PIN;
+            NVIC_SetPriority(GPIO_7_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_7_IRQ);
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            port = GPIO_8_PORT;
+            pin = GPIO_8_PIN;
+            NVIC_SetPriority(GPIO_8_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_8_IRQ);
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            port = GPIO_9_PORT;
+            pin = GPIO_9_PIN;
+            NVIC_SetPriority(GPIO_9_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_9_IRQ);
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            port = GPIO_10_PORT;
+            pin = GPIO_10_PIN;
+            NVIC_SetPriority(GPIO_10_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_10_IRQ);
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            port = GPIO_11_PORT;
+            pin = GPIO_11_PIN;
+            NVIC_SetPriority(GPIO_11_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_11_IRQ);
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            port = GPIO_12_PORT;
+            pin = GPIO_12_PIN;
+            NVIC_SetPriority(GPIO_12_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_12_IRQ);
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            port = GPIO_13_PORT;
+            pin = GPIO_13_PIN;
+            NVIC_SetPriority(GPIO_13_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_13_IRQ);
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            port = GPIO_14_PORT;
+            pin = GPIO_14_PIN;
+            NVIC_SetPriority(GPIO_14_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_14_IRQ);
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            port = GPIO_15_PORT;
+            pin = GPIO_15_PIN;
+            NVIC_SetPriority(GPIO_15_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_15_IRQ);
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            port = GPIO_16_PORT;
+            pin = GPIO_16_PIN;
+            NVIC_SetPriority(GPIO_16_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_16_IRQ);
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            port = GPIO_17_PORT;
+            pin = GPIO_17_PIN;
+            NVIC_SetPriority(GPIO_17_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_17_IRQ);
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            port = GPIO_18_PORT;
+            pin = GPIO_18_PIN;
+            NVIC_SetPriority(GPIO_18_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_18_IRQ);
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            port = GPIO_19_PORT;
+            pin = GPIO_19_PIN;
+            NVIC_SetPriority(GPIO_19_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_19_IRQ);
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            port = GPIO_20_PORT;
+            pin = GPIO_20_PIN;
+            NVIC_SetPriority(GPIO_20_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_20_IRQ);
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            port = GPIO_21_PORT;
+            pin = GPIO_21_PIN;
+            NVIC_SetPriority(GPIO_21_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_21_IRQ);
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            port = GPIO_22_PORT;
+            pin = GPIO_22_PIN;
+            NVIC_SetPriority(GPIO_22_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_22_IRQ);
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            port = GPIO_23_PORT;
+            pin = GPIO_23_PIN;
+            NVIC_SetPriority(GPIO_23_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_23_IRQ);
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            port = GPIO_24_PORT;
+            pin = GPIO_24_PIN;
+            NVIC_SetPriority(GPIO_24_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_24_IRQ);
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            port = GPIO_25_PORT;
+            pin = GPIO_25_PIN;
+            NVIC_SetPriority(GPIO_25_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_25_IRQ);
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            port = GPIO_26_PORT;
+            pin = GPIO_26_PIN;
+            NVIC_SetPriority(GPIO_26_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_26_IRQ);
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            port = GPIO_27_PORT;
+            pin = GPIO_27_PIN;
+            NVIC_SetPriority(GPIO_27_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_27_IRQ);
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            port = GPIO_28_PORT;
+            pin = GPIO_28_PIN;
+            NVIC_SetPriority(GPIO_28_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_28_IRQ);
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            port = GPIO_29_PORT;
+            pin = GPIO_29_PIN;
+            NVIC_SetPriority(GPIO_29_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_29_IRQ);
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            port = GPIO_30_PORT;
+            pin = GPIO_30_PIN;
+            NVIC_SetPriority(GPIO_30_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_30_IRQ);
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            port = GPIO_31_PORT;
+            pin = GPIO_31_PIN;
+            NVIC_SetPriority(GPIO_31_IRQ, GPIO_IRQ_PRIO);
+            NVIC_EnableIRQ(GPIO_31_IRQ);
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* set callback */
+    config[dev].cb = cb;
+    config[dev].arg = arg;
+
+    /* configure the active edges */
+    switch (flank) {
+        case GPIO_RISING:
+            port->PCR[pin] &= ~(PORT_PCR_IRQC_MASK); /* Disable interrupt */
+            port->PCR[pin] |= PORT_PCR_ISF_MASK; /* Clear interrupt flag */
+            port->PCR[pin] |= PORT_PCR_IRQC(PIN_INTERRUPT_RISING); /* Enable interrupt */
+            config[dev].irqc = PORT_PCR_IRQC(PIN_INTERRUPT_RISING);
+            break;
+
+        case GPIO_FALLING:
+            port->PCR[pin] &= ~(PORT_PCR_IRQC_MASK); /* Disable interrupt */
+            port->PCR[pin] |= PORT_PCR_ISF_MASK; /* Clear interrupt flag */
+            port->PCR[pin] |= PORT_PCR_IRQC(PIN_INTERRUPT_FALLING); /* Enable interrupt */
+            config[dev].irqc = PORT_PCR_IRQC(PIN_INTERRUPT_FALLING);
+            break;
+
+        case GPIO_BOTH:
+            port->PCR[pin] &= ~(PORT_PCR_IRQC_MASK); /* Disable interrupt */
+            port->PCR[pin] |= PORT_PCR_ISF_MASK; /* Clear interrupt flag */
+            port->PCR[pin] |= PORT_PCR_IRQC(PIN_INTERRUPT_EDGE); /* Enable interrupt */
+            config[dev].irqc = PORT_PCR_IRQC(PIN_INTERRUPT_EDGE);
+            break;
+
+        default:
+            /* Unknown setting */
+            return -1;
+    }
+
+    return 0;
+}
+
+void gpio_irq_enable(gpio_t dev)
+{
+    PORT_Type *port;
+    uint32_t pin = 0;
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            port = GPIO_0_PORT;
+            pin = GPIO_0_PIN;
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            port = GPIO_1_PORT;
+            pin = GPIO_1_PIN;
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            port = GPIO_2_PORT;
+            pin = GPIO_2_PIN;
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            port = GPIO_3_PORT;
+            pin = GPIO_3_PIN;
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            port = GPIO_4_PORT;
+            pin = GPIO_4_PIN;
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            port = GPIO_5_PORT;
+            pin = GPIO_5_PIN;
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            port = GPIO_6_PORT;
+            pin = GPIO_6_PIN;
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            port = GPIO_7_PORT;
+            pin = GPIO_7_PIN;
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            port = GPIO_8_PORT;
+            pin = GPIO_8_PIN;
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            port = GPIO_9_PORT;
+            pin = GPIO_9_PIN;
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            port = GPIO_10_PORT;
+            pin = GPIO_10_PIN;
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            port = GPIO_11_PORT;
+            pin = GPIO_11_PIN;
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            port = GPIO_12_PORT;
+            pin = GPIO_12_PIN;
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            port = GPIO_13_PORT;
+            pin = GPIO_13_PIN;
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            port = GPIO_14_PORT;
+            pin = GPIO_14_PIN;
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            port = GPIO_15_PORT;
+            pin = GPIO_15_PIN;
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            port = GPIO_16_PORT;
+            pin = GPIO_16_PIN;
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            port = GPIO_17_PORT;
+            pin = GPIO_17_PIN;
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            port = GPIO_18_PORT;
+            pin = GPIO_18_PIN;
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            port = GPIO_19_PORT;
+            pin = GPIO_19_PIN;
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            port = GPIO_20_PORT;
+            pin = GPIO_20_PIN;
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            port = GPIO_21_PORT;
+            pin = GPIO_21_PIN;
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            port = GPIO_22_PORT;
+            pin = GPIO_22_PIN;
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            port = GPIO_23_PORT;
+            pin = GPIO_23_PIN;
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            port = GPIO_24_PORT;
+            pin = GPIO_24_PIN;
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            port = GPIO_25_PORT;
+            pin = GPIO_25_PIN;
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            port = GPIO_26_PORT;
+            pin = GPIO_26_PIN;
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            port = GPIO_27_PORT;
+            pin = GPIO_27_PIN;
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            port = GPIO_28_PORT;
+            pin = GPIO_28_PIN;
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            port = GPIO_29_PORT;
+            pin = GPIO_29_PIN;
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            port = GPIO_30_PORT;
+            pin = GPIO_30_PIN;
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            port = GPIO_31_PORT;
+            pin = GPIO_31_PIN;
+            break;
+#endif
+
+        default:
+            return;
+    }
+
+    /* Restore saved state */
+    port->PCR[pin] &= ~(PORT_PCR_IRQC_MASK);
+    port->PCR[pin] |= PORT_PCR_IRQC_MASK & config[dev].irqc;
+}
+
+void gpio_irq_disable(gpio_t dev)
+{
+    PORT_Type *port;
+    uint32_t pin = 0;
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            port = GPIO_0_PORT;
+            pin = GPIO_0_PIN;
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            port = GPIO_1_PORT;
+            pin = GPIO_1_PIN;
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            port = GPIO_2_PORT;
+            pin = GPIO_2_PIN;
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            port = GPIO_3_PORT;
+            pin = GPIO_3_PIN;
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            port = GPIO_4_PORT;
+            pin = GPIO_4_PIN;
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            port = GPIO_5_PORT;
+            pin = GPIO_5_PIN;
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            port = GPIO_6_PORT;
+            pin = GPIO_6_PIN;
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            port = GPIO_7_PORT;
+            pin = GPIO_7_PIN;
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            port = GPIO_8_PORT;
+            pin = GPIO_8_PIN;
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            port = GPIO_9_PORT;
+            pin = GPIO_9_PIN;
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            port = GPIO_10_PORT;
+            pin = GPIO_10_PIN;
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            port = GPIO_11_PORT;
+            pin = GPIO_11_PIN;
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            port = GPIO_12_PORT;
+            pin = GPIO_12_PIN;
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            port = GPIO_13_PORT;
+            pin = GPIO_13_PIN;
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            port = GPIO_14_PORT;
+            pin = GPIO_14_PIN;
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            port = GPIO_15_PORT;
+            pin = GPIO_15_PIN;
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            port = GPIO_16_PORT;
+            pin = GPIO_16_PIN;
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            port = GPIO_17_PORT;
+            pin = GPIO_17_PIN;
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            port = GPIO_18_PORT;
+            pin = GPIO_18_PIN;
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            port = GPIO_19_PORT;
+            pin = GPIO_19_PIN;
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            port = GPIO_20_PORT;
+            pin = GPIO_20_PIN;
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            port = GPIO_21_PORT;
+            pin = GPIO_21_PIN;
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            port = GPIO_22_PORT;
+            pin = GPIO_22_PIN;
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            port = GPIO_23_PORT;
+            pin = GPIO_23_PIN;
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            port = GPIO_24_PORT;
+            pin = GPIO_24_PIN;
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            port = GPIO_25_PORT;
+            pin = GPIO_25_PIN;
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            port = GPIO_26_PORT;
+            pin = GPIO_26_PIN;
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            port = GPIO_27_PORT;
+            pin = GPIO_27_PIN;
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            port = GPIO_28_PORT;
+            pin = GPIO_28_PIN;
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            port = GPIO_29_PORT;
+            pin = GPIO_29_PIN;
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            port = GPIO_30_PORT;
+            pin = GPIO_30_PIN;
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            port = GPIO_31_PORT;
+            pin = GPIO_31_PIN;
+            break;
+#endif
+
+        default:
+            return;
+    }
+
+    /* Save irqc state before disabling to allow enabling with the same trigger settings later. */
+    config[dev].irqc = PORT_PCR_IRQC_MASK & port->PCR[pin];
+    port->PCR[pin] &= ~(PORT_PCR_IRQC_MASK);
+}
+
+int gpio_read(gpio_t dev)
+{
+    GPIO_Type *gpio;
+    uint32_t pin = 0;
+
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            gpio = GPIO_0_DEV;
+            pin = GPIO_0_PIN;
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            gpio = GPIO_1_DEV;
+            pin = GPIO_1_PIN;
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            gpio = GPIO_2_DEV;
+            pin = GPIO_2_PIN;
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            gpio = GPIO_3_DEV;
+            pin = GPIO_3_PIN;
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            gpio = GPIO_4_DEV;
+            pin = GPIO_4_PIN;
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            gpio = GPIO_5_DEV;
+            pin = GPIO_5_PIN;
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            gpio = GPIO_6_DEV;
+            pin = GPIO_6_PIN;
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            gpio = GPIO_7_DEV;
+            pin = GPIO_7_PIN;
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            gpio = GPIO_8_DEV;
+            pin = GPIO_8_PIN;
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            gpio = GPIO_9_DEV;
+            pin = GPIO_9_PIN;
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            gpio = GPIO_10_DEV;
+            pin = GPIO_10_PIN;
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            gpio = GPIO_11_DEV;
+            pin = GPIO_11_PIN;
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            gpio = GPIO_12_DEV;
+            pin = GPIO_12_PIN;
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            gpio = GPIO_13_DEV;
+            pin = GPIO_13_PIN;
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            gpio = GPIO_14_DEV;
+            pin = GPIO_14_PIN;
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            gpio = GPIO_15_DEV;
+            pin = GPIO_15_PIN;
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            gpio = GPIO_16_DEV;
+            pin = GPIO_16_PIN;
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            gpio = GPIO_17_DEV;
+            pin = GPIO_17_PIN;
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            gpio = GPIO_18_DEV;
+            pin = GPIO_18_PIN;
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            gpio = GPIO_19_DEV;
+            pin = GPIO_19_PIN;
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            gpio = GPIO_20_DEV;
+            pin = GPIO_20_PIN;
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            gpio = GPIO_21_DEV;
+            pin = GPIO_21_PIN;
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            gpio = GPIO_22_DEV;
+            pin = GPIO_22_PIN;
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            gpio = GPIO_23_DEV;
+            pin = GPIO_23_PIN;
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            gpio = GPIO_24_DEV;
+            pin = GPIO_24_PIN;
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            gpio = GPIO_25_DEV;
+            pin = GPIO_25_PIN;
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            gpio = GPIO_26_DEV;
+            pin = GPIO_26_PIN;
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            gpio = GPIO_27_DEV;
+            pin = GPIO_27_PIN;
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            gpio = GPIO_28_DEV;
+            pin = GPIO_28_PIN;
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            gpio = GPIO_29_DEV;
+            pin = GPIO_29_PIN;
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            gpio = GPIO_30_DEV;
+            pin = GPIO_30_PIN;
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            gpio = GPIO_31_DEV;
+            pin = GPIO_31_PIN;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (gpio->PDDR & GPIO_PDDR_PDD(1 << pin)) {      /* if configured as output */
+        return gpio->PDOR & GPIO_PDOR_PDO(1 << pin); /* read output data register */
+    }
+    else {
+        return gpio->PDIR & GPIO_PDIR_PDI(1 << pin); /* else read input data register */
+    }
+}
+
+void gpio_set(gpio_t dev)
+{
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            GPIO_0_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_0_PIN);
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            GPIO_1_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_1_PIN);
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            GPIO_2_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_2_PIN);
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            GPIO_3_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_3_PIN);
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            GPIO_4_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_4_PIN);
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            GPIO_5_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_5_PIN);
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            GPIO_6_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_6_PIN);
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            GPIO_7_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_7_PIN);
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            GPIO_8_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_8_PIN);
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            GPIO_9_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_9_PIN);
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            GPIO_10_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_10_PIN);
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            GPIO_11_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_11_PIN);
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            GPIO_12_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_12_PIN);
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            GPIO_13_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_13_PIN);
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            GPIO_14_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_14_PIN);
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            GPIO_15_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_15_PIN);
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            GPIO_16_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_16_PIN);
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            GPIO_17_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_17_PIN);
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            GPIO_18_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_18_PIN);
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            GPIO_19_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_19_PIN);
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            GPIO_20_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_20_PIN);
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            GPIO_21_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_21_PIN);
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            GPIO_22_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_22_PIN);
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            GPIO_23_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_23_PIN);
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            GPIO_24_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_24_PIN);
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            GPIO_25_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_25_PIN);
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            GPIO_26_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_26_PIN);
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            GPIO_27_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_27_PIN);
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            GPIO_28_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_28_PIN);
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            GPIO_29_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_29_PIN);
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            GPIO_30_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_30_PIN);
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            GPIO_31_DEV->PSOR |= GPIO_PSOR_PTSO(1 << GPIO_31_PIN);
+            break;
+#endif
+    }
+}
+
+void gpio_clear(gpio_t dev)
+{
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            GPIO_0_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_0_PIN);
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            GPIO_1_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_1_PIN);
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            GPIO_2_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_2_PIN);
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            GPIO_3_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_3_PIN);
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            GPIO_4_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_4_PIN);
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            GPIO_5_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_5_PIN);
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            GPIO_6_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_6_PIN);
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            GPIO_7_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_7_PIN);
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            GPIO_8_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_8_PIN);
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            GPIO_9_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_9_PIN);
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            GPIO_10_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_10_PIN);
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            GPIO_11_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_11_PIN);
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            GPIO_12_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_12_PIN);
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            GPIO_13_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_13_PIN);
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            GPIO_14_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_14_PIN);
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            GPIO_15_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_15_PIN);
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            GPIO_16_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_16_PIN);
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            GPIO_17_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_17_PIN);
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            GPIO_18_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_18_PIN);
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            GPIO_19_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_19_PIN);
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            GPIO_20_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_20_PIN);
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            GPIO_21_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_21_PIN);
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            GPIO_22_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_22_PIN);
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            GPIO_23_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_23_PIN);
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            GPIO_24_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_24_PIN);
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            GPIO_25_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_25_PIN);
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            GPIO_26_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_26_PIN);
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            GPIO_27_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_27_PIN);
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            GPIO_28_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_28_PIN);
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            GPIO_29_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_29_PIN);
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            GPIO_30_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_30_PIN);
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            GPIO_31_DEV->PCOR |= GPIO_PCOR_PTCO(1 << GPIO_31_PIN);
+            break;
+#endif
+    }
+}
+
+void gpio_toggle(gpio_t dev)
+{
+    switch (dev) {
+#if GPIO_0_EN
+
+        case GPIO_0:
+            GPIO_0_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_0_PIN);
+            break;
+#endif
+#if GPIO_1_EN
+
+        case GPIO_1:
+            GPIO_1_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_1_PIN);
+            break;
+#endif
+#if GPIO_2_EN
+
+        case GPIO_2:
+            GPIO_2_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_2_PIN);
+            break;
+#endif
+#if GPIO_3_EN
+
+        case GPIO_3:
+            GPIO_3_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_3_PIN);
+            break;
+#endif
+#if GPIO_4_EN
+
+        case GPIO_4:
+            GPIO_4_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_4_PIN);
+            break;
+#endif
+#if GPIO_5_EN
+
+        case GPIO_5:
+            GPIO_5_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_5_PIN);
+            break;
+#endif
+#if GPIO_6_EN
+
+        case GPIO_6:
+            GPIO_6_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_6_PIN);
+            break;
+#endif
+#if GPIO_7_EN
+
+        case GPIO_7:
+            GPIO_7_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_7_PIN);
+            break;
+#endif
+#if GPIO_8_EN
+
+        case GPIO_8:
+            GPIO_8_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_8_PIN);
+            break;
+#endif
+#if GPIO_9_EN
+
+        case GPIO_9:
+            GPIO_9_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_9_PIN);
+            break;
+#endif
+#if GPIO_10_EN
+
+        case GPIO_10:
+            GPIO_10_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_10_PIN);
+            break;
+#endif
+#if GPIO_11_EN
+
+        case GPIO_11:
+            GPIO_11_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_11_PIN);
+            break;
+#endif
+#if GPIO_12_EN
+
+        case GPIO_12:
+            GPIO_12_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_12_PIN);
+            break;
+#endif
+#if GPIO_13_EN
+
+        case GPIO_13:
+            GPIO_13_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_13_PIN);
+            break;
+#endif
+#if GPIO_14_EN
+
+        case GPIO_14:
+            GPIO_14_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_14_PIN);
+            break;
+#endif
+#if GPIO_15_EN
+
+        case GPIO_15:
+            GPIO_15_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_15_PIN);
+            break;
+#endif
+#if GPIO_16_EN
+
+        case GPIO_16:
+            GPIO_16_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_16_PIN);
+            break;
+#endif
+#if GPIO_17_EN
+
+        case GPIO_17:
+            GPIO_17_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_17_PIN);
+            break;
+#endif
+#if GPIO_18_EN
+
+        case GPIO_18:
+            GPIO_18_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_18_PIN);
+            break;
+#endif
+#if GPIO_19_EN
+
+        case GPIO_19:
+            GPIO_19_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_19_PIN);
+            break;
+#endif
+#if GPIO_20_EN
+
+        case GPIO_20:
+            GPIO_20_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_20_PIN);
+            break;
+#endif
+#if GPIO_21_EN
+
+        case GPIO_21:
+            GPIO_21_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_21_PIN);
+            break;
+#endif
+#if GPIO_22_EN
+
+        case GPIO_22:
+            GPIO_22_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_22_PIN);
+            break;
+#endif
+#if GPIO_23_EN
+
+        case GPIO_23:
+            GPIO_23_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_23_PIN);
+            break;
+#endif
+#if GPIO_24_EN
+
+        case GPIO_24:
+            GPIO_24_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_24_PIN);
+            break;
+#endif
+#if GPIO_25_EN
+
+        case GPIO_25:
+            GPIO_25_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_25_PIN);
+            break;
+#endif
+#if GPIO_26_EN
+
+        case GPIO_26:
+            GPIO_26_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_26_PIN);
+            break;
+#endif
+#if GPIO_27_EN
+
+        case GPIO_27:
+            GPIO_27_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_27_PIN);
+            break;
+#endif
+#if GPIO_28_EN
+
+        case GPIO_28:
+            GPIO_28_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_28_PIN);
+            break;
+#endif
+#if GPIO_29_EN
+
+        case GPIO_29:
+            GPIO_29_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_29_PIN);
+            break;
+#endif
+#if GPIO_30_EN
+
+        case GPIO_30:
+            GPIO_30_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_30_PIN);
+            break;
+#endif
+#if GPIO_31_EN
+
+        case GPIO_31:
+            GPIO_31_DEV->PTOR |= GPIO_PTOR_PTTO(1 << GPIO_31_PIN);
+            break;
+#endif
+    }
+}
+
+void gpio_write(gpio_t dev, int value)
+{
+    if (value) {
+        gpio_set(dev);
+    }
+    else {
+        gpio_clear(dev);
+    }
+}
+
+static inline void irq_handler(gpio_t dev)
+{
+    config[dev].cb(config[dev].arg);
+
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+}
+
+
+/* the following interrupt handlers are quite ugly, the preprocessor is used to
+ * insert only the relevant checks in each isr, however, in the source all of
+ * the ISRs contain all GPIO checks...
+ */
+#define GPIO_ISR_TEMPLATE(gpio) \
+    if (gpio##_PORT->ISFR & PORT_ISFR_ISF(1 << gpio##_PIN)) { \
+        irq_handler(gpio); \
+        /* clear status bit by writing a 1 to it */ \
+        gpio##_PORT->ISFR = PORT_ISFR_ISF(1 << gpio##_PIN); \
+    }
+
+/* Generate the below part with: (in bash or zsh)
+for p in $(seq 8 | tr 123456789 abcdefghi); do echo -n "
+#if PORT$(echo $p | tr '[:lower:]' '[:upper:]')_BASE
+void ISR_PORT_${p}(void)
+{
+"; for f in $(seq 0 31); do echo -n "
+#if GPIO_${f}_EN && (GPIO_${f}_PORT_BASE == PORT$(echo $p | tr '[:lower:]' '[:upper:]')_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_${f})
+#endif
+"; done;
+echo -n "
+}
+#endif // PORT$(echo $p | tr '[:lower:]' '[:upper:]')_BASE
+"; done > gpio-isr.c
+*/
+
+/* Script generated code below. */
+/* -------------------------------------------------------------------------- */
+
+#if PORTA_BASE
+void ISR_PORT_A(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTA_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTA_BASE */
+
+#if PORTB_BASE
+void ISR_PORT_B(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTB_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTB_BASE */
+
+#if PORTC_BASE
+void ISR_PORT_C(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTC_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTC_BASE */
+
+#if PORTD_BASE
+void ISR_PORT_D(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTD_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTD_BASE */
+
+#if PORTE_BASE
+void ISR_PORT_E(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTE_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTE_BASE */
+
+#if PORTF_BASE
+void ISR_PORT_F(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTF_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTF_BASE */
+
+#if PORTG_BASE
+void ISR_PORT_G(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTG_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTG_BASE */
+
+#if PORTH_BASE
+void ISR_PORT_H(void)
+{
+
+#if GPIO_0_EN && (GPIO_0_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_0)
+#endif
+
+#if GPIO_1_EN && (GPIO_1_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_1)
+#endif
+
+#if GPIO_2_EN && (GPIO_2_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_2)
+#endif
+
+#if GPIO_3_EN && (GPIO_3_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_3)
+#endif
+
+#if GPIO_4_EN && (GPIO_4_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_4)
+#endif
+
+#if GPIO_5_EN && (GPIO_5_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_5)
+#endif
+
+#if GPIO_6_EN && (GPIO_6_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_6)
+#endif
+
+#if GPIO_7_EN && (GPIO_7_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_7)
+#endif
+
+#if GPIO_8_EN && (GPIO_8_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_8)
+#endif
+
+#if GPIO_9_EN && (GPIO_9_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_9)
+#endif
+
+#if GPIO_10_EN && (GPIO_10_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_10)
+#endif
+
+#if GPIO_11_EN && (GPIO_11_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_11)
+#endif
+
+#if GPIO_12_EN && (GPIO_12_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_12)
+#endif
+
+#if GPIO_13_EN && (GPIO_13_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_13)
+#endif
+
+#if GPIO_14_EN && (GPIO_14_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_14)
+#endif
+
+#if GPIO_15_EN && (GPIO_15_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_15)
+#endif
+
+#if GPIO_16_EN && (GPIO_16_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_16)
+#endif
+
+#if GPIO_17_EN && (GPIO_17_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_17)
+#endif
+
+#if GPIO_18_EN && (GPIO_18_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_18)
+#endif
+
+#if GPIO_19_EN && (GPIO_19_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_19)
+#endif
+
+#if GPIO_20_EN && (GPIO_20_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_20)
+#endif
+
+#if GPIO_21_EN && (GPIO_21_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_21)
+#endif
+
+#if GPIO_22_EN && (GPIO_22_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_22)
+#endif
+
+#if GPIO_23_EN && (GPIO_23_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_23)
+#endif
+
+#if GPIO_24_EN && (GPIO_24_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_24)
+#endif
+
+#if GPIO_25_EN && (GPIO_25_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_25)
+#endif
+
+#if GPIO_26_EN && (GPIO_26_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_26)
+#endif
+
+#if GPIO_27_EN && (GPIO_27_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_27)
+#endif
+
+#if GPIO_28_EN && (GPIO_28_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_28)
+#endif
+
+#if GPIO_29_EN && (GPIO_29_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_29)
+#endif
+
+#if GPIO_30_EN && (GPIO_30_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_30)
+#endif
+
+#if GPIO_31_EN && (GPIO_31_PORT_BASE == PORTH_BASE)
+    GPIO_ISR_TEMPLATE(GPIO_31)
+#endif
+
+}
+#endif /* PORTH_BASE */
+
+#endif /* GPIO_NUMOF */
diff --git a/cpu/kinetis_common/hwtimer_arch.c b/cpu/kinetis_common/hwtimer_arch.c
new file mode 100644
index 0000000000..559970a491
--- /dev/null
+++ b/cpu/kinetis_common/hwtimer_arch.c
@@ -0,0 +1,223 @@
+/*
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_hwtimer
+ * @{
+ *
+ * @file
+ * @brief       Implementation of the kernels hwtimer interface.
+ *              hwtimer uses Freescale Low Power Timer lptmr0.
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include "arch/hwtimer_arch.h"
+#include "hwtimer_cpu.h"
+#include "cpu-conf.h"
+#include "thread.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+#define LPTMR_MAXTICKS            (0x0000FFFF)
+
+#ifndef LPTIMER_CNR_NEEDS_LATCHING
+#warning LPTIMER_CNR_NEEDS_LATCHING is not defined in cpu-conf.h! Defaulting to 1
+#define LPTIMER_CNR_NEEDS_LATCHING 1
+#endif
+
+typedef struct {
+    uint32_t counter32b;
+    uint32_t cmr32b;
+    uint32_t diff;
+} hwtimer_stimer32b_t;
+
+static hwtimer_stimer32b_t stimer;
+
+/**
+ * @brief Reference to the hwtimer callback
+ */
+void (*timeout_handler)(int);
+
+inline static uint32_t lptmr_get_cnr(void)
+{
+#if LPTIMER_CNR_NEEDS_LATCHING
+    /* Write some garbage to CNR to latch the current value */
+    LPTIMER_DEV->CNR = 42;
+    return (uint32_t)LPTIMER_DEV->CNR;
+#else
+    /* The early revisions of the Kinetis CPUs do not need latching of the CNR
+     * register. However, this may lead to corrupt values, we read it twice to
+     * ensure that we got a valid value */
+    int i;
+    uint32_t tmp;
+    uint32_t cnr = LPTIMER_DEV->CNR;
+
+    /* you get three retries */
+    for (i = 0; i < 3; ++i) {
+        tmp = LPTIMER_DEV->CNR;
+
+        if (tmp == cnr) {
+            return cnr;
+        }
+
+        cnr = tmp;
+    }
+
+#endif
+}
+
+inline static void hwtimer_start(void)
+{
+    LPTIMER_DEV->CSR |= LPTMR_CSR_TEN_MASK;
+}
+
+inline static void hwtimer_stop(void)
+{
+    LPTIMER_DEV->CSR &= ~LPTMR_CSR_TEN_MASK;
+}
+
+void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu)
+{
+    timeout_handler = handler;
+
+    /* unlock LPTIMER_DEV */
+    LPTIMER_CLKEN();
+    /* set lptmr's IRQ priority */
+    NVIC_SetPriority(LPTIMER_IRQ_CHAN, LPTIMER_IRQ_PRIO);
+    /* reset lptmr */
+    LPTIMER_DEV->CSR = 0;
+
+    switch (LPTIMER_CLKSRC) {
+        case LPTIMER_CLKSRC_MCGIRCLK:
+            /* Select MCGIRCLK as clock source */
+            LPTIMER_DEV->PSR = LPTMR_PSR_PRESCALE(LPTIMER_CLK_PRESCALE) | LPTMR_PSR_PCS(0);
+            break;
+
+        case LPTIMER_CLKSRC_OSCERCLK:
+            /* Select OSCERCLK(4 MHz) as clock source */
+            LPTIMER_DEV->PSR = LPTMR_PSR_PRESCALE(LPTIMER_CLK_PRESCALE) | LPTMR_PSR_PCS(3);
+            break;
+
+        case LPTIMER_CLKSRC_ERCLK32K:
+            /* Select rtc oscillator output as clock source for ERCLK32K, */
+            /* it needs functioning RTC module and driver. */
+            SIM->SOPT1 &= ~(SIM_SOPT1_OSC32KSEL_MASK);
+            SIM->SOPT1 |= SIM_SOPT1_OSC32KSEL(2);
+            /* select ERCLK32K as clock source for lptmr0 */
+            LPTIMER_DEV->PSR = LPTMR_PSR_PBYP_MASK | LPTMR_PSR_PCS(2);
+            break;
+
+        case LPTIMER_CLKSRC_LPO:
+        default:
+            /* select LPO as clock source (1 kHz)*/
+            LPTIMER_DEV->PSR = LPTMR_PSR_PBYP_MASK | LPTMR_PSR_PCS(1);
+    }
+
+    LPTIMER_DEV->CMR = (uint16_t)(LPTMR_MAXTICKS);
+    /* enable lptrm interrupt */
+    LPTIMER_DEV->CSR = LPTMR_CSR_TIE_MASK;
+
+    stimer.counter32b = 0;
+    stimer.cmr32b = 0;
+    stimer.diff = 0;
+
+    hwtimer_arch_enable_interrupt();
+    hwtimer_start();
+}
+
+void hwtimer_arch_enable_interrupt(void)
+{
+    NVIC_EnableIRQ(LPTIMER_IRQ_CHAN);
+}
+
+void hwtimer_arch_disable_interrupt(void)
+{
+    NVIC_DisableIRQ(LPTIMER_IRQ_CHAN);
+}
+
+void hwtimer_arch_set(unsigned long offset, short timer)
+{
+    (void)timer;
+    stimer.counter32b += lptmr_get_cnr();
+    hwtimer_stop();
+
+    stimer.cmr32b = stimer.counter32b + offset;
+    stimer.diff = offset;
+
+    if (stimer.diff > LPTMR_MAXTICKS) {
+        stimer.diff = LPTMR_MAXTICKS;
+    }
+
+    DEBUG("cntr: %lu, cmr: %lu, diff: %lu\n", stimer.counter32b, stimer.cmr32b, stimer.diff);
+
+    LPTIMER_DEV->CMR = (uint16_t)(stimer.diff);
+    hwtimer_start();
+}
+
+void hwtimer_arch_set_absolute(unsigned long value, short timer)
+{
+    (void)timer;
+    stimer.counter32b += lptmr_get_cnr();
+    hwtimer_stop();
+
+    stimer.cmr32b = value;
+    stimer.diff = stimer.cmr32b - stimer.counter32b;
+
+    if (stimer.diff > LPTMR_MAXTICKS) {
+        stimer.diff = LPTMR_MAXTICKS;
+    }
+
+    DEBUG("cntr: %lu, cmr: %lu, diff: %lu\n", stimer.counter32b, stimer.cmr32b, stimer.diff);
+
+    LPTIMER_DEV->CMR = (uint16_t)(stimer.diff);
+    hwtimer_start();
+}
+
+void hwtimer_arch_unset(short timer)
+{
+    stimer.counter32b += lptmr_get_cnr();
+    hwtimer_stop();
+    stimer.diff = 0;
+    stimer.cmr32b = 0;
+    LPTIMER_DEV->CMR = (uint16_t)(LPTMR_MAXTICKS);
+    hwtimer_start();
+
+}
+
+unsigned long hwtimer_arch_now(void)
+{
+    return (unsigned int)((lptmr_get_cnr() + stimer.counter32b));
+}
+
+void isr_lptmr0(void)
+{
+    stimer.counter32b += (uint32_t)LPTIMER_DEV->CMR;
+    /* clear compare flag (w1c bit) */
+    LPTIMER_DEV->CSR |= LPTMR_CSR_TCF_MASK;
+
+    if (stimer.diff) {
+        if (stimer.cmr32b > stimer.counter32b) {
+            hwtimer_arch_set_absolute(stimer.cmr32b, 0);
+        }
+        else {
+            stimer.diff = 0;
+            timeout_handler((short)0);
+        }
+    }
+    else {
+        hwtimer_arch_unset(0);
+    }
+
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+}
diff --git a/cpu/kinetis_common/i2c.c b/cpu/kinetis_common/i2c.c
new file mode 100644
index 0000000000..82ab7d9f26
--- /dev/null
+++ b/cpu/kinetis_common/i2c.c
@@ -0,0 +1,436 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_i2c
+ *
+ * @note        This driver only implements the 7-bit addressing master mode.
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level I2C driver implementation
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include <stdint.h>
+
+#include "cpu.h"
+#include "irq.h"
+#include "mutex.h"
+#include "periph_conf.h"
+#include "periph/i2c.h"
+
+#define ENABLE_DEBUG    (0)
+#include "debug.h"
+
+/* guard file in case no I2C device is defined */
+#if I2C_NUMOF
+
+/**
+ * @brief Array holding one pre-initialized mutex for each I2C device
+ */
+static mutex_t locks[] =  {
+#if I2C_0_EN
+    [I2C_0] = MUTEX_INIT,
+#endif
+#if I2C_1_EN
+    [I2C_1] = MUTEX_INIT,
+#endif
+#if I2C_2_EN
+    [I2C_2] = MUTEX_INIT
+#endif
+#if I2C_3_EN
+    [I2C_3] = MUTEX_INIT
+#endif
+};
+
+int i2c_acquire(i2c_t dev)
+{
+    if (dev >= I2C_NUMOF) {
+        return -1;
+    }
+    mutex_lock(&locks[dev]);
+    return 0;
+}
+
+int i2c_release(i2c_t dev)
+{
+    if (dev >= I2C_NUMOF) {
+        return -1;
+    }
+    mutex_unlock(&locks[dev]);
+    return 0;
+}
+
+int i2c_init_master(i2c_t dev, i2c_speed_t speed)
+{
+    I2C_Type *i2c;
+    PORT_Type *i2c_port;
+    int pin_scl = 0;
+    int pin_sda = 0;
+
+    /* TODO: read speed configuration */
+    switch (speed) {
+        case I2C_SPEED_NORMAL:
+            break;
+
+        case I2C_SPEED_FAST:
+            break;
+
+        default:
+            return -2;
+    }
+
+    /* read static device configuration */
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            i2c = I2C_0_DEV;
+            i2c_port = I2C_0_PORT;
+            pin_scl = I2C_0_SCL_PIN;
+            pin_sda = I2C_0_SDA_PIN;
+            I2C_0_CLKEN();
+            I2C_0_PORT_CLKEN();
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* configure pins, alternate output */
+    i2c_port->PCR[pin_scl] = I2C_0_PORT_CFG;
+    i2c_port->PCR[pin_sda] = I2C_0_PORT_CFG;
+
+    /* 
+    * TODO: Add baud rate selection function
+    * See the Chapter "I2C divider and hold values":
+    *     Kinetis K60 Reference Manual, section 51.4.1.10, Table 51-41. 
+    *     Kinetis MKW2x  Reference Manual, section 52.4.1.10, Table 52-41. 
+    *
+    * baud rate = I2C_module_clock / (mul × ICR)
+    *
+    * The assignment below will set baud rate to I2C_module_clock / (240 x 2).
+    */
+    i2c->F = I2C_F_MULT(1) | I2C_F_ICR(0x1f);
+
+    /* enable i2c-module and interrupt */
+    i2c->C1 = I2C_C1_IICEN_MASK | I2C_C1_IICIE_MASK | I2C_C1_TXAK_MASK;
+    i2c->C2 = 0;
+
+    return 0;
+}
+
+int i2c_init_slave(i2c_t dev, uint8_t address)
+{
+    /* TODO: implement slave mode */
+    return -1;
+}
+
+static inline int _i2c_start(I2C_Type *dev, uint8_t address, uint8_t rw_flag)
+{
+    /* bus free ? */
+    if (dev->S & I2C_S_BUSY_MASK) {
+        return -1;
+    }
+
+    dev->S = I2C_S_IICIF_MASK;
+
+    dev->C1 = I2C_C1_IICEN_MASK | I2C_C1_MST_MASK | I2C_C1_TX_MASK;
+    dev->D = address << 1 | (rw_flag & 1);
+
+    /* wait for bus-busy to be set */
+    while (!(dev->S & I2C_S_BUSY_MASK));
+
+    /* wait for address transfer to complete */
+    while (!(dev->S & I2C_S_IICIF_MASK));
+
+    dev->S = I2C_S_IICIF_MASK;
+
+    /* check for receive acknowledge */
+    if (dev->S & I2C_S_RXAK_MASK) {
+        return -1;
+    }
+
+    return 0;
+}
+
+static inline int _i2c_restart(I2C_Type *dev, uint8_t address, uint8_t rw_flag)
+{
+    /* put master in rx mode and repeat start */
+    dev->C1 |= I2C_C1_RSTA_MASK;
+    dev->D = address << 1 | (rw_flag & 1);
+
+    /* wait for address transfer to complete */
+    while (!(dev->S & I2C_S_IICIF_MASK));
+
+    dev->S = I2C_S_IICIF_MASK;
+
+    /* check for receive acknowledge */
+    if (dev->S & I2C_S_RXAK_MASK) {
+        return -1;
+    }
+
+    return 0;
+}
+
+static inline int _i2c_receive(I2C_Type *dev, uint8_t *data, int length)
+{
+    int n = 0;
+
+    /* set receive mode */
+    dev->C1 = I2C_C1_IICEN_MASK | I2C_C1_MST_MASK;
+
+    if (length == 1) {
+        /* no ack signal */
+        dev->C1 |= I2C_C1_TXAK_MASK;
+    }
+
+    /* dummy read */
+    dev->D;
+
+    while (length > 0) {
+        while (!(dev->S & I2C_S_IICIF_MASK));
+
+        dev->S = I2C_S_IICIF_MASK;
+
+        if (length == 2) {
+            /* no ack signal is sent on the following receiving byte */
+            dev->C1 |= I2C_C1_TXAK_MASK;
+        }
+
+        if (length == 1) {
+            /* generate stop */
+            dev->C1 &= ~I2C_C1_MST_MASK;
+        }
+
+        data[n] = (char)dev->D;
+        length--;
+        n++;
+    }
+
+    return n;
+}
+
+static inline int _i2c_transmit(I2C_Type *dev, uint8_t *data, int length)
+{
+    int n = 0;
+
+    while (length > 0) {
+        dev->D = data[n];
+
+        while (!(dev->S & I2C_S_IICIF_MASK));
+
+        dev->S = I2C_S_IICIF_MASK;
+
+        if (dev->S & I2C_S_RXAK_MASK) {
+            return n;
+        }
+
+        n++;
+        length--;
+    }
+
+    return n;
+}
+
+static inline void _i2c_stop(I2C_Type *dev)
+{
+    /* put bus in idle state */
+    dev->C1 = I2C_C1_IICEN_MASK;
+
+    /* wait for bus idle */
+    while (dev->S & I2C_S_BUSY_MASK);
+}
+
+
+int i2c_read_byte(i2c_t dev, uint8_t address, char *data)
+{
+    return i2c_read_bytes(dev, address, data, 1);
+}
+
+int i2c_read_bytes(i2c_t dev, uint8_t address, char *data, int length)
+{
+    I2C_Type *i2c;
+    int n = 0;
+
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            i2c = I2C_0_DEV;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (_i2c_start(i2c, address, I2C_FLAG_READ)) {
+        _i2c_stop(i2c);
+        return -1;
+    }
+
+    n = _i2c_receive(i2c, (uint8_t *)data, length);
+    _i2c_stop(i2c);
+
+    return n;
+}
+
+int i2c_write_byte(i2c_t dev, uint8_t address, char data)
+{
+    return i2c_write_bytes(dev, address, &data, 1);
+}
+
+int i2c_write_bytes(i2c_t dev, uint8_t address, char *data, int length)
+{
+    I2C_Type *i2c;
+    int n = 0;
+
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            i2c = I2C_0_DEV;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (_i2c_start(i2c, address, I2C_FLAG_WRITE)) {
+        _i2c_stop(i2c);
+        return -1;
+    }
+
+    n = _i2c_transmit(i2c, (uint8_t *)data, length);
+    _i2c_stop(i2c);
+
+    return n;
+}
+
+int i2c_read_reg(i2c_t dev, uint8_t address, uint8_t reg, char *data)
+{
+    return i2c_read_regs(dev, address, reg, data, 1);
+
+}
+
+int i2c_read_regs(i2c_t dev, uint8_t address, uint8_t reg, char *data, int length)
+{
+    I2C_Type *i2c;
+    int n = 0;
+
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            i2c = I2C_0_DEV;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (_i2c_start(i2c, address, I2C_FLAG_WRITE)) {
+        _i2c_stop(i2c);
+        return -1;
+    }
+
+    /* send reg */
+    n = _i2c_transmit(i2c, &reg, 1);
+
+    if (!n) {
+        _i2c_stop(i2c);
+        return n;
+    }
+
+    if (_i2c_restart(i2c, address, I2C_FLAG_READ)) {
+        _i2c_stop(i2c);
+        return -1;
+    }
+
+    n = _i2c_receive(i2c, (uint8_t *)data, length);
+    _i2c_stop(i2c);
+
+    return n;
+}
+
+
+int i2c_write_reg(i2c_t dev, uint8_t address, uint8_t reg, char data)
+{
+    return i2c_write_regs(dev, address, reg, &data, 1);
+}
+
+int i2c_write_regs(i2c_t dev, uint8_t address, uint8_t reg, char *data, int length)
+{
+    I2C_Type *i2c;
+    int n = 0;
+
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            i2c = I2C_0_DEV;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (_i2c_start(i2c, address, I2C_FLAG_WRITE)) {
+        _i2c_stop(i2c);
+        return -1;
+    }
+
+    n = _i2c_transmit(i2c, &reg, 1);
+
+    if (!n) {
+        _i2c_stop(i2c);
+        return n;
+    }
+
+    n = _i2c_transmit(i2c, (uint8_t *)data, length);
+    _i2c_stop(i2c);
+
+    return n;
+}
+
+void i2c_poweron(i2c_t dev)
+{
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            I2C_0_CLKEN();
+            break;
+#endif
+    }
+}
+
+void i2c_poweroff(i2c_t dev)
+{
+    switch (dev) {
+#if I2C_0_EN
+
+        case I2C_0:
+            I2C_0_CLKDIS();
+            break;
+#endif
+    }
+}
+
+#endif /* I2C_NUMOF */
diff --git a/cpu/kinetis_common/include/hwtimer_cpu.h b/cpu/kinetis_common/include/hwtimer_cpu.h
new file mode 100644
index 0000000000..76285a140d
--- /dev/null
+++ b/cpu/kinetis_common/include/hwtimer_cpu.h
@@ -0,0 +1,113 @@
+/*
+ * Copyright (C) 2015 PHYTEC Messtechnik GmbH
+ *
+ * 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    cpu_kinetis_common_hwtimer Kinetis hwtimer
+ * @ingroup     cpu_kinetis_common
+ * @brief       Driver uses Freescale Low Power Timer lptmr0.
+ *              There are four clock sources available:
+ *
+ *                  LPTIMER_CLKSRC_MCGIRCLK - slow or fast internal reference clock
+ *                  LPTIMER_CLKSRC_LPO - PMC 1kHz output
+ *                  LPTIMER_CLKSRC_ERCLK32K - OSC32KCLK or the RTC clock
+ *                  LPTIMER_CLKSRC_OSCERCLK - system oscillator output
+ *
+ *              Tested clock sources:
+ *
+ *                  LPO - 1kHz
+ *                  RTC - 32768Hz
+ *
+ *              Possibly, additional settings in System Integration Module are necessary.
+ *              Please consult the Reference Manual of your MCU for proper clock settings.
+ *
+ *              ### LPTMR Configuration Example (for cpu-conf.h) ###
+ *
+ *                  #define LPTIMER_CLKSRC                   LPTIMER_CLKSRC_LPO
+ *                  #define LPTIMER_CLKEN()                  (SIM->SCGC5 |= SIM_SCGC5_LPTMR_MASK)
+ *                  #define LPTIMER_CLKDIS()                 (SIM->SCGC5 &= ~SIM_SCGC5_PTMR_MASK)
+ *                  #define LPTIMER_CNR_NEEDS_LATCHING       1
+ *
+ *              Optional settings:
+ *
+ *                  #define LPTIMER_DEV                      LPTMR0
+ *                  #define LPTIMER_IRQ_PRIO                 1
+ *                  #define LPTIMER_IRQ_CHAN                 LPTMR0_IRQn
+ * @{
+
+ * @file
+ * @brief       Interface definition for the Kinetis hwtimer driver.
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ */
+
+#ifndef __HWTIMER_CPU_H
+#define __HWTIMER_CPU_H
+
+#include "cpu-conf.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**
+ * @name Clock settings for the lptmr timer
+ */
+#define LPTIMER_CLKSRC_MCGIRCLK          0    /**< internal reference clock (4MHz) */
+#define LPTIMER_CLKSRC_LPO               1    /**< PMC 1kHz output */
+#define LPTIMER_CLKSRC_ERCLK32K          2    /**< RTC clock 32768Hz */
+#define LPTIMER_CLKSRC_OSCERCLK          3    /**< system oscillator output, clock from RF-Part */
+
+#ifndef LPTIMER_CLKSRC
+#define LPTIMER_CLKSRC                   LPTIMER_CLKSRC_LPO    /**< default clock source */
+#endif
+
+#if (LPTIMER_CLKSRC == LPTIMER_CLKSRC_MCGIRCLK)
+#define LPTIMER_CLK_PRESCALE    1
+#define LPTIMER_SPEED           1000000
+#elif (LPTIMER_CLKSRC == LPTIMER_CLKSRC_OSCERCLK)
+#define LPTIMER_CLK_PRESCALE    1
+#define LPTIMER_SPEED           1000000
+#elif (LPTIMER_CLKSRC == LPTIMER_CLKSRC_ERCLK32K)
+#define LPTIMER_CLK_PRESCALE    0
+#define LPTIMER_SPEED           32768
+#else
+#define LPTIMER_CLK_PRESCALE    0
+#define LPTIMER_SPEED           1000
+#endif
+
+#ifndef LPTIMER_DEV
+/** default Low Power Timer device */
+#define LPTIMER_DEV             LPTMR0
+#endif
+
+#ifndef LPTIMER_IRQ_PRIO
+/** IRQ priority for hwtimer interrupts */
+#define LPTIMER_IRQ_PRIO        1
+#endif
+
+#ifndef LPTIMER_IRQ_CHAN
+/** IRQ channel for hwtimer interrupts */
+#define LPTIMER_IRQ_CHAN        LPTMR0_IRQn
+#endif
+
+/**
+ * @name Hardware timer configuration
+ * @{
+ */
+#define HWTIMER_MAXTIMERS    1                /**< the CPU implementation supports 1 HW timer */
+#define HWTIMER_MAXTICKS     (0xFFFFFFFF)     /**< simulating 32-bit timer behavior */
+#define HWTIMER_SPEED        LPTIMER_SPEED    /**< speed depends on clock source and prescale */
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __HWTIMER_CPU_H */
+/** @} */
diff --git a/cpu/kinetis_common/include/mcg.h b/cpu/kinetis_common/include/mcg.h
new file mode 100644
index 0000000000..1668c3203e
--- /dev/null
+++ b/cpu/kinetis_common/include/mcg.h
@@ -0,0 +1,137 @@
+/*
+ * Copyright (C) 2015 PHYTEC Messtechnik GmbH
+ *
+ * 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    cpu_kinetis_common_mcg Kinetis MCG
+ * @ingroup     cpu_kinetis_common
+ * @brief       Implementation of the Kinetis Multipurpose Clock Generator
+ *              (MCG) driver.
+ *              Please add mcg.h in cpu conf.h
+ *              and MCG configuration to periph_conf.h
+ *
+ *              MCG neighbor modes matrix:
+ *
+ *                x  | FEI | FEE | FBI | FBE | BLPI | BLPE | PBE | PEE
+ *              :---:|:---:|:---:|:---:|:---:|:----:|:----:|:---:|:---:
+ *              PEE  |  0  |  0  |  0  |  0  |  0   |  0   |  1  |  0
+ *              PBE  |  0  |  0  |  0  |  1  |  0   |  1   |  0  |  1
+ *              BLPE |  0  |  0  |  0  |  1  |  0   |  0   |  1  |  0
+ *              BLPI |  0  |  0  |  1  |  0  |  0   |  0   |  0  |  0
+ *              FBE  |  1  |  1  |  1  |  0  |  0   |  1   |  1  |  0
+ *              FBI  |  1  |  1  |  0  |  1  |  1   |  0   |  0  |  0
+ *              FEE  |  1  |  0  |  1  |  1  |  0   |  0   |  0  |  0
+ *              FEI  |  1  |  1  |  1  |  1  |  0   |  0   |  0  |  0
+ *
+ *              Each neighbor mode can be selected directly.
+ *              Further, the paths between the following modes are defined:
+ *              -  FEI -> PEE
+ *              -  BLPE -> PEE
+ *              -  PEE -> BLPE
+ *              -  FEE -> BLPE
+ *              -  FEE -> BLPI
+ *              -  BLPE -> FEE
+ *              -  BLPI -> FEE
+ *
+ *              ### MCG Configuration Examples (for periph_conf.h) ###
+ *
+ *              Example for FEI Mode (MCGOUTCLK = 20MHz ... 25MHz):
+ *
+ *                  #define KINETIS_MCG_USE_ERC               0
+ *                  #define KINETIS_MCG_DCO_RANGE             (24000000U)
+ *
+ *
+ *              Example for FEE Mode, 32768Hz Crystal,
+ *              (MCGOUTCLK = 24MHz):
+ *
+ *                  #define KINETIS_MCG_USE_ERC               1
+ *                  #define KINETIS_MCG_USE_PLL               0
+ *                  #define KINETIS_MCG_DCO_RANGE             (24000000U)
+ *                  #define KINETIS_MCG_ERC_OSCILLATOR        1
+ *                  #define KINETIS_MCG_ERC_FRDIV             0
+ *                  #define KINETIS_MCG_ERC_RANGE             0
+ *                  #define KINETIS_MCG_ERC_FREQ              (32768U)
+ *
+ *
+ *              Example for FEE Mode, external 4MHz reference
+ *              (\f$MCGOUTCLK
+ *              = \frac{ERC_{\mathrm{freq}}\cdot FFL_{\mathrm{Factor}}}{FRDIV}
+ *              = \frac{4\,\mathrm{MHz}\cdot 732}{128} = 22.875\,\mathrm{MHz}\f$):
+ *
+ *                  #define KINETIS_MCG_USE_ERC               1
+ *                  #define KINETIS_MCG_USE_PLL               0
+ *                  #define KINETIS_MCG_DCO_RANGE             (24000000U)
+ *                  #define KINETIS_MCG_ERC_OSCILLATOR        0
+ *                  #define KINETIS_MCG_ERC_FRDIV             2
+ *                  #define KINETIS_MCG_ERC_RANGE             1
+ *                  #define KINETIS_MCG_ERC_FREQ              (4000000U)
+ *
+ *              Example for PEE Mode, external 4MHz reference
+ *              (\f$MCGOUTCLK
+ *              = \frac{ERC_{\mathrm{freq}}\cdot VDIV0}{PRDIV}
+ *              = \frac{4\,\mathrm{MHz}\cdot 24}{2} = 48\,\mathrm{MHz}\f$):
+ *
+ *                  #define KINETIS_MCG_USE_ERC               1
+ *                  #define KINETIS_MCG_USE_PLL               1
+ *                  #define KINETIS_MCG_DCO_RANGE             (24000000U)
+ *                  #define KINETIS_MCG_ERC_OSCILLATOR        0
+ *                  #define KINETIS_MCG_ERC_FRDIV             2
+ *                  #define KINETIS_MCG_ERC_RANGE             1
+ *                  #define KINETIS_MCG_ERC_FREQ              (4000000U)
+ *                  #define KINETIS_MCG_PLL_PRDIV             1
+ *                  #define KINETIS_MCG_PLL_VDIV0             0
+ *                  #define KINETIS_MCG_PLL_FREQ              (48000000U)
+ *
+ *
+ *              The desired mode can be selected in cpu.c:cpu_clock_init()
+ *              with kinetis_mcg_set_mode(KINETIS_MCG_PEE);
+ * @{
+ *
+ * @file
+ * @brief       Interface definition for the Kinetis MCG driver.
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ */
+
+#ifndef __MCG_CPU_H
+#define __MCG_CPU_H
+
+#include "cpu-conf.h"
+#include "periph_conf.h"
+
+#if KINETIS_CPU_USE_MCG
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+typedef enum kinetis_mcg_mode {
+    KINETIS_MCG_PEE = 0, /**< PLL Engaged External Mode */
+    KINETIS_MCG_PBE,     /**< PLL Bypassed External Mode */
+    KINETIS_MCG_BLPE,    /**< FLL Bypassed Low Power External Mode */
+    KINETIS_MCG_BLPI,    /**< FLL Bypassed Low Power Internal Mode */
+    KINETIS_MCG_FBE,     /**< FLL Bypassed External Mode */
+    KINETIS_MCG_FBI,     /**< FLL Bypassed Internal Mode */
+    KINETIS_MCG_FEE,     /**< FLL Engaged External Mode */
+    KINETIS_MCG_FEI,     /**< FLL Engaged Internal Mode */
+} kinetis_mcg_mode_t;
+
+/**
+ * @brief Initialize the MCG
+ *
+ */
+int kinetis_mcg_set_mode(kinetis_mcg_mode_t mode);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MCG_CPU_H */
+/** @} */
+
+#endif /* KINETIS_CPU_USE_MCG */
diff --git a/cpu/kinetis_common/mcg.c b/cpu/kinetis_common/mcg.c
new file mode 100644
index 0000000000..b567b348e4
--- /dev/null
+++ b/cpu/kinetis_common/mcg.c
@@ -0,0 +1,484 @@
+/*
+ * Copyright (C) 2015 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_mcg
+ * @{
+ *
+ * @file
+ * @brief       Implementation of the Kinetis Multipurpose Clock Generator
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ * @}
+ */
+
+#include <stdint.h>
+#include "mcg.h"
+#include "periph_conf.h"
+
+#if KINETIS_CPU_USE_MCG
+
+/* MCG neighbor modes matrix */
+static uint8_t mcg_pm[8] = {0x02, 0x15, 0x12, 0x20, 0xe6, 0xd8, 0xb0, 0xf0};
+
+static uint8_t current_mode = KINETIS_MCG_FEI;
+
+#define KINETIS_MCG_FLL_FACTOR_640        0
+#define KINETIS_MCG_FLL_FACTOR_732        (MCG_C4_DRST_DRS(0) | MCG_C4_DMX32_MASK)
+#define KINETIS_MCG_FLL_FACTOR_1280       (MCG_C4_DRST_DRS(1))
+#define KINETIS_MCG_FLL_FACTOR_1464       (MCG_C4_DRST_DRS(1) | MCG_C4_DMX32_MASK)
+#define KINETIS_MCG_FLL_FACTOR_1920       (MCG_C4_DRST_DRS(2))
+#define KINETIS_MCG_FLL_FACTOR_2197       (MCG_C4_DRST_DRS(2) | MCG_C4_DMX32_MASK)
+#define KINETIS_MCG_FLL_FACTOR_2560       (MCG_C4_DRST_DRS(3))
+#define KINETIS_MCG_FLL_FACTOR_2929       (MCG_C4_DRST_DRS(3) | MCG_C4_DMX32_MASK)
+
+#ifndef KINETIS_MCG_DCO_RANGE
+#define KINETIS_MCG_DCO_RANGE             (48000000U)
+#endif
+
+/* Default DCO_RANGE should be defined in periph_conf.h */
+#if (KINETIS_MCG_DCO_RANGE == 24000000U)
+#define KINETIS_MCG_FLL_FACTOR_FEI        KINETIS_MCG_FLL_FACTOR_640
+#define KINETIS_MCG_FLL_FACTOR_FEE        KINETIS_MCG_FLL_FACTOR_732
+#elif (KINETIS_MCG_DCO_RANGE == 48000000U)
+#define KINETIS_MCG_FLL_FACTOR_FEI        KINETIS_MCG_FLL_FACTOR_1280
+#define KINETIS_MCG_FLL_FACTOR_FEE        KINETIS_MCG_FLL_FACTOR_1464
+#elif (KINETIS_MCG_DCO_RANGE == 72000000U)
+#define KINETIS_MCG_FLL_FACTOR_FEI        KINETIS_MCG_FLL_FACTOR_1920
+#define KINETIS_MCG_FLL_FACTOR_FEE        KINETIS_MCG_FLL_FACTOR_2197
+#elif (KINETIS_MCG_DCO_RANGE == 96000000U)
+#define KINETIS_MCG_FLL_FACTOR_FEI        KINETIS_MCG_FLL_FACTOR_2560
+#define KINETIS_MCG_FLL_FACTOR_FEE        KINETIS_MCG_FLL_FACTOR_2929
+#else
+#error "KINETIS_MCG_DCO_RANGE is wrong"
+#endif
+
+#ifndef KINETIS_MCG_USE_FAST_IRC
+#define KINETIS_MCG_USE_FAST_IRC          0
+#endif
+
+#if (KINETIS_MCG_USE_ERC == 0)
+#define KINETIS_MCG_USE_ERC               0
+#define KINETIS_MCG_USE_PLL               0
+#define KINETIS_MCG_ERC_FREQ              0
+#define KINETIS_MCG_ERC_FRDIV             0
+#define KINETIS_MCG_ERC_RANGE             0
+#define KINETIS_MCG_ERC_OSCILLATOR        0
+#endif
+
+#if (KINETIS_MCG_USE_PLL == 0)
+#define KINETIS_MCG_PLL_PRDIV             0
+#define KINETIS_MCG_PLL_VDIV0             0
+#define KINETIS_MCG_PLL_FREQ              0
+#endif
+
+#ifndef KINETIS_MCG_OSC_CLC
+#define KINETIS_MCG_OSC_CLC               0
+#endif
+
+#ifndef KINETIS_MCG_ERC_OSCILLATOR
+#error "KINETIS_MCG_ERC_OSCILLATOR not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_ERC_FREQ
+#error "KINETIS_MCG_ERC_FREQ not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_ERC_FRDIV
+#error "KINETIS_MCG_ERC_FRDIV not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_ERC_RANGE
+#error "KINETIS_MCG_ERC_RANGE not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_PLL_PRDIV
+#error "KINETIS_MCG_PLL_PRDIV not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_PLL_VDIV0
+#error "KINETIS_MCG_PLL_VDIV0 not defined in periph_conf.h"
+#endif
+
+#ifndef KINETIS_MCG_PLL_FREQ
+#error "KINETIS_MCG_PLL_FREQ not defined in periph_conf.h"
+#endif
+
+/**
+ * @brief Disable Phase Locked Loop (PLL)
+ *
+ */
+static inline void kinetis_mcg_disable_pll(void)
+{
+    MCG->C5 = (uint8_t)0;
+    MCG->C6 = (uint8_t)0;
+}
+
+/**
+ * @brief Set Frequency Locked Loop (FLL) factor.
+ *
+ * The FLL will lock the DCO frequency to the FLL factor.
+ * FLL factor will be selected by DRST_DRS and DMX32 bits
+ * and depends on KINETIS_MCG_DCO_RANGE value.
+ */
+static inline void kinetis_mcg_set_fll_factor(uint8_t factor)
+{
+    MCG->C4 &= ~(uint8_t)(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK);
+    MCG->C4 |= (uint8_t)(factor);
+}
+
+/**
+ * @brief Enable Oscillator module
+ *
+ * The module settings depend on KINETIS_MCG_ERC_RANGE
+ * KINETIS_MCG_ERC_OSCILLATOR values.
+ */
+static void kinetis_mcg_enable_osc(void)
+{
+    if (KINETIS_MCG_ERC_RANGE == 1) {
+        /* select high frequency range and oscillator clock */
+        MCG->C2 = (uint8_t)(MCG_C2_RANGE0(1));
+    }
+    else if (KINETIS_MCG_ERC_RANGE == 2) {
+        /* select very high frequency range and osciallor clock */
+        MCG->C2 = (uint8_t)(MCG_C2_RANGE0(2));
+    }
+    else {
+        /* select low frequency range and osciallor clock */
+        MCG->C2 = (uint8_t)(MCG_C2_RANGE0(0));
+    }
+
+    OSC0->CR = (uint8_t)(OSC_CR_ERCLKEN_MASK | OSC_CR_EREFSTEN_MASK
+                         | (KINETIS_MCG_OSC_CLC & 0xf));
+
+    /* Enable Oscillator */
+    if (KINETIS_MCG_ERC_OSCILLATOR) {
+        MCG->C2 |= (uint8_t)(MCG_C2_EREFS0_MASK);
+
+        /* wait fo OSC initialization */
+        while ((MCG->S & MCG_S_OSCINIT0_MASK) == 0);
+    }
+}
+
+/**
+ * @brief Initialize the FLL Engaged Internal Mode.
+ *
+ * MCGOUTCLK is derived from the FLL clock.
+ * Clock source is the 32kHz slow Internal Reference Clock.
+ * The FLL loop will lock the DCO frequency to the FLL-Factor.
+ */
+static void kinetis_mcg_set_fei(void)
+{
+    kinetis_mcg_set_fll_factor(KINETIS_MCG_FLL_FACTOR_FEI);
+    /* enable and select slow internal reference clock */
+    MCG->C1 = (uint8_t)(MCG_C1_CLKS(0) | MCG_C1_IREFS_MASK);
+
+    /* set to defaults */
+    MCG->C2 = (uint8_t)0;
+
+    /* source of the FLL reference clock shall be internal reference clock */
+    while ((MCG->S & MCG_S_IREFST_MASK) == 0);
+
+    /* Wait until output of the FLL is selected */
+    while (MCG->S & (MCG_S_CLKST_MASK));
+
+    kinetis_mcg_disable_pll();
+    current_mode = KINETIS_MCG_FEI;
+}
+
+/**
+ * @brief Initialize the FLL Engaged External Mode.
+ *
+ * MCGOUTCLK is derived from the FLL clock.
+ * Clock source is the external reference clock (IRC or oscillator).
+ * The FLL loop will lock the DCO frequency to the FLL-Factor.
+ */
+static void kinetis_mcg_set_fee(void)
+{
+    kinetis_mcg_enable_osc();
+    kinetis_mcg_set_fll_factor(KINETIS_MCG_FLL_FACTOR_FEE);
+
+    /* select external reference clock and divide factor */
+    MCG->C1 = (uint8_t)(MCG_C1_CLKS(0) | MCG_C1_FRDIV(KINETIS_MCG_ERC_FRDIV));
+
+    /* Wait until output of FLL is selected */
+    while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(0));
+
+    kinetis_mcg_disable_pll();
+    current_mode = KINETIS_MCG_FEE;
+}
+
+/**
+ * @brief Initialize the FLL Bypassed Internal Mode.
+ *
+ * MCGOUTCLK is derived from 32kHz IRC or 4MHz IRC.
+ * FLL output is not used.
+ * FLL clock source is internal 32kHz IRC.
+ * The FLL loop will lock the DCO frequency to the FLL-Factor.
+ * Next useful mode: BLPI or FEI.
+ */
+static void kinetis_mcg_set_fbi(void)
+{
+    /* select IRC source */
+    if (KINETIS_MCG_USE_FAST_IRC) {
+        MCG->C2 = (uint8_t)(MCG_C2_IRCS_MASK);
+    }
+    else {
+        MCG->C2 = (uint8_t)(0);
+    }
+
+    kinetis_mcg_set_fll_factor(KINETIS_MCG_FLL_FACTOR_FEI);
+    /* enable and select slow internal reference clock */
+    MCG->C1 = (uint8_t)(MCG_C1_CLKS(1) | MCG_C1_IREFS_MASK);
+
+    /* Wait until output of IRC is selected */
+    while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(1));
+
+    /* source of the FLL reference clock shall be internal reference clock */
+    while ((MCG->S & MCG_S_IREFST_MASK) == 0);
+
+    kinetis_mcg_disable_pll();
+    current_mode = KINETIS_MCG_FBI;
+}
+
+/**
+ * @brief Initialize the FLL Bypassed External Mode.
+ *
+ * MCGOUTCLK is derived from external reference clock (oscillator).
+ * FLL output is not used.
+ * Clock source is the external reference clock (oscillator).
+ * The FLL loop will lock the DCO frequency to the FLL-Factor.
+ */
+static void kinetis_mcg_set_fbe(void)
+{
+    kinetis_mcg_enable_osc();
+    kinetis_mcg_set_fll_factor(KINETIS_MCG_FLL_FACTOR_FEE);
+
+    /* FLL is not disabled in bypass mode */
+    MCG->C2 &= ~(uint8_t)(MCG_C2_LP_MASK);
+
+    /* select external reference clock and divide factor */
+    MCG->C1 = (uint8_t)(MCG_C1_CLKS(2) | MCG_C1_FRDIV(KINETIS_MCG_ERC_FRDIV));
+
+    /* Wait until ERC is selected */
+    while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(2));
+
+    kinetis_mcg_disable_pll();
+    current_mode = KINETIS_MCG_FBE;
+}
+
+
+/**
+ * @brief Initialize the FLL Bypassed Low Power Internal Mode.
+ *
+ * MCGOUTCLK is derived from IRC.
+ * FLL and PLL are disable.
+ * Previous and next allowed mode is FBI.
+ */
+static void kinetis_mcg_set_blpi(void)
+{
+    MCG->C2 |= (uint8_t)(MCG_C2_LP_MASK);
+    current_mode = KINETIS_MCG_BLPI;
+}
+
+/**
+ * @brief Initialize the FLL Bypassed Low Power External Mode.
+ *
+ * MCGOUTCLK is derived from ERC.
+ * FLL and PLL are disable.
+ * Previous and next allowed mode: FBE or PBE.
+ */
+static void kinetis_mcg_set_blpe(void)
+{
+    MCG->C2 |= (uint8_t)(MCG_C2_LP_MASK);
+    current_mode = KINETIS_MCG_BLPE;
+}
+
+/**
+ * @brief Initialize the PLL Bypassed External Mode.
+ *
+ * MCGOUTCLK is derived from external reference clock (oscillator).
+ * PLL output is not used.
+ * Clock source is the external reference clock (oscillator).
+ * The PLL loop will locks to VDIV times the frequency
+ * corresponding by PRDIV.
+ * Previous allowed mode are FBE or BLPE.
+ */
+static void kinetis_mcg_set_pbe(void)
+{
+    /* select external reference clock and divide factor */
+    MCG->C1 = (uint8_t)(MCG_C1_CLKS(2) | MCG_C1_FRDIV(KINETIS_MCG_ERC_FRDIV));
+
+    /* Wait until ERC is selected */
+    while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(2));
+
+    /* PLL is not disabled in bypass mode */
+    MCG->C2 &= ~(uint8_t)(MCG_C2_LP_MASK);
+
+    /* set external reference devider */
+    MCG->C5 = (uint8_t)(MCG_C5_PRDIV0(KINETIS_MCG_PLL_PRDIV));
+
+    /* set external reference devider */
+    MCG->C6 = (uint8_t)(MCG_C6_VDIV0(KINETIS_MCG_PLL_VDIV0));
+
+    /* select PLL */
+    MCG->C6 |= (uint8_t)(MCG_C6_PLLS_MASK);
+
+    /* Wait until the source of the PLLS clock is PLL */
+    while ((MCG->S & MCG_S_PLLST_MASK) == 0);
+
+    /* Wait until PLL locked */
+    while ((MCG->S & MCG_S_LOCK0_MASK) == 0);
+
+    current_mode = KINETIS_MCG_PBE;
+}
+
+/**
+ * @brief Initialize the PLL Engaged External Mode.
+ *
+ * MCGOUTCLK is derived from PLL.
+ * PLL output is used.
+ * Previous and next allowed mode is PBE.
+ */
+static void kinetis_mcg_set_pee(void)
+{
+    MCG->C1 &= ~(uint8_t)(MCG_C1_CLKS_MASK);
+
+    /* Wait until output of the PLL is selected */
+    while ((MCG->S & MCG_S_CLKST_MASK) != MCG_S_CLKST(3));
+
+    current_mode = KINETIS_MCG_PEE;
+}
+
+
+int kinetis_mcg_set_mode(kinetis_mcg_mode_t mode)
+{
+    if (mode > KINETIS_MCG_FEI) {
+        return -1;
+    }
+
+    if (mcg_pm[current_mode] & (1 << mode)) {
+        if (mode == KINETIS_MCG_FEI) {
+            kinetis_mcg_set_fei();
+        }
+
+        if (mode == KINETIS_MCG_FBI) {
+            kinetis_mcg_set_fbi();
+        }
+
+        if (mode == KINETIS_MCG_FEE) {
+            kinetis_mcg_set_fee();
+        }
+
+        if (mode == KINETIS_MCG_FBE) {
+            kinetis_mcg_set_fbe();
+        }
+
+        if (mode == KINETIS_MCG_BLPI) {
+            kinetis_mcg_set_blpi();
+        }
+
+        if (mode == KINETIS_MCG_BLPE) {
+            kinetis_mcg_set_blpe();
+        }
+
+        if (mode == KINETIS_MCG_PBE) {
+            kinetis_mcg_set_pbe();
+        }
+
+        if (mode == KINETIS_MCG_PEE) {
+            kinetis_mcg_set_pee();
+        }
+
+        return 0;
+    }
+
+    switch (mode) {
+        case KINETIS_MCG_PEE:
+            /* cppcheck-suppress duplicateExpression */
+            if (!(KINETIS_MCG_USE_ERC || KINETIS_MCG_USE_PLL)) {
+                return -1;
+            }
+
+            if (current_mode == KINETIS_MCG_FEI) {
+                /* set FBE -> PBE -> PEE */
+                kinetis_mcg_set_fbe();
+                kinetis_mcg_set_pbe();
+                kinetis_mcg_set_pee();
+                return 0;
+            }
+
+            if (current_mode == KINETIS_MCG_BLPE) {
+                /* set PBE -> PEE */
+                kinetis_mcg_set_pbe();
+                kinetis_mcg_set_pee();
+                return 0;
+            }
+
+            break;
+
+        case KINETIS_MCG_BLPE:
+            if (!KINETIS_MCG_USE_ERC) {
+                return -1;
+            }
+
+            if (current_mode == KINETIS_MCG_PEE) {
+                /* set PBE -> BLPE */
+                kinetis_mcg_set_pbe();
+                kinetis_mcg_set_blpe();
+                return 0;
+            }
+
+            if (current_mode == KINETIS_MCG_FEE) {
+                /* set FBE -> BLPE */
+                kinetis_mcg_set_fbe();
+                kinetis_mcg_set_blpe();
+                return 0;
+            }
+
+            break;
+
+        case KINETIS_MCG_BLPI:
+            if (current_mode == KINETIS_MCG_FEE) {
+                /* set FBI -> BLPI */
+                kinetis_mcg_set_fbi();
+                kinetis_mcg_set_blpi();
+                return 0;
+            }
+
+            break;
+
+        case KINETIS_MCG_FEE:
+            if (!KINETIS_MCG_USE_ERC) {
+                return -1;
+            }
+
+            if (current_mode == KINETIS_MCG_BLPE) {
+                /* set FBE -> FEE */
+                kinetis_mcg_set_fbe();
+                kinetis_mcg_set_fee();
+                return 0;
+            }
+
+            if (current_mode == KINETIS_MCG_BLPI) {
+                /* set FBI -> FEE */
+                kinetis_mcg_set_fbi();
+                kinetis_mcg_set_fee();
+                return 0;
+            }
+
+            break;
+
+        default:
+            break;
+    }
+
+    return -1;
+}
+
+#endif /* KINETIS_CPU_USE_MCG */
diff --git a/cpu/kinetis_common/pwm.c b/cpu/kinetis_common/pwm.c
new file mode 100644
index 0000000000..1b0bbbd966
--- /dev/null
+++ b/cpu/kinetis_common/pwm.c
@@ -0,0 +1,274 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_pwm
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level PWM driver implementation
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ * @author      Jonas Remmert <j.remmert@phytec.de>
+ *
+ * @}
+ */
+
+#include <stdint.h>
+#include <string.h>
+
+#include "cpu.h"
+#include "periph/pwm.h"
+#include "periph_conf.h"
+
+#include "hwtimer.h"
+
+/* ignore file in case no PWM devices are defined */
+#if PWM_NUMOF
+
+int pwm_init(pwm_t dev, pwm_mode_t mode, unsigned int frequency, unsigned int resolution)
+{
+    FTM_Type *tim = NULL;
+    PORT_Type *port[PWM_MAX_CHANNELS];
+    /* cppcheck-suppress unassignedVariable */
+    uint8_t pins[PWM_MAX_CHANNELS];
+    uint8_t af[PWM_MAX_CHANNELS];
+    /* cppcheck-suppress unassignedVariable */
+    uint8_t ftmchan[PWM_MAX_CHANNELS];
+    int channels = 0;
+    uint32_t pwm_clk = 0;
+
+    pwm_poweron(dev);
+
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            tim = PWM_0_DEV;
+            port[0] = PWM_0_PORT_CH0;
+            port[1] = PWM_0_PORT_CH1;
+            port[2] = PWM_0_PORT_CH2;
+            port[3] = PWM_0_PORT_CH3;
+            pins[0] = PWM_0_PIN_CH0;
+            pins[1] = PWM_0_PIN_CH1;
+            pins[2] = PWM_0_PIN_CH2;
+            pins[3] = PWM_0_PIN_CH3;
+            ftmchan[0] = PWM_0_FTMCHAN_CH0;
+            ftmchan[1] = PWM_0_FTMCHAN_CH1;
+            ftmchan[2] = PWM_0_FTMCHAN_CH2;
+            ftmchan[3] = PWM_0_FTMCHAN_CH3;
+            af[0] = PWM_0_PIN_AF_CH0;
+            af[1] = PWM_0_PIN_AF_CH1;
+            af[2] = PWM_0_PIN_AF_CH2;
+            af[3] = PWM_0_PIN_AF_CH3;
+            channels = PWM_0_CHANNELS;
+            pwm_clk = PWM_0_CLK;
+            PWM_0_PORT_CLKEN();
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    if (channels > PWM_MAX_CHANNELS) {
+        return -1;
+    }
+
+    /* cppcheck-suppress nullPointer */
+    tim->MODE = (1 << FTM_MODE_WPDIS_SHIFT);
+
+    /* setup pins, reset timer match value */
+    for (int i = 0; i < channels; i++) {
+        port[i]->PCR[pins[i]] = PORT_PCR_MUX(af[i]);
+        /* cppcheck-suppress nullPointer */
+        tim->CONTROLS[i].CnV = 0;
+    }
+
+    /* reset timer configuration registers */
+    /* cppcheck-suppress nullPointer */
+    tim->COMBINE = 0;
+
+    /* set prescale and mod registers to matching values for resolution and frequency */
+    if (resolution > 0xffff || (resolution * frequency) > pwm_clk) {
+        return -2;
+    }
+
+    /* cppcheck-suppress nullPointer */
+    tim->SC = FTM_SC_PS((pwm_clk / (resolution * frequency)) - 1);
+    /* cppcheck-suppress nullPointer */
+    tim->MOD = resolution;
+
+    /* set PWM mode */
+    switch (mode) {
+        case PWM_LEFT:
+            for (int i = 0; i < channels; i++) {
+                /* cppcheck-suppress nullPointer */
+                tim->CONTROLS[ftmchan[i]].CnSC = (1 << FTM_CnSC_MSB_SHIFT |
+                                                  1 << FTM_CnSC_ELSB_SHIFT);
+            }
+
+            break;
+
+        case PWM_RIGHT:
+            for (int i = 0; i < channels; i++) {
+                /* cppcheck-suppress nullPointer */
+                tim->CONTROLS[ftmchan[i]].CnSC = (1 << FTM_CnSC_MSB_SHIFT |
+                                                  1 << FTM_CnSC_ELSA_SHIFT);
+            }
+
+            break;
+
+        case PWM_CENTER:
+            for (int i = 0; i < channels; i++) {
+                /* cppcheck-suppress nullPointer */
+                tim->CONTROLS[ftmchan[i]].CnSC = (1 << FTM_CnSC_MSB_SHIFT);
+            }
+
+            /* cppcheck-suppress nullPointer */
+            tim->SC |= (1 << FTM_SC_CPWMS_SHIFT);
+            break;
+    }
+
+    /* enable timer ergo the PWM generation */
+    pwm_start(dev);
+
+    return 0;
+}
+
+int pwm_set(pwm_t dev, int channel, unsigned int value)
+{
+    FTM_Type *tim = NULL;
+
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            tim = PWM_0_DEV;
+            break;
+#endif
+#if PWM_1_EN
+
+        case PWM_1:
+            tim = PWM_1_DEV;
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* norm value to maximum possible value */
+    if (value > 0xffff) {
+        value = 0xffff;
+    }
+
+    switch (channel) {
+        case 0:
+            /* cppcheck-suppress nullPointer */
+            tim->CONTROLS[PWM_0_FTMCHAN_CH0].CnV = value;
+            break;
+
+        case 1:
+            /* cppcheck-suppress nullPointer */
+            tim->CONTROLS[PWM_0_FTMCHAN_CH1].CnV = value;
+            break;
+
+        case 2:
+            /* cppcheck-suppress nullPointer */
+            tim->CONTROLS[PWM_0_FTMCHAN_CH2].CnV = value;
+            break;
+
+        case 3:
+            /* cppcheck-suppress nullPointer */
+            tim->CONTROLS[PWM_0_FTMCHAN_CH3].CnV = value;
+            break;
+
+        default:
+            return -1;
+    }
+
+    return 0;
+}
+
+void pwm_start(pwm_t dev)
+{
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            PWM_0_DEV->SC |= FTM_SC_CLKS(1);
+            break;
+#endif
+#if PWM_1_EN
+
+        case PWM_1:
+            PWM_1_DEV->SC |= FTM_SC_CLKS(1);
+            break;
+#endif
+    }
+}
+
+void pwm_stop(pwm_t dev)
+{
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            PWM_0_DEV->SC &= ~FTM_SC_CLKS_MASK;
+            break;
+#endif
+#if PWM_1_EN
+
+        case PWM_1:
+            PWM_1_DEV->SC &= ~FTM_SC_CLKS_MASK;
+            break;
+#endif
+    }
+}
+
+void pwm_poweron(pwm_t dev)
+{
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            PWM_0_CLKEN();
+            break;
+#endif
+#if PWM_1_EN
+
+        case PWM_1:
+            PWM_1_CLKEN();
+            break;
+#endif
+    }
+}
+
+void pwm_poweroff(pwm_t dev)
+{
+    switch (dev) {
+#if PWM_0_EN
+
+        case PWM_0:
+            PWM_0_CLKDIS();
+            break;
+#endif
+#if PWM_1_EN
+
+        case PWM_1:
+            PWM_1_CLKDIS();
+            break;
+#endif
+    }
+}
+
+#endif /* PWM_NUMOF */
diff --git a/cpu/kinetis_common/random_rnga.c b/cpu/kinetis_common/random_rnga.c
new file mode 100644
index 0000000000..af6e2ec936
--- /dev/null
+++ b/cpu/kinetis_common/random_rnga.c
@@ -0,0 +1,82 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_rnga
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level random number generator driver implementation.
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de> (adaption for Freescale's RNGA)
+ * @author      Hauke Petersen <mail@haukepetersen.de>
+ *
+ * @}
+ */
+
+#include "cpu.h"
+#include "periph/random.h"
+#include "periph_conf.h"
+
+#if RANDOM_NUMOF
+#ifdef KINETIS_RNGA
+
+void random_init(void)
+{
+    random_poweron();
+}
+
+int random_read(char *buf, unsigned int num)
+{
+    /* cppcheck-suppress variableScope */
+    uint32_t tmp;
+    int count = 0;
+
+    /* self-seeding */
+    while (!(KINETIS_RNGA->SR & RNG_SR_OREG_LVL_MASK));
+
+    KINETIS_RNGA->ER = KINETIS_RNGA->OR ^ (uint32_t)buf;
+
+    while (count < num) {
+        /* wait for random data to be ready to read */
+        while (!(KINETIS_RNGA->SR & RNG_SR_OREG_LVL_MASK));
+
+        tmp = KINETIS_RNGA->OR;
+
+        /* copy data into result vector */
+        for (int i = 0; i < 4 && count < num; i++) {
+            buf[count++] = (char)tmp;
+            tmp = tmp >> 8;
+        }
+    }
+
+    return count;
+}
+
+void random_poweron(void)
+{
+    RANDOM_CLKEN();
+    KINETIS_RNGA->CR = RNG_CR_INTM_MASK | RNG_CR_HA_MASK | RNG_CR_GO_MASK;
+}
+
+void random_poweroff(void)
+{
+    KINETIS_RNGA->CR = 0;
+    RANDOM_CLKDIS();
+}
+
+/*
+void isr_rng(void)
+{
+}
+*/
+
+#endif /* KINETIS_RNGA */
+#endif /* RANDOM_NUMOF */
diff --git a/cpu/kinetis_common/random_rngb.c b/cpu/kinetis_common/random_rngb.c
new file mode 100644
index 0000000000..648dc27eba
--- /dev/null
+++ b/cpu/kinetis_common/random_rngb.c
@@ -0,0 +1,88 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ * Copyright (C) 2015 Eistec AB
+ *
+ * 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     cpu_kinetis_common_rngb
+ * @{
+ *
+ * @file
+ * @brief       Low-level random number generator driver implementation.
+ *
+ * @author      Joakim Gebart <joakim.gebart@eistec.se> (adaption for Freescale's RNGB)
+ * @author      Johann Fischer <j.fischer@phytec.de> (adaption for Freescale's RNGA)
+ * @author      Hauke Petersen <mail@haukepetersen.de>
+ *
+ * @}
+ */
+
+#include "cpu.h"
+#include "periph/random.h"
+#include "periph_conf.h"
+
+#if RANDOM_NUMOF
+#ifdef KINETIS_RNGB
+
+
+void random_init(void)
+{
+    random_poweron();
+}
+
+int random_read(char *buf, unsigned int num)
+{
+    int count = 0;
+
+    while (count < num) {
+        uint32_t tmp;
+
+        /* wait for random data to be ready to read */
+        while (!(KINETIS_RNGB->SR & RNG_SR_FIFO_LVL_MASK));
+
+        tmp = KINETIS_RNGB->OUT;
+
+        /* copy data into result vector */
+        for (int i = 0; i < 4 && count < num; i++) {
+            buf[count++] = (char)tmp;
+            tmp = tmp >> 8;
+        }
+    }
+
+    return count;
+}
+
+void random_poweron(void)
+{
+    RANDOM_CLKEN();
+
+    if ((KINETIS_RNGB->VER & RNG_VER_TYPE_MASK) != 0b0001) {
+        /* Wrong type of RNG */
+        /* TODO: Handle */
+    }
+
+    /* Software reset, bit is self-clearing */
+    BITBAND_REG(KINETIS_RNGB->CMD, RNG_CMD_SR_SHIFT) = 1;
+    /* Set up automatic reseed */
+    KINETIS_RNGB->CR = RNG_CR_AR_MASK | RNG_CR_MASKERR_MASK | RNG_CR_MASKDONE_MASK;
+}
+
+void random_poweroff(void)
+{
+    KINETIS_RNGB->CR = 0;
+    RANDOM_CLKDIS();
+}
+
+/*
+void isr_rng(void)
+{
+}
+*/
+
+#endif /* KINETIS_RNGB */
+#endif /* RANDOM_NUMOF */
diff --git a/cpu/kinetis_common/rtc.c b/cpu/kinetis_common/rtc.c
new file mode 100644
index 0000000000..e5013e719a
--- /dev/null
+++ b/cpu/kinetis_common/rtc.c
@@ -0,0 +1,177 @@
+/*
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_rtc
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level RTC driver implementation for Freescale Kinetis MCUs.
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include <time.h>
+#include "cpu.h"
+#include "periph/rtc.h"
+#include "periph_conf.h"
+#include "sched.h"
+#include "thread.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+#if RTC_NUMOF
+
+
+#ifndef RTC_LOAD_CAP_BITS
+#define RTC_LOAD_CAP_BITS    0
+#endif
+
+typedef struct {
+    rtc_alarm_cb_t cb;        /**< callback called from RTC interrupt */
+    void *arg;                /**< argument passed to the callback */
+} rtc_state_t;
+
+static rtc_state_t rtc_callback;
+
+void rtc_init(void)
+{
+    RTC_Type *rtc = RTC_DEV;
+
+    RTC_UNLOCK();
+    /* Reset RTC */
+    rtc->CR = RTC_CR_SWR_MASK;
+    rtc->CR = 0;
+
+    if (rtc->SR & RTC_SR_TIF_MASK) {
+        /* Clear TIF by writing TSR. */
+        rtc->TSR = 0;
+    }
+
+    /* Enable RTC oscillator and non-supervisor mode accesses. */
+    /* Enable load capacitance as configured by periph_conf.h */
+    rtc->CR = RTC_CR_OSCE_MASK | RTC_CR_SUP_MASK | RTC_LOAD_CAP_BITS;
+
+    /* Clear TAF by writing TAR. */
+    rtc->TAR = 0xffffff42;
+
+    /* Disable all RTC interrupts. */
+    rtc->IER = 0;
+
+    rtc_poweron();
+}
+
+int rtc_set_time(struct tm *time)
+{
+    RTC_Type *rtc = RTC_DEV;
+    time_t t = mktime(time);
+
+    /* Disable Time Counter */
+    rtc->SR &= ~RTC_SR_TCE_MASK;
+    rtc->TSR = t;
+    rtc->SR |= RTC_SR_TCE_MASK;
+    return 0;
+}
+
+int rtc_get_time(struct tm *time)
+{
+    RTC_Type *rtc = RTC_DEV;
+    time_t t;
+
+    for (int i = 0; i < 3; i++) {
+        t = rtc->TSR;
+
+        if (t == (time_t)rtc->TSR) {
+            gmtime_r(&t, time);
+            return 0;
+        }
+    }
+
+    return -1;
+}
+
+int rtc_set_alarm(struct tm *time, rtc_alarm_cb_t cb, void *arg)
+{
+    RTC_Type *rtc = RTC_DEV;
+    time_t t = mktime(time);
+
+    /* Disable Timer Alarm Interrupt */
+    rtc->IER &= ~RTC_IER_TAIE_MASK;
+
+    rtc->TAR = t;
+
+    rtc_callback.cb = cb;
+    rtc_callback.arg = arg;
+
+    /* Enable Timer Alarm Interrupt */
+    rtc->IER |= RTC_IER_TAIE_MASK;
+
+    /* Enable RTC interrupts */
+    NVIC_SetPriority(RTC_IRQn, 10);
+    NVIC_EnableIRQ(RTC_IRQn);
+
+    return 0;
+}
+
+int rtc_get_alarm(struct tm *time)
+{
+    RTC_Type *rtc = RTC_DEV;
+    time_t t = rtc->TAR;
+
+    gmtime_r(&t, time);
+
+    return 0;
+}
+
+void rtc_clear_alarm(void)
+{
+    RTC_Type *rtc = RTC_DEV;
+
+    NVIC_DisableIRQ(RTC_IRQn);
+    /* Disable Timer Alarm Interrupt */
+    rtc->IER &= ~RTC_IER_TAIE_MASK;
+    rtc->TAR = 0;
+    rtc_callback.cb = NULL;
+    rtc_callback.arg = NULL;
+}
+
+/* RTC module has independent power suply. We can not really turn it on/off. */
+
+void rtc_poweron(void)
+{
+    RTC_Type *rtc = RTC_DEV;
+    /* Enable Time Counter */
+    rtc->SR |= RTC_SR_TCE_MASK;
+}
+
+void rtc_poweroff(void)
+{
+    RTC_Type *rtc = RTC_DEV;
+    /* Disable Time Counter */
+    rtc->SR &= ~RTC_SR_TCE_MASK;
+}
+
+void isr_rtc(void)
+{
+    RTC_Type *rtc = RTC_DEV;
+
+    if (rtc->SR & RTC_SR_TAF_MASK) {
+        rtc_callback.cb(rtc_callback.arg);
+        rtc->TAR = 0;
+    }
+
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+}
+
+#endif /* RTC_NUMOF */
diff --git a/cpu/kinetis_common/spi.c b/cpu/kinetis_common/spi.c
new file mode 100644
index 0000000000..47ac6487e5
--- /dev/null
+++ b/cpu/kinetis_common/spi.c
@@ -0,0 +1,1583 @@
+/*
+ * Copyright (C) 2014 Hamburg University of Applied Sciences
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ * Copyright (C) 2015 Eistec AB
+ *
+ * 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.
+ */
+
+#include <stdio.h>
+
+#include "board.h"
+#include "cpu.h"
+#include "periph/spi.h"
+#include "periph_conf.h"
+#include "thread.h"
+#include "sched.h"
+#include "vtimer.h"
+#include "mutex.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+/**
+ * @ingroup     cpu_kinetis_common_spi
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level SPI driver implementation
+ *
+ * @author      Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ * @author      Joakim Gebart <joakim.gebart@eistec.se>
+ *
+ * @}
+ */
+
+/* guard this file in case no SPI device is defined */
+#if SPI_NUMOF
+
+#if SPI_0_EN
+#ifdef SPI_0_PORT
+#define SPI_0_SCK_PORT          SPI_0_PORT
+#define SPI_0_SOUT_PORT         SPI_0_PORT
+#define SPI_0_SIN_PORT          SPI_0_PORT
+#define SPI_0_PCS0_PORT         SPI_0_PORT
+#endif
+
+#ifdef SPI_0_PORT_CLKEN
+#define SPI_0_SCK_PORT_CLKEN    SPI_0_PORT_CLKEN
+#define SPI_0_SOUT_PORT_CLKEN   SPI_0_PORT_CLKEN
+#define SPI_0_SIN_PORT_CLKEN    SPI_0_PORT_CLKEN
+#define SPI_0_PCS0_PORT_CLKEN   SPI_0_PORT_CLKEN
+#endif
+
+#ifdef SPI_0_AF
+#define SPI_0_SCK_AF            SPI_0_AF
+#define SPI_0_SOUT_AF           SPI_0_AF
+#define SPI_0_SIN_AF            SPI_0_AF
+#define SPI_0_PCS0_AF           SPI_0_AF
+#endif
+
+#ifndef SPI_0_TCSC_FREQ
+#define SPI_0_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_0_TASC_FREQ
+#define SPI_0_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_0_TDT_FREQ
+#define SPI_0_TDT_FREQ     (0)
+#endif
+#endif /* SPI_0_EN */
+
+#if SPI_1_EN
+#ifdef SPI_1_PORT
+#define SPI_1_SCK_PORT          SPI_1_PORT
+#define SPI_1_SOUT_PORT         SPI_1_PORT
+#define SPI_1_SIN_PORT          SPI_1_PORT
+#define SPI_1_PCS1_PORT         SPI_1_PORT
+#endif
+
+#ifdef SPI_1_PORT_CLKEN
+#define SPI_1_SCK_PORT_CLKEN    SPI_1_PORT_CLKEN
+#define SPI_1_SOUT_PORT_CLKEN   SPI_1_PORT_CLKEN
+#define SPI_1_SIN_PORT_CLKEN    SPI_1_PORT_CLKEN
+#define SPI_1_PCS1_PORT_CLKEN   SPI_1_PORT_CLKEN
+#endif
+
+#ifdef SPI_1_AF
+#define SPI_1_SCK_AF            SPI_1_AF
+#define SPI_1_SOUT_AF           SPI_1_AF
+#define SPI_1_SIN_AF            SPI_1_AF
+#define SPI_1_PCS1_AF           SPI_1_AF
+#endif
+
+#ifndef SPI_1_TCSC_FREQ
+#define SPI_1_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_1_TASC_FREQ
+#define SPI_1_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_1_TDT_FREQ
+#define SPI_1_TDT_FREQ     (0)
+#endif
+#endif /* SPI_1_EN */
+
+#if SPI_2_EN
+#ifdef SPI_2_PORT
+#define SPI_2_SCK_PORT          SPI_2_PORT
+#define SPI_2_SOUT_PORT         SPI_2_PORT
+#define SPI_2_SIN_PORT          SPI_2_PORT
+#define SPI_2_PCS2_PORT         SPI_2_PORT
+#endif
+
+#ifdef SPI_2_PORT_CLKEN
+#define SPI_2_SCK_PORT_CLKEN    SPI_2_PORT_CLKEN
+#define SPI_2_SOUT_PORT_CLKEN   SPI_2_PORT_CLKEN
+#define SPI_2_SIN_PORT_CLKEN    SPI_2_PORT_CLKEN
+#define SPI_2_PCS2_PORT_CLKEN   SPI_2_PORT_CLKEN
+#endif
+
+#ifdef SPI_2_AF
+#define SPI_2_SCK_AF            SPI_2_AF
+#define SPI_2_SOUT_AF           SPI_2_AF
+#define SPI_2_SIN_AF            SPI_2_AF
+#define SPI_2_PCS2_AF           SPI_2_AF
+#endif
+
+#ifndef SPI_2_TCSC_FREQ
+#define SPI_2_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_2_TASC_FREQ
+#define SPI_2_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_2_TDT_FREQ
+#define SPI_2_TDT_FREQ     (0)
+#endif
+#endif /* SPI_2_EN */
+
+#if SPI_3_EN
+#ifdef SPI_3_PORT
+#define SPI_3_SCK_PORT          SPI_3_PORT
+#define SPI_3_SOUT_PORT         SPI_3_PORT
+#define SPI_3_SIN_PORT          SPI_3_PORT
+#define SPI_3_PCS3_PORT         SPI_3_PORT
+#endif
+
+#ifdef SPI_3_PORT_CLKEN
+#define SPI_3_SCK_PORT_CLKEN    SPI_3_PORT_CLKEN
+#define SPI_3_SOUT_PORT_CLKEN   SPI_3_PORT_CLKEN
+#define SPI_3_SIN_PORT_CLKEN    SPI_3_PORT_CLKEN
+#define SPI_3_PCS3_PORT_CLKEN   SPI_3_PORT_CLKEN
+#endif
+
+#ifdef SPI_3_AF
+#define SPI_3_SCK_AF            SPI_3_AF
+#define SPI_3_SOUT_AF           SPI_3_AF
+#define SPI_3_SIN_AF            SPI_3_AF
+#define SPI_3_PCS3_AF           SPI_3_AF
+#endif
+
+#ifndef SPI_3_TCSC_FREQ
+#define SPI_3_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_3_TASC_FREQ
+#define SPI_3_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_3_TDT_FREQ
+#define SPI_3_TDT_FREQ     (0)
+#endif
+#endif /* SPI_3_EN */
+
+#if SPI_4_EN
+#ifdef SPI_4_PORT
+#define SPI_4_SCK_PORT          SPI_4_PORT
+#define SPI_4_SOUT_PORT         SPI_4_PORT
+#define SPI_4_SIN_PORT          SPI_4_PORT
+#define SPI_4_PCS4_PORT         SPI_4_PORT
+#endif
+
+#ifdef SPI_4_PORT_CLKEN
+#define SPI_4_SCK_PORT_CLKEN    SPI_4_PORT_CLKEN
+#define SPI_4_SOUT_PORT_CLKEN   SPI_4_PORT_CLKEN
+#define SPI_4_SIN_PORT_CLKEN    SPI_4_PORT_CLKEN
+#define SPI_4_PCS4_PORT_CLKEN   SPI_4_PORT_CLKEN
+#endif
+
+#ifdef SPI_4_AF
+#define SPI_4_SCK_AF            SPI_4_AF
+#define SPI_4_SOUT_AF           SPI_4_AF
+#define SPI_4_SIN_AF            SPI_4_AF
+#define SPI_4_PCS4_AF           SPI_4_AF
+#endif
+
+#ifndef SPI_4_TCSC_FREQ
+#define SPI_4_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_4_TASC_FREQ
+#define SPI_4_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_4_TDT_FREQ
+#define SPI_4_TDT_FREQ     (0)
+#endif
+#endif /* SPI_4_EN */
+
+#if SPI_5_EN
+#ifdef SPI_5_PORT
+#define SPI_5_SCK_PORT          SPI_5_PORT
+#define SPI_5_SOUT_PORT         SPI_5_PORT
+#define SPI_5_SIN_PORT          SPI_5_PORT
+#define SPI_5_PCS5_PORT         SPI_5_PORT
+#endif
+
+#ifdef SPI_5_PORT_CLKEN
+#define SPI_5_SCK_PORT_CLKEN    SPI_5_PORT_CLKEN
+#define SPI_5_SOUT_PORT_CLKEN   SPI_5_PORT_CLKEN
+#define SPI_5_SIN_PORT_CLKEN    SPI_5_PORT_CLKEN
+#define SPI_5_PCS5_PORT_CLKEN   SPI_5_PORT_CLKEN
+#endif
+
+#ifdef SPI_5_AF
+#define SPI_5_SCK_AF            SPI_5_AF
+#define SPI_5_SOUT_AF           SPI_5_AF
+#define SPI_5_SIN_AF            SPI_5_AF
+#define SPI_5_PCS5_AF           SPI_5_AF
+#endif
+
+#ifndef SPI_5_TCSC_FREQ
+#define SPI_5_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_5_TASC_FREQ
+#define SPI_5_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_5_TDT_FREQ
+#define SPI_5_TDT_FREQ     (0)
+#endif
+#endif /* SPI_5_EN */
+
+#if SPI_6_EN
+#ifdef SPI_6_PORT
+#define SPI_6_SCK_PORT          SPI_6_PORT
+#define SPI_6_SOUT_PORT         SPI_6_PORT
+#define SPI_6_SIN_PORT          SPI_6_PORT
+#define SPI_6_PCS6_PORT         SPI_6_PORT
+#endif
+
+#ifdef SPI_6_PORT_CLKEN
+#define SPI_6_SCK_PORT_CLKEN    SPI_6_PORT_CLKEN
+#define SPI_6_SOUT_PORT_CLKEN   SPI_6_PORT_CLKEN
+#define SPI_6_SIN_PORT_CLKEN    SPI_6_PORT_CLKEN
+#define SPI_6_PCS6_PORT_CLKEN   SPI_6_PORT_CLKEN
+#endif
+
+#ifdef SPI_6_AF
+#define SPI_6_SCK_AF            SPI_6_AF
+#define SPI_6_SOUT_AF           SPI_6_AF
+#define SPI_6_SIN_AF            SPI_6_AF
+#define SPI_6_PCS6_AF           SPI_6_AF
+#endif
+
+#ifndef SPI_6_TCSC_FREQ
+#define SPI_6_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_6_TASC_FREQ
+#define SPI_6_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_6_TDT_FREQ
+#define SPI_6_TDT_FREQ     (0)
+#endif
+#endif /* SPI_6_EN */
+
+#if SPI_7_EN
+#ifdef SPI_7_PORT
+#define SPI_7_SCK_PORT          SPI_7_PORT
+#define SPI_7_SOUT_PORT         SPI_7_PORT
+#define SPI_7_SIN_PORT          SPI_7_PORT
+#define SPI_7_PCS7_PORT         SPI_7_PORT
+#endif
+
+#ifdef SPI_7_PORT_CLKEN
+#define SPI_7_SCK_PORT_CLKEN    SPI_7_PORT_CLKEN
+#define SPI_7_SOUT_PORT_CLKEN   SPI_7_PORT_CLKEN
+#define SPI_7_SIN_PORT_CLKEN    SPI_7_PORT_CLKEN
+#define SPI_7_PCS7_PORT_CLKEN   SPI_7_PORT_CLKEN
+#endif
+
+#ifdef SPI_7_AF
+#define SPI_7_SCK_AF            SPI_7_AF
+#define SPI_7_SOUT_AF           SPI_7_AF
+#define SPI_7_SIN_AF            SPI_7_AF
+#define SPI_7_PCS7_AF           SPI_7_AF
+#endif
+
+#ifndef SPI_7_TCSC_FREQ
+#define SPI_7_TCSC_FREQ    (0)
+#endif
+
+#ifndef SPI_7_TASC_FREQ
+#define SPI_7_TASC_FREQ    (0)
+#endif
+
+#ifndef SPI_7_TDT_FREQ
+#define SPI_7_TDT_FREQ     (0)
+#endif
+#endif /* SPI_7_EN */
+
+/**
+ * @brief Array holding one pre-initialized mutex for each hardware SPI device
+ */
+/* TODO: Avoid adding duplicate entries with the same index. GCC warns about it
+ * but it works. It does look strange in the preprocessed output, however.
+ *
+ * The warning message is:
+ * warning: initialized field overwritten [-Woverride-init]
+ * warning: (near initialization for ‘locks[0]’) [-Woverride-init]
+ *
+ * Example of preprocessed source:
+ * static mutex_t locks[] = {
+ *     [0] = { 0, { ((void *)0) } },
+ *     [1] = { 0, { ((void *)0) } },
+ *     [0] = { 0, { ((void *)0) } }, // index [0] is given (the same, again) initial value.
+ * };
+ */
+
+static mutex_t locks[] =  {
+#if SPI_0_EN
+    [SPI_0_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_1_EN
+    [SPI_1_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_2_EN
+    [SPI_2_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_3_EN
+    [SPI_3_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_4_EN
+    [SPI_4_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_5_EN
+    [SPI_5_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_6_EN
+    [SPI_6_INDEX] = MUTEX_INIT,
+#endif
+#if SPI_7_EN
+    [SPI_7_INDEX] = MUTEX_INIT,
+#endif
+};
+
+/**
+ * @brief Array of pointers that map RIOT SPI device number to actual hardware
+ * module lock.
+ *
+ * Every RIOT device shares the bus lock with any other bus devices for the same
+ * hardware module. This allows us to let two RIOT devices point to the same
+ * hardware but using different CTAR registers for timing information.
+ */
+static mutex_t *locks_map[] = {
+#if SPI_0_EN
+    [SPI_0] = &locks[SPI_0_INDEX],
+#endif
+#if SPI_1_EN
+    [SPI_1] = &locks[SPI_1_INDEX],
+#endif
+#if SPI_2_EN
+    [SPI_2] = &locks[SPI_2_INDEX],
+#endif
+#if SPI_3_EN
+    [SPI_3] = &locks[SPI_3_INDEX],
+#endif
+#if SPI_4_EN
+    [SPI_4] = &locks[SPI_4_INDEX],
+#endif
+#if SPI_5_EN
+    [SPI_5] = &locks[SPI_5_INDEX],
+#endif
+#if SPI_6_EN
+    [SPI_6] = &locks[SPI_6_INDEX],
+#endif
+#if SPI_7_EN
+    [SPI_7] = &locks[SPI_7_INDEX],
+#endif
+};
+
+typedef struct {
+    char(*cb)(char data);
+} spi_state_t;
+
+static inline void irq_handler_transfer(SPI_Type *spi, spi_t dev);
+
+static spi_state_t spi_config[SPI_NUMOF];
+
+#define SPI_IDLE_DATA (0xff)
+
+/**
+ * @brief Helper function for finding optimal baud rate scalers.
+ *
+ * Find the prescaler and scaler settings that will yield a clock frequency
+ * as close as possible (but not above) the target frequency, given the module
+ * runs at module_clock Hz.
+ *
+ * Hardware properties (Baud rate configuration):
+ * Possible prescalers: 2, 3, 5, 7
+ * Possible scalers: 2, 4, 6 (sic!), 8, 16, 32, 64, 128, 256, 512, 1024, 2048, 4096, 8192, 16384, 32768
+ *
+ * SCK baud rate = (f_BUS/PBR) x [(1+DBR)/BR]
+ *
+ * where PBR is the prescaler, BR is the scaler, DBR is the Double BaudRate bit.
+ *
+ * @note We are not using the DBR bit because it may affect the SCK duty cycle.
+ *
+ * @param module_clock Module clock frequency (e.g. F_BUS)
+ * @param target_clock Desired baud rate
+ * @param closest_prescaler pointer where to write the optimal prescaler index.
+ * @param closest_scaler pointer where to write the optimal scaler index.
+ *
+ * @return The actual achieved frequency on success
+ * @return Less than 0 on error.
+ */
+static int find_closest_baudrate_scalers(const uint32_t module_clock, const uint32_t target_clock,
+        uint8_t *closest_prescaler, uint8_t *closest_scaler)
+{
+    uint8_t i;
+    uint8_t k;
+    int freq;
+    static const uint8_t num_scalers = 16;
+    static const uint8_t num_prescalers = 4;
+    static const int br_scalers[16] = {
+        2,     4,     6,     8,    16,    32,    64,   128,
+        256,   512,  1024,  2048,  4096,  8192, 16384, 32768
+    };
+    static const int br_prescalers[4] = {2, 3, 5, 7};
+
+    int closest_frequency = -1;
+
+    /* Test all combinations until we arrive close to the target clock */
+    for (i = 0; i < num_prescalers; ++i) {
+        for (k = 0; k < num_scalers; ++k) {
+            freq = module_clock / (br_scalers[k] * br_prescalers[i]);
+
+            if (freq <= target_clock) {
+                /* Found closest lower frequency at this prescaler setting,
+                 * compare to the best result */
+                if (closest_frequency < freq) {
+                    closest_frequency = freq;
+                    *closest_scaler = k;
+                    *closest_prescaler = i;
+                }
+
+                break;
+            }
+        }
+    }
+
+    if (closest_frequency < 0) {
+        /* Error, no solution found, this line is never reachable with current
+         * hardware settings unless a _very_ low target clock is requested.
+         * (scaler_max * prescaler_max) = 229376 => target_min@100MHz = 435 Hz*/
+        return -1;
+    }
+
+    return closest_frequency;
+}
+
+/**
+ * @brief Helper function for finding optimal delay scalers.
+ *
+ * Find the prescaler and scaler settings that will yield a delay timing
+ * as close as possible (but not shorter than) the target delay, given the
+ * module runs at module_clock Hz.
+ *
+ * Hardware properties (delay configuration):
+ * Possible prescalers: 1, 3, 5, 7
+ * Possible scalers: 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, 4096, 8192, 16384, 32768, 65536
+ *
+ * delay = (1/f_BUS) x prescaler x scaler
+ *
+ * Because we want to do this using only integers, the target_freq parameter is
+ * the reciprocal of the delay time.
+ *
+ * @param module_clock Module clock frequency (e.g. F_BUS)
+ * @param target_freq Reciprocal (i.e. 1/t [Hz], frequency) of the desired delay time.
+ * @param closest_prescaler pointer where to write the optimal prescaler index.
+ * @param closest_scaler pointer where to write the optimal scaler index.
+ *
+ * @return The actual achieved frequency on success
+ * @return Less than 0 on error.
+ */
+static int find_closest_delay_scalers(const uint32_t module_clock, const uint32_t target_freq,
+                                      uint8_t *closest_prescaler, uint8_t *closest_scaler)
+{
+    uint8_t i;
+    uint8_t k;
+    int freq;
+    int prescaler;
+    int scaler;
+    static const uint8_t num_scalers = 16;
+    static const uint8_t num_prescalers = 4;
+
+    int closest_frequency = -1;
+
+    /* Test all combinations until we arrive close to the target clock */
+    for (i = 0; i < num_prescalers; ++i) {
+        for (k = 0; k < num_scalers; ++k) {
+            prescaler = (i * 2) + 1;
+            scaler = (1 << (k + 1)); /* 2^(k+1) */
+            freq = module_clock / (prescaler * scaler);
+
+            if (freq <= target_freq) {
+                /* Found closest lower frequency at this prescaler setting,
+                 * compare to the best result */
+                if (closest_frequency < freq) {
+                    closest_frequency = freq;
+                    *closest_scaler = k;
+                    *closest_prescaler = i;
+                }
+
+                break;
+            }
+        }
+    }
+
+    if (closest_frequency < 0) {
+        /* Error, no solution found, this line is never reachable with current
+         * hardware settings unless a _very_ low target clock is requested.
+         * (scaler_max * prescaler_max) = 458752 */
+        return -1;
+    }
+
+    return closest_frequency;
+}
+
+int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
+{
+    SPI_Type *spi_dev;
+    uint8_t br_prescaler = 0xff;
+    uint8_t br_scaler = 0xff;
+    uint8_t prescaler_tmp = 0xff;
+    uint8_t scaler_tmp = 0xff;
+    uint32_t ctas = 0;
+    uint32_t ctar = 0;
+    uint32_t br_desired;
+    uint32_t module_clock;
+    uint32_t tcsc_freq;
+    uint32_t tasc_freq;
+    uint32_t tdt_freq;
+
+    switch (speed) {
+        case SPI_SPEED_100KHZ:
+            br_desired = 100000;
+            break;
+
+        case SPI_SPEED_400KHZ:
+            br_desired = 400000;
+            break;
+
+        case SPI_SPEED_1MHZ:
+            br_desired = 1000000;
+            break;
+
+        case SPI_SPEED_5MHZ:
+            br_desired = 5000000;
+            break;
+
+        case SPI_SPEED_10MHZ:
+            br_desired = 10000000;
+            break;
+
+        default:
+            return -2;
+    }
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            module_clock = SPI_0_FREQ;
+            tcsc_freq = SPI_0_TCSC_FREQ;
+            tasc_freq = SPI_0_TASC_FREQ;
+            tdt_freq = SPI_0_TDT_FREQ;
+            ctas = SPI_0_CTAS;
+            /* enable clocks */
+            SPI_0_CLKEN();
+            SPI_0_SCK_PORT_CLKEN();
+            SPI_0_SOUT_PORT_CLKEN();
+            SPI_0_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_0_SCK_PORT->PCR[SPI_0_SCK_PIN] = PORT_PCR_MUX(SPI_0_SCK_AF);
+            SPI_0_SOUT_PORT->PCR[SPI_0_SOUT_PIN] = PORT_PCR_MUX(SPI_0_SOUT_AF);
+            SPI_0_SIN_PORT->PCR[SPI_0_SIN_PIN] = PORT_PCR_MUX(SPI_0_SIN_AF);
+            break;
+#endif /* SPI_0_EN */
+
+#if SPI_1_EN
+
+        case SPI_1:
+            spi_dev = SPI_1_DEV;
+            module_clock = SPI_1_FREQ;
+            tcsc_freq = SPI_1_TCSC_FREQ;
+            tasc_freq = SPI_1_TASC_FREQ;
+            tdt_freq = SPI_1_TDT_FREQ;
+            ctas = SPI_1_CTAS;
+            /* enable clocks */
+            SPI_1_CLKEN();
+            SPI_1_SCK_PORT_CLKEN();
+            SPI_1_SOUT_PORT_CLKEN();
+            SPI_1_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_1_SCK_PORT->PCR[SPI_1_SCK_PIN] = PORT_PCR_MUX(SPI_1_SCK_AF);
+            SPI_1_SOUT_PORT->PCR[SPI_1_SOUT_PIN] = PORT_PCR_MUX(SPI_1_SOUT_AF);
+            SPI_1_SIN_PORT->PCR[SPI_1_SIN_PIN] = PORT_PCR_MUX(SPI_1_SIN_AF);
+            break;
+#endif /* SPI_1_EN */
+
+#if SPI_2_EN
+
+        case SPI_2:
+            spi_dev = SPI_2_DEV;
+            module_clock = SPI_2_FREQ;
+            tcsc_freq = SPI_2_TCSC_FREQ;
+            tasc_freq = SPI_2_TASC_FREQ;
+            tdt_freq = SPI_2_TDT_FREQ;
+            ctas = SPI_2_CTAS;
+            /* enable clocks */
+            SPI_2_CLKEN();
+            SPI_2_SCK_PORT_CLKEN();
+            SPI_2_SOUT_PORT_CLKEN();
+            SPI_2_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_2_SCK_PORT->PCR[SPI_2_SCK_PIN] = PORT_PCR_MUX(SPI_2_SCK_AF);
+            SPI_2_SOUT_PORT->PCR[SPI_2_SOUT_PIN] = PORT_PCR_MUX(SPI_2_SOUT_AF);
+            SPI_2_SIN_PORT->PCR[SPI_2_SIN_PIN] = PORT_PCR_MUX(SPI_2_SIN_AF);
+            break;
+#endif /* SPI_2_EN */
+
+#if SPI_3_EN
+
+        case SPI_3:
+            spi_dev = SPI_3_DEV;
+            module_clock = SPI_3_FREQ;
+            tcsc_freq = SPI_3_TCSC_FREQ;
+            tasc_freq = SPI_3_TASC_FREQ;
+            tdt_freq = SPI_3_TDT_FREQ;
+            ctas = SPI_3_CTAS;
+            /* enable clocks */
+            SPI_3_CLKEN();
+            SPI_3_SCK_PORT_CLKEN();
+            SPI_3_SOUT_PORT_CLKEN();
+            SPI_3_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_3_SCK_PORT->PCR[SPI_3_SCK_PIN] = PORT_PCR_MUX(SPI_3_SCK_AF);
+            SPI_3_SOUT_PORT->PCR[SPI_3_SOUT_PIN] = PORT_PCR_MUX(SPI_3_SOUT_AF);
+            SPI_3_SIN_PORT->PCR[SPI_3_SIN_PIN] = PORT_PCR_MUX(SPI_3_SIN_AF);
+            break;
+#endif /* SPI_3_EN */
+
+#if SPI_4_EN
+
+        case SPI_4:
+            spi_dev = SPI_4_DEV;
+            module_clock = SPI_4_FREQ;
+            tcsc_freq = SPI_4_TCSC_FREQ;
+            tasc_freq = SPI_4_TASC_FREQ;
+            tdt_freq = SPI_4_TDT_FREQ;
+            ctas = SPI_4_CTAS;
+            /* enable clocks */
+            SPI_4_CLKEN();
+            SPI_4_SCK_PORT_CLKEN();
+            SPI_4_SOUT_PORT_CLKEN();
+            SPI_4_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_4_SCK_PORT->PCR[SPI_4_SCK_PIN] = PORT_PCR_MUX(SPI_4_SCK_AF);
+            SPI_4_SOUT_PORT->PCR[SPI_4_SOUT_PIN] = PORT_PCR_MUX(SPI_4_SOUT_AF);
+            SPI_4_SIN_PORT->PCR[SPI_4_SIN_PIN] = PORT_PCR_MUX(SPI_4_SIN_AF);
+            break;
+#endif /* SPI_4_EN */
+
+#if SPI_5_EN
+
+        case SPI_5:
+            spi_dev = SPI_5_DEV;
+            module_clock = SPI_5_FREQ;
+            tcsc_freq = SPI_5_TCSC_FREQ;
+            tasc_freq = SPI_5_TASC_FREQ;
+            tdt_freq = SPI_5_TDT_FREQ;
+            ctas = SPI_5_CTAS;
+            /* enable clocks */
+            SPI_5_CLKEN();
+            SPI_5_SCK_PORT_CLKEN();
+            SPI_5_SOUT_PORT_CLKEN();
+            SPI_5_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_5_SCK_PORT->PCR[SPI_5_SCK_PIN] = PORT_PCR_MUX(SPI_5_SCK_AF);
+            SPI_5_SOUT_PORT->PCR[SPI_5_SOUT_PIN] = PORT_PCR_MUX(SPI_5_SOUT_AF);
+            SPI_5_SIN_PORT->PCR[SPI_5_SIN_PIN] = PORT_PCR_MUX(SPI_5_SIN_AF);
+            break;
+#endif /* SPI_5_EN */
+
+#if SPI_6_EN
+
+        case SPI_6:
+            spi_dev = SPI_6_DEV;
+            module_clock = SPI_6_FREQ;
+            tcsc_freq = SPI_6_TCSC_FREQ;
+            tasc_freq = SPI_6_TASC_FREQ;
+            tdt_freq = SPI_6_TDT_FREQ;
+            ctas = SPI_6_CTAS;
+            /* enable clocks */
+            SPI_6_CLKEN();
+            SPI_6_SCK_PORT_CLKEN();
+            SPI_6_SOUT_PORT_CLKEN();
+            SPI_6_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_6_SCK_PORT->PCR[SPI_6_SCK_PIN] = PORT_PCR_MUX(SPI_6_SCK_AF);
+            SPI_6_SOUT_PORT->PCR[SPI_6_SOUT_PIN] = PORT_PCR_MUX(SPI_6_SOUT_AF);
+            SPI_6_SIN_PORT->PCR[SPI_6_SIN_PIN] = PORT_PCR_MUX(SPI_6_SIN_AF);
+            break;
+#endif /* SPI_6_EN */
+
+#if SPI_7_EN
+
+        case SPI_7:
+            spi_dev = SPI_7_DEV;
+            module_clock = SPI_7_FREQ;
+            tcsc_freq = SPI_7_TCSC_FREQ;
+            tasc_freq = SPI_7_TASC_FREQ;
+            tdt_freq = SPI_7_TDT_FREQ;
+            ctas = SPI_7_CTAS;
+            /* enable clocks */
+            SPI_7_CLKEN();
+            SPI_7_SCK_PORT_CLKEN();
+            SPI_7_SOUT_PORT_CLKEN();
+            SPI_7_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_7_SCK_PORT->PCR[SPI_7_SCK_PIN] = PORT_PCR_MUX(SPI_7_SCK_AF);
+            SPI_7_SOUT_PORT->PCR[SPI_7_SOUT_PIN] = PORT_PCR_MUX(SPI_7_SOUT_AF);
+            SPI_7_SIN_PORT->PCR[SPI_7_SIN_PIN] = PORT_PCR_MUX(SPI_7_SIN_AF);
+            break;
+#endif /* SPI_7_EN */
+
+        default:
+            return -1;
+    }
+
+    /* Find baud rate scaler and prescaler settings */
+    if (find_closest_baudrate_scalers(module_clock, br_desired,
+                                      &br_prescaler, &br_scaler) < 0) {
+        /* Desired baud rate is too low to be reachable at current module clock frequency. */
+        return -2;
+    }
+
+    ctar |= SPI_CTAR_PBR(br_prescaler) | SPI_CTAR_BR(br_scaler);
+
+    /* Find the other delay divisors */
+    /* tCSC */
+    if (tcsc_freq == 0) {
+        /* Default to same as baud rate if set to zero. */
+        tcsc_freq = br_desired;
+    }
+
+    if (find_closest_delay_scalers(module_clock, tcsc_freq,
+                                   &prescaler_tmp, &scaler_tmp) < 0) {
+        /* failed to find a solution */
+        return -2;
+    }
+
+    ctar |= SPI_CTAR_PCSSCK(prescaler_tmp) | SPI_CTAR_CSSCK(scaler_tmp);
+
+    /* tASC */
+    if (tasc_freq == 0) {
+        /* Default to same as baud rate if set to zero. */
+        tasc_freq = br_desired;
+    }
+
+    if (find_closest_delay_scalers(module_clock, tasc_freq,
+                                   &prescaler_tmp, &scaler_tmp) < 0) {
+        /* failed to find a solution */
+        return -2;
+    }
+
+    ctar |= SPI_CTAR_PASC(prescaler_tmp) | SPI_CTAR_ASC(scaler_tmp);
+
+    /* tDT */
+    if (tdt_freq == 0) {
+        /* Default to same as baud rate if set to zero. */
+        tdt_freq = br_desired;
+    }
+
+    if (find_closest_delay_scalers(module_clock, tdt_freq,
+                                   &prescaler_tmp, &scaler_tmp) < 0) {
+        /* failed to find a solution */
+        return -2;
+    }
+
+    ctar |= SPI_CTAR_PDT(prescaler_tmp) | SPI_CTAR_DT(scaler_tmp);
+
+
+    /* Set clock polarity and phase. */
+    switch (conf) {
+        case SPI_CONF_FIRST_RISING:
+            break;
+
+        case SPI_CONF_SECOND_RISING:
+            ctar |= SPI_CTAR_CPHA_MASK;
+            break;
+
+        case SPI_CONF_FIRST_FALLING:
+            ctar |= SPI_CTAR_CPOL_MASK;
+            break;
+
+        case SPI_CONF_SECOND_FALLING:
+            ctar |= SPI_CTAR_CPHA_MASK | SPI_CTAR_CPOL_MASK;
+            break;
+
+        default:
+            return -2;
+    }
+
+    /* Update CTAR register with new timing settings, 8-bit frame size. */
+    spi_dev->CTAR[ctas] = SPI_CTAR_FMSZ(7) | ctar;
+
+    /* enable SPI */
+    spi_dev->MCR = SPI_MCR_MSTR_MASK
+                   | SPI_MCR_DOZE_MASK
+                   | SPI_MCR_CLR_TXF_MASK
+                   | SPI_MCR_CLR_RXF_MASK;
+
+    spi_dev->RSER = (uint32_t)0;
+
+    return 0;
+}
+
+int spi_init_slave(spi_t dev, spi_conf_t conf, char(*cb)(char data))
+{
+    SPI_Type *spi_dev;
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            /* enable clocks */
+            SPI_0_CLKEN();
+            SPI_0_PCS0_PORT_CLKEN();
+            SPI_0_SCK_PORT_CLKEN();
+            SPI_0_SOUT_PORT_CLKEN();
+            SPI_0_SIN_PORT_CLKEN();
+            /* Set PORT to AF mode */
+            SPI_0_PCS0_PORT->PCR[SPI_0_PCS0_PIN] = PORT_PCR_MUX(SPI_0_PCS0_AF);
+            SPI_0_SCK_PORT->PCR[SPI_0_SCK_PIN] = PORT_PCR_MUX(SPI_0_SCK_AF);
+            SPI_0_SOUT_PORT->PCR[SPI_0_SOUT_PIN] = PORT_PCR_MUX(SPI_0_SOUT_AF);
+            SPI_0_SIN_PORT->PCR[SPI_0_SIN_PIN] = PORT_PCR_MUX(SPI_0_SIN_AF);
+            break;
+#endif /* SPI_0_EN */
+
+        default:
+            return -1;
+    }
+
+    /* set frame size, slave mode always uses CTAR0 */
+    spi_dev->CTAR[0] = SPI_CTAR_SLAVE_FMSZ(7);
+
+    /* Set clock polarity and phase. */
+    switch (conf) {
+        case SPI_CONF_FIRST_RISING:
+            spi_dev->CTAR[0] &= ~(SPI_CTAR_CPHA_MASK | SPI_CTAR_CPOL_MASK);
+            break;
+
+        case SPI_CONF_SECOND_RISING:
+            spi_dev->CTAR[0] &= ~(SPI_CTAR_CPOL_MASK);
+            spi_dev->CTAR[0] |= SPI_CTAR_CPHA_MASK;
+            break;
+
+        case SPI_CONF_FIRST_FALLING:
+            spi_dev->CTAR[0] &= ~(SPI_CTAR_CPHA_MASK);
+            spi_dev->CTAR[0] |= SPI_CTAR_CPOL_MASK;
+            break;
+
+        case SPI_CONF_SECOND_FALLING:
+            spi_dev->CTAR[0] |= SPI_CTAR_CPHA_MASK | SPI_CTAR_CPOL_MASK;
+            break;
+
+        default:
+            return -2;
+    }
+
+    /* enable SPI */
+    spi_dev->MCR = SPI_MCR_DOZE_MASK
+                   | SPI_MCR_PCSIS(SPI_0_PCS0_ACTIVE_LOW << 0)
+                   | SPI_MCR_CLR_TXF_MASK
+                   | SPI_MCR_CLR_RXF_MASK;
+
+    spi_dev->RSER = (uint32_t)0;
+
+    return 0;
+}
+
+int spi_acquire(spi_t dev)
+{
+    if (dev >= SPI_NUMOF) {
+        return -1;
+    }
+
+    mutex_lock(locks_map[dev]);
+    return 0;
+}
+
+int spi_release(spi_t dev)
+{
+    if (dev >= SPI_NUMOF) {
+        return -1;
+    }
+
+    mutex_unlock(locks_map[dev]);
+    return 0;
+}
+
+static inline uint8_t spi_transfer_internal(SPI_Type *spi_dev, uint32_t flags, uint8_t byte_out)
+{
+    /* Wait until there is space in the TXFIFO */
+    while (!(spi_dev->SR & SPI_SR_TFFF_MASK));
+
+    spi_dev->PUSHR = flags | SPI_PUSHR_TXDATA(byte_out);
+
+    /* Wait until we have received a byte */
+    while (!(spi_dev->SR & SPI_SR_RXCTR_MASK));
+
+    return (uint8_t)spi_dev->POPR;
+}
+
+int spi_transfer_byte(spi_t dev, char out, char *in)
+{
+    SPI_Type *spi_dev;
+    uint8_t byte_in;
+    uint32_t flags;
+
+    /* The chip select lines are expected to be controlled via software in RIOT.
+     * Don't set PCS bits in flags. */
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_0_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_1_EN
+
+        case SPI_1:
+            spi_dev = SPI_1_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_1_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_2_EN
+
+        case SPI_2:
+            spi_dev = SPI_2_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_2_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_3_EN
+
+        case SPI_3:
+            spi_dev = SPI_3_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_3_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_4_EN
+
+        case SPI_4:
+            spi_dev = SPI_4_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_4_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_5_EN
+
+        case SPI_5:
+            spi_dev = SPI_5_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_5_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_6_EN
+
+        case SPI_6:
+            spi_dev = SPI_6_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_6_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+#if SPI_7_EN
+
+        case SPI_7:
+            spi_dev = SPI_7_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_7_CTAS) | SPI_PUSHR_EOQ_MASK);
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    byte_in = spi_transfer_internal(spi_dev, flags, out);
+
+    /* Clear End-of-Queue status flag */
+    spi_dev->SR = SPI_SR_EOQF_MASK;
+
+    if (in != NULL) {
+        *in = (char)byte_in;
+    }
+
+    return 1;
+}
+
+int spi_transfer_bytes(spi_t dev, char *out, char *in, unsigned int length)
+{
+    SPI_Type *spi_dev;
+    uint8_t byte_in;
+    uint8_t byte_out;
+    uint32_t flags;
+    int i;
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_0_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_1_EN
+
+        case SPI_1:
+            spi_dev = SPI_1_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_1_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_2_EN
+
+        case SPI_2:
+            spi_dev = SPI_2_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_2_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_3_EN
+
+        case SPI_3:
+            spi_dev = SPI_3_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_3_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_4_EN
+
+        case SPI_4:
+            spi_dev = SPI_4_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_4_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_5_EN
+
+        case SPI_5:
+            spi_dev = SPI_5_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_5_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_6_EN
+
+        case SPI_6:
+            spi_dev = SPI_6_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_6_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_7_EN
+
+        case SPI_7:
+            spi_dev = SPI_7_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_7_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* Default: send idle data */
+    byte_out = (uint8_t)SPI_IDLE_DATA;
+
+    for (i = 0; i < length; i++) {
+        if (out != NULL) {
+            /* Send given out data */
+            byte_out = (uint8_t)out[i];
+        }
+
+        if (i >= length - 1) {
+            /* Last byte, set End-of-Queue flag, clear Continue flag. */
+            flags &= ~(SPI_PUSHR_CONT_MASK);
+            flags |= SPI_PUSHR_EOQ_MASK;
+        }
+
+        byte_in = spi_transfer_internal(spi_dev, flags, byte_out);
+
+        if (in != NULL) {
+            /* Save input byte to buffer */
+            in[i] = (char)byte_in;
+        }
+    }
+
+    /* Clear End-of-Queue status flag */
+    spi_dev->SR = SPI_SR_EOQF_MASK;
+
+    return i;
+}
+
+int spi_transfer_reg(spi_t dev, uint8_t reg, char out, char *in)
+{
+    SPI_Type *spi_dev;
+    uint8_t byte_in;
+    uint32_t flags;
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_0_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_1_EN
+
+        case SPI_1:
+            spi_dev = SPI_1_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_1_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_2_EN
+
+        case SPI_2:
+            spi_dev = SPI_2_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_2_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_3_EN
+
+        case SPI_3:
+            spi_dev = SPI_3_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_3_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_4_EN
+
+        case SPI_4:
+            spi_dev = SPI_4_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_4_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_5_EN
+
+        case SPI_5:
+            spi_dev = SPI_5_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_5_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_6_EN
+
+        case SPI_6:
+            spi_dev = SPI_6_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_6_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_7_EN
+
+        case SPI_7:
+            spi_dev = SPI_7_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_7_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* Transfer the register address first. */
+    spi_transfer_internal(spi_dev, flags, reg);
+
+    /* Last byte, set End-of-Queue flag, clear Continue flag. */
+    flags &= ~(SPI_PUSHR_CONT_MASK);
+    flags |= SPI_PUSHR_EOQ_MASK;
+
+    /* Transfer the value. */
+    byte_in = spi_transfer_internal(spi_dev, flags, out);
+
+    if (in != NULL) {
+        /* Save input byte to buffer */
+        *in = (char)byte_in;
+    }
+
+    /* Clear End-of-Queue status flag */
+    spi_dev->SR = SPI_SR_EOQF_MASK;
+
+    return 2;
+}
+
+int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, unsigned int length)
+{
+    SPI_Type *spi_dev;
+    uint8_t byte_in;
+    uint8_t byte_out;
+    uint32_t flags;
+    int i;
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            spi_dev = SPI_0_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_0_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_1_EN
+
+        case SPI_1:
+            spi_dev = SPI_1_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_1_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_2_EN
+
+        case SPI_2:
+            spi_dev = SPI_2_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_2_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_3_EN
+
+        case SPI_3:
+            spi_dev = SPI_3_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_3_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_4_EN
+
+        case SPI_4:
+            spi_dev = SPI_4_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_4_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_5_EN
+
+        case SPI_5:
+            spi_dev = SPI_5_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_5_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_6_EN
+
+        case SPI_6:
+            spi_dev = SPI_6_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_6_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+#if SPI_7_EN
+
+        case SPI_7:
+            spi_dev = SPI_7_DEV;
+            flags = (SPI_PUSHR_CTAS(SPI_7_CTAS) | SPI_PUSHR_CONT_MASK);
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    byte_out = reg;
+
+    /* Send register address */
+    byte_in = spi_transfer_internal(spi_dev, flags, byte_out);
+
+    /* Default: send idle data */
+    byte_out = (uint8_t)SPI_IDLE_DATA;
+
+    for (i = 0; i < length; i++) {
+        if (out != NULL) {
+            /* Send given out data */
+            byte_out = (uint8_t)out[i];
+        }
+
+        if (i >= length - 1) {
+            /* Last byte, set End-of-Queue flag, clear Continue flag. */
+            flags &= ~(SPI_PUSHR_CONT_MASK);
+            flags |= SPI_PUSHR_EOQ_MASK;
+        }
+
+        byte_in = spi_transfer_internal(spi_dev, flags, byte_out);
+
+        if (in != NULL) {
+            /* Save input byte to buffer */
+            in[i] = (char)byte_in;
+        }
+    }
+
+    /* Clear End-of-Queue status flag */
+    spi_dev->SR = SPI_SR_EOQF_MASK;
+
+    return i;
+}
+
+void spi_transmission_begin(spi_t dev, char reset_val)
+{
+
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            SPI_0_DEV->PUSHR = SPI_PUSHR_CTAS(SPI_0_CTAS)
+                               | SPI_PUSHR_EOQ_MASK
+                               | SPI_PUSHR_TXDATA(reset_val);
+            break;
+#endif
+    }
+}
+
+void spi_poweron(spi_t dev)
+{
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            SPI_0_CLKEN();
+            break;
+#endif
+#if SPI_1_EN
+
+        case SPI_1:
+            SPI_1_CLKEN();
+            break;
+#endif
+#if SPI_2_EN
+
+        case SPI_2:
+            SPI_2_CLKEN();
+            break;
+#endif
+#if SPI_3_EN
+
+        case SPI_3:
+            SPI_3_CLKEN();
+            break;
+#endif
+#if SPI_4_EN
+
+        case SPI_4:
+            SPI_4_CLKEN();
+            break;
+#endif
+#if SPI_5_EN
+
+        case SPI_5:
+            SPI_5_CLKEN();
+            break;
+#endif
+#if SPI_6_EN
+
+        case SPI_6:
+            SPI_6_CLKEN();
+            break;
+#endif
+#if SPI_7_EN
+
+        case SPI_7:
+            SPI_7_CLKEN();
+            break;
+#endif
+    }
+}
+
+void spi_poweroff(spi_t dev)
+{
+    /* Wait until the last byte has been transmitted before turning off
+     * the clock. */
+    switch (dev) {
+#if SPI_0_EN
+
+        case SPI_0:
+            while ((SPI_0_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_0_CLKDIS();
+            break;
+#endif
+#if SPI_1_EN
+
+        case SPI_1:
+            while ((SPI_1_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_1_CLKDIS();
+            break;
+#endif
+#if SPI_2_EN
+
+        case SPI_2:
+            while ((SPI_2_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_2_CLKDIS();
+            break;
+#endif
+#if SPI_3_EN
+
+        case SPI_3:
+            while ((SPI_3_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_3_CLKDIS();
+            break;
+#endif
+#if SPI_4_EN
+
+        case SPI_4:
+            while ((SPI_4_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_4_CLKDIS();
+            break;
+#endif
+#if SPI_5_EN
+
+        case SPI_5:
+            while ((SPI_5_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_5_CLKDIS();
+            break;
+#endif
+#if SPI_6_EN
+
+        case SPI_6:
+            while ((SPI_6_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_6_CLKDIS();
+            break;
+#endif
+#if SPI_7_EN
+
+        case SPI_7:
+            while ((SPI_7_DEV->SR & SPI_SR_TXCTR_MASK) != 0);
+
+            SPI_7_CLKDIS();
+            break;
+#endif
+    }
+}
+
+static inline void irq_handler_transfer(SPI_Type *spi, spi_t dev)
+{
+
+    if (spi->SR & SPI_SR_RFDF_MASK) {
+        char data;
+        data = (char)spi->POPR;
+        data = spi_config[dev].cb(data);
+        spi->PUSHR = SPI_PUSHR_CTAS(0)
+                     | SPI_PUSHR_EOQ_MASK
+                     | SPI_PUSHR_TXDATA(data);
+    }
+
+    /* see if a thread with higher priority wants to run now */
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+}
+
+#if SPI_0_EN
+#ifdef SPI_0_IRQ_HANDLER
+void SPI_0_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_0_DEV, SPI_0);
+}
+#endif
+#endif
+
+#if SPI_1_EN
+#ifdef SPI_1_IRQ_HANDLER
+void SPI_1_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_1_DEV, SPI_1);
+}
+#endif
+#endif
+
+#if SPI_2_EN
+#ifdef SPI_2_IRQ_HANDLER
+void SPI_2_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_2_DEV, SPI_2);
+}
+#endif
+#endif
+
+#if SPI_3_EN
+#ifdef SPI_3_IRQ_HANDLER
+void SPI_3_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_3_DEV, SPI_3);
+}
+#endif
+#endif
+
+#if SPI_4_EN
+#ifdef SPI_4_IRQ_HANDLER
+void SPI_4_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_4_DEV, SPI_4);
+}
+#endif
+#endif
+
+#if SPI_5_EN
+#ifdef SPI_5_IRQ_HANDLER
+void SPI_5_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_5_DEV, SPI_5);
+}
+#endif
+#endif
+
+#if SPI_6_EN
+#ifdef SPI_6_IRQ_HANDLER
+void SPI_6_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_6_DEV, SPI_6);
+}
+#endif
+#endif
+
+#if SPI_7_EN
+#ifdef SPI_7_IRQ_HANDLER
+void SPI_7_IRQ_HANDLER(void)
+{
+    irq_handler_transfer(SPI_7_DEV, SPI_7);
+}
+#endif
+#endif
+
+#endif /* SPI_NUMOF */
diff --git a/cpu/kinetis_common/timer.c b/cpu/kinetis_common/timer.c
new file mode 100644
index 0000000000..0312699fdd
--- /dev/null
+++ b/cpu/kinetis_common/timer.c
@@ -0,0 +1,368 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ *
+ * 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     cpu_kinetis_common_timer
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level timer driver implementation
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include <stdlib.h>
+
+#include "cpu.h"
+#include "board.h"
+#include "sched.h"
+#include "thread.h"
+#include "periph_conf.h"
+#include "periph/timer.h"
+
+#define ENABLE_DEBUG (0)
+#include "debug.h"
+
+#if TIMER_NUMOF
+
+/** Type for timer state */
+typedef struct {
+    void (*cb)(int);
+} timer_conf_t;
+
+/** Type for virtual count up timer */
+typedef struct {
+    uint32_t counter32b;
+    uint32_t diff;
+} count_up_timer_t;
+
+static count_up_timer_t cu_timer[TIMER_NUMOF];
+
+/** Timer state memory */
+static timer_conf_t config[TIMER_NUMOF];
+
+inline static void pit_timer_start(uint8_t ch)
+{
+    TIMER_DEV->CHANNEL[ch].TCTRL |= (PIT_TCTRL_TEN_MASK);
+}
+
+inline static void pit_timer_stop(uint8_t ch)
+{
+    TIMER_DEV->CHANNEL[ch].TCTRL &= ~(PIT_TCTRL_TEN_MASK);
+}
+
+/** use channel n-1 as prescaler */
+inline static void timer_set_prescaler(uint8_t ch, unsigned int ticks_per_us)
+{
+    TIMER_DEV->CHANNEL[ch].TCTRL = 0x0;
+    TIMER_DEV->CHANNEL[ch].LDVAL = (TIMER_CLOCK / 1e6) / ticks_per_us;
+    TIMER_DEV->CHANNEL[ch].TCTRL = (PIT_TCTRL_TEN_MASK);
+}
+
+inline static void timer_set_counter(uint8_t ch)
+{
+    TIMER_DEV->CHANNEL[ch].TCTRL = 0x0;
+    TIMER_DEV->CHANNEL[ch].LDVAL = TIMER_MAX_VALUE;
+    TIMER_DEV->CHANNEL[ch].TCTRL = (PIT_TCTRL_TIE_MASK | PIT_TCTRL_CHN_MASK);
+}
+
+inline static uint32_t pit_timer_read(tim_t dev, uint8_t ch)
+{
+    return cu_timer[dev].counter32b + (TIMER_DEV->CHANNEL[ch].LDVAL
+                                       - TIMER_DEV->CHANNEL[ch].CVAL);
+}
+
+inline static void pit_timer_set_max(uint8_t ch)
+{
+    pit_timer_stop(ch);
+    TIMER_DEV->CHANNEL[ch].LDVAL = TIMER_MAX_VALUE;
+    pit_timer_start(ch);
+}
+
+int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
+{
+    PIT_Type *timer = TIMER_DEV;
+
+    /* enable timer peripheral clock */
+    TIMER_CLKEN();
+
+    timer->MCR = PIT_MCR_FRZ_MASK;
+
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_IRQ_PRIO);
+            timer_set_prescaler(TIMER_0_PRESCALER_CH, ticks_per_us);
+            timer_set_counter(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_IRQ_PRIO);
+            timer_set_prescaler(TIMER_1_PRESCALER_CH, ticks_per_us);
+            timer_set_counter(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+        default:
+            return -1;
+    }
+
+    /* set callback function */
+    config[dev].cb = callback;
+    cu_timer[dev].counter32b = 0;
+    cu_timer[dev].diff = 0;
+
+    /* enable the timer's interrupt */
+    timer_irq_enable(dev);
+
+    /* start the timer */
+    timer_start(dev);
+
+    return 0;
+}
+
+int timer_set(tim_t dev, int channel, unsigned int timeout)
+{
+    unsigned int now = timer_read(dev);
+
+    return timer_set_absolute(dev, channel, now + timeout);
+}
+
+int timer_set_absolute(tim_t dev, int channel, unsigned int value)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            pit_timer_stop(TIMER_0_COUNTER_CH);
+            cu_timer[dev].counter32b = pit_timer_read(dev, TIMER_0_COUNTER_CH);
+            cu_timer[dev].diff = value - cu_timer[dev].counter32b;
+            TIMER_DEV->CHANNEL[TIMER_0_COUNTER_CH].LDVAL = cu_timer[dev].diff;
+            pit_timer_start(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            pit_timer_stop(TIMER_1_COUNTER_CH);
+            cu_timer[dev].counter32b = pit_timer_read(dev, TIMER_1_COUNTER_CH);
+            cu_timer[dev].diff = value - cu_timer[dev].counter32b;
+            TIMER_DEV->CHANNEL[TIMER_1_COUNTER_CH].LDVAL = cu_timer[dev].diff;
+            pit_timer_start(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+        default:
+            return -1;
+    }
+
+    DEBUG("cntr: %lu, value: %u, diff: %lu\n",
+          cu_timer[dev].counter32b, value, cu_timer[dev].diff);
+
+    return 0;
+}
+
+int timer_clear(tim_t dev, int channel)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            cu_timer[dev].counter32b = timer_read(dev);
+            cu_timer[dev].diff = 0;
+            pit_timer_set_max(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            cu_timer[dev].counter32b = timer_read(dev);
+            cu_timer[dev].diff = 0;
+            pit_timer_set_max(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+        default:
+            return -1;
+    }
+
+    DEBUG("clear\n");
+
+    return 0;
+}
+
+unsigned int timer_read(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            return pit_timer_read(dev, TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            return pit_timer_read(dev, TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+        default:
+            return 0;
+    }
+}
+
+void timer_start(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            pit_timer_start(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            pit_timer_start(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+            break;
+    }
+}
+
+void timer_stop(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            pit_timer_stop(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            pit_timer_stop(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+            break;
+    }
+}
+
+void timer_irq_enable(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            NVIC_EnableIRQ(TIMER_0_IRQ_CHAN);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            NVIC_EnableIRQ(TIMER_1_IRQ_CHAN);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+            break;
+    }
+}
+
+void timer_irq_disable(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            NVIC_DisableIRQ(TIMER_0_IRQ_CHAN);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            NVIC_DisableIRQ(TIMER_1_IRQ_CHAN);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+            break;
+    }
+}
+
+void timer_reset(tim_t dev)
+{
+    switch (dev) {
+#if TIMER_0_EN
+
+        case TIMER_0:
+            pit_timer_set_max(TIMER_0_COUNTER_CH);
+            break;
+#endif
+#if TIMER_1_EN
+
+        case TIMER_1:
+            pit_timer_set_max(TIMER_1_COUNTER_CH);
+            break;
+#endif
+
+        case TIMER_UNDEFINED:
+            break;
+    }
+}
+
+inline static void pit_timer_irq_handler(tim_t dev, uint8_t ch)
+{
+    cu_timer[dev].counter32b += TIMER_DEV->CHANNEL[ch].LDVAL;
+
+    TIMER_DEV->CHANNEL[ch].TFLG = PIT_TFLG_TIF_MASK;
+
+    if (cu_timer[dev].diff) {
+        if (config[dev].cb != NULL) {
+            config[dev].cb(0);
+        }
+    }
+
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+}
+
+#if TIMER_0_EN
+void TIMER_0_ISR(void)
+{
+    pit_timer_irq_handler(TIMER_0, TIMER_0_COUNTER_CH);
+}
+#endif
+
+#if TIMER_1_EN
+void TIMER_1_ISR(void)
+{
+    pit_timer_irq_handler(TIMER_1, TIMER_1_COUNTER_CH);
+}
+#endif
+
+#endif
diff --git a/cpu/kinetis_common/uart.c b/cpu/kinetis_common/uart.c
new file mode 100644
index 0000000000..2dda61d89d
--- /dev/null
+++ b/cpu/kinetis_common/uart.c
@@ -0,0 +1,360 @@
+/*
+ * Copyright (C) 2014 PHYTEC Messtechnik GmbH
+ * 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     cpu_kinetis_common_uart
+ *
+ * @{
+ *
+ * @file
+ * @brief       Low-level UART driver implementation
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include <math.h>
+
+#include "cpu.h"
+#include "thread.h"
+#include "sched.h"
+#include "periph_conf.h"
+#include "periph/uart.h"
+
+#ifndef KINETIS_UART_ADVANCED
+/**
+ * Attempts to determine the type of the UART,
+ * using the BRFA field in the UART C4 register.
+ */
+#ifdef UART_C4_BRFA
+#define KINETIS_UART_ADVANCED    1
+#endif
+#endif
+
+/**
+ * @brief Each UART device has to store two callbacks.
+ */
+typedef struct {
+    uart_rx_cb_t rx_cb;
+    uart_tx_cb_t tx_cb;
+    void *arg;
+} uart_conf_t;
+
+/**
+ * @brief Unified interrupt handler for all UART devices
+ *
+ * @param uartnum       the number of the UART that triggered the ISR
+ * @param uart          the UART device that triggered the ISR
+ */
+static inline void irq_handler(uart_t uartnum, KINETIS_UART *uart);
+
+/**
+ * @brief Allocate memory to store the callback functions.
+ */
+static uart_conf_t config[UART_NUMOF];
+
+static inline void kinetis_set_brfa(KINETIS_UART *dev, uint32_t baudrate, uint32_t clk)
+{
+#if KINETIS_UART_ADVANCED
+    /* set baudrate fine adjust (brfa) */
+    uint8_t brfa = ((((4 * clk) / baudrate) + 1) / 2) % 32;
+    dev->C4 = UART_C4_BRFA(brfa);
+#endif
+}
+
+int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, uart_tx_cb_t tx_cb, void *arg)
+{
+    /* do basic initialization */
+    int res = uart_init_blocking(uart, baudrate);
+
+    if (res < 0) {
+        return res;
+    }
+
+    /* remember callback addresses */
+    config[uart].rx_cb = rx_cb;
+    config[uart].tx_cb = tx_cb;
+    config[uart].arg = arg;
+
+    /* enable receive interrupt */
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            NVIC_SetPriority(UART_0_IRQ_CHAN, UART_IRQ_PRIO);
+            NVIC_EnableIRQ(UART_0_IRQ_CHAN);
+            UART_0_DEV->C2 |= (1 << UART_C2_RIE_SHIFT);
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            NVIC_SetPriority(UART_1_IRQ_CHAN, UART_IRQ_PRIO);
+            NVIC_EnableIRQ(UART_1_IRQ_CHAN);
+            UART_1_DEV->C2 |= (1 << UART_C2_RIE_SHIFT);
+            break;
+#endif
+
+        default:
+            return -2;
+            break;
+    }
+
+    return 0;
+}
+
+int uart_init_blocking(uart_t uart, uint32_t baudrate)
+{
+    KINETIS_UART *dev;
+    PORT_Type *port;
+    uint32_t clk;
+    uint16_t ubd;
+    uint8_t tx_pin = 0;
+    uint8_t rx_pin = 0;
+    uint8_t af;
+
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            dev = UART_0_DEV;
+            port = UART_0_PORT;
+            clk = UART_0_CLK;
+            tx_pin = UART_0_TX_PIN;
+            rx_pin = UART_0_RX_PIN;
+            af = UART_0_AF;
+            UART_0_PORT_CLKEN();
+            UART_0_CLKEN();
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            dev = UART_1_DEV;
+            port = UART_1_PORT;
+            clk = UART_1_CLK;
+            tx_pin = UART_1_TX_PIN;
+            rx_pin = UART_1_RX_PIN;
+            af = UART_1_AF;
+            UART_1_PORT_CLKEN();
+            UART_1_CLKEN();
+            break;
+#endif
+
+        default:
+            return -1;
+    }
+
+    /* configure RX and TX pins, set pin to use alternative function mode */
+    port->PCR[rx_pin] = PORT_PCR_MUX(af);
+    port->PCR[tx_pin] = PORT_PCR_MUX(af);
+
+    /* disable transmitter and receiver */
+    dev->C2 &= ~(1 << UART_C2_TE_SHIFT | 1 << UART_C2_RE_SHIFT);
+    /* set defaults, 8-bit mode, no parity */
+    dev->C1 = 0;
+
+    /* calculate baudrate */
+    ubd = (uint16_t)(clk / (baudrate * 16));
+
+    /* set baudrate */
+    dev->BDH = (uint8_t)UART_BDH_SBR(ubd >> 8);
+    dev->BDL = (uint8_t)UART_BDL_SBR(ubd);
+    kinetis_set_brfa(dev, baudrate, clk);
+
+    /* enable transmitter and receiver */
+    dev->C2 |= (1 << UART_C2_TE_SHIFT | 1 << UART_C2_RE_SHIFT);
+    return 0;
+}
+
+void uart_tx_begin(uart_t uart)
+{
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            UART_0_DEV->C2 |= (1 << UART_C2_TIE_SHIFT);
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            UART_1_DEV->C2 |= (1 << UART_C2_TIE_SHIFT);
+            break;
+#endif
+
+        default:
+            break;
+    }
+}
+
+void uart_tx_end(uart_t uart)
+{
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            UART_0_DEV->C2 &= ~(1 << UART_C2_TIE_SHIFT);
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            UART_1_DEV->C2 &= ~(1 << UART_C2_TIE_SHIFT);
+            break;
+#endif
+
+        default:
+            break;
+    }
+}
+
+int uart_write(uart_t uart, char data)
+{
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            if (UART_0_DEV->S1 & UART_S1_TDRE_MASK) {
+                UART_0_DEV->D = (uint8_t)data;
+            }
+
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            if (UART_1_DEV->S1 & UART_S1_TDRE_MASK) {
+                UART_1_DEV->D = (uint8_t)data;
+            }
+
+            break;
+#endif
+
+        default:
+            return -2;
+            break;
+    }
+
+    return 0;
+}
+
+int uart_read_blocking(uart_t uart, char *data)
+{
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            while (!(UART_0_DEV->S1 & UART_S1_RDRF_MASK));
+
+            *data = (char)UART_0_DEV->D;
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            while (!(UART_1_DEV->S1 & UART_S1_RDRF_MASK));
+
+            *data = (char)UART_1_DEV->D;
+            break;
+#endif
+
+        default:
+            return -2;
+            break;
+    }
+
+    return 1;
+}
+
+int uart_write_blocking(uart_t uart, char data)
+{
+    switch (uart) {
+#if UART_0_EN
+
+        case UART_0:
+            while (!(UART_0_DEV->S1 & UART_S1_TDRE_MASK));
+
+            UART_0_DEV->D = (uint8_t)data;
+            break;
+#endif
+#if UART_1_EN
+
+        case UART_1:
+            while (!(UART_1_DEV->S1 & UART_S1_TDRE_MASK));
+
+            UART_1_DEV->D = (uint8_t)data;
+            break;
+#endif
+
+        default:
+            return -2;
+            break;
+    }
+
+    return 1;
+}
+
+#if UART_0_EN
+void UART_0_ISR(void)
+{
+    irq_handler(UART_0, UART_0_DEV);
+}
+#endif
+
+#if UART_1_EN
+void UART_1_ISR(void)
+{
+    irq_handler(UART_1, UART_1_DEV);
+}
+#endif
+
+static inline void irq_handler(uart_t uartnum, KINETIS_UART *dev)
+{
+    /*
+    * On Cortex-M0, it happens that S1 is read with LDR
+    * instruction instead of LDRB. This will read the data register
+    * at the same time and arrived byte will be lost. Maybe it's a GCC bug.
+    *
+    * Observed with: arm-none-eabi-gcc (4.8.3-8+..)
+    * It does not happen with: arm-none-eabi-gcc (4.8.3-9+11)
+    */
+
+    if (dev->S1 & UART_S1_RDRF_MASK) {
+        /* RDRF flag will be cleared when dev-D was read */
+        uint8_t data = dev->D;
+
+        if (config[uartnum].rx_cb != NULL) {
+            config[uartnum].rx_cb(config[uartnum].arg, data);
+        }
+    }
+
+    if (dev->S1 & UART_S1_TDRE_MASK) {
+        if (config[uartnum].tx_cb == NULL) {
+            dev->C2 &= ~(UART_C2_TIE_MASK);
+        }
+        else if (config[uartnum].tx_cb(config[uartnum].arg) == 0) {
+            dev->C2 &= ~(UART_C2_TIE_MASK);
+        }
+    }
+
+#if (KINETIS_UART_ADVANCED == 0)
+    /* clear overrun flag */
+    if (dev->S1 & UART_S1_OR_MASK) {
+        dev->S1 = UART_S1_OR_MASK;
+    }
+#endif
+
+    if (sched_context_switch_request) {
+        thread_yield();
+    }
+
+}
-- 
GitLab