From 3291b27a989971ddd4e26fc411ea5d699c527e53 Mon Sep 17 00:00:00 2001
From: Johann F <j.fischer@phytec.de>
Date: Sat, 23 May 2015 09:44:20 +0200
Subject: [PATCH] boards/frdm-k64f: initial import for the Freescale FRDM-K64F
 Board

---
 boards/frdm-k64f/Makefile              |   4 +
 boards/frdm-k64f/Makefile.dep          |   0
 boards/frdm-k64f/Makefile.features     |  12 +
 boards/frdm-k64f/Makefile.include      |  32 +++
 boards/frdm-k64f/board.c               |  53 ++++
 boards/frdm-k64f/dist/openocd.cfg      |  50 ++++
 boards/frdm-k64f/include/board.h       | 103 ++++++++
 boards/frdm-k64f/include/periph_conf.h | 348 +++++++++++++++++++++++++
 8 files changed, 602 insertions(+)
 create mode 100644 boards/frdm-k64f/Makefile
 create mode 100644 boards/frdm-k64f/Makefile.dep
 create mode 100644 boards/frdm-k64f/Makefile.features
 create mode 100644 boards/frdm-k64f/Makefile.include
 create mode 100644 boards/frdm-k64f/board.c
 create mode 100644 boards/frdm-k64f/dist/openocd.cfg
 create mode 100644 boards/frdm-k64f/include/board.h
 create mode 100644 boards/frdm-k64f/include/periph_conf.h

diff --git a/boards/frdm-k64f/Makefile b/boards/frdm-k64f/Makefile
new file mode 100644
index 0000000000..37891de8e6
--- /dev/null
+++ b/boards/frdm-k64f/Makefile
@@ -0,0 +1,4 @@
+# tell the Makefile.base which module to build
+MODULE = $(BOARD)_base
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/frdm-k64f/Makefile.dep b/boards/frdm-k64f/Makefile.dep
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/boards/frdm-k64f/Makefile.features b/boards/frdm-k64f/Makefile.features
new file mode 100644
index 0000000000..079a2edb76
--- /dev/null
+++ b/boards/frdm-k64f/Makefile.features
@@ -0,0 +1,12 @@
+FEATURES_PROVIDED += cpp
+FEATURES_PROVIDED += periph_gpio
+FEATURES_PROVIDED += periph_uart
+FEATURES_PROVIDED += periph_spi
+FEATURES_PROVIDED += periph_i2c
+FEATURES_PROVIDED += periph_pwm
+FEATURES_PROVIDED += periph_adc
+FEATURES_PROVIDED += periph_rtt
+FEATURES_PROVIDED += periph_rtc
+FEATURES_PROVIDED += periph_random
+FEATURES_PROVIDED += periph_cpuid
+FEATURES_MCU_GROUP = cortex_m4
diff --git a/boards/frdm-k64f/Makefile.include b/boards/frdm-k64f/Makefile.include
new file mode 100644
index 0000000000..53e3e97053
--- /dev/null
+++ b/boards/frdm-k64f/Makefile.include
@@ -0,0 +1,32 @@
+# define the cpu used by the FRDM-K64F board
+export CPU = k64f
+export CPU_MODEL = mk64fn1m0vll12
+
+# set default port depending on operating system
+PORT_LINUX ?= /dev/ttyACM0
+
+.PHONY: flash
+flash: $(RIOTCPU)/kinetis_common/dist/wdog-disable.bin
+
+# Reset the default goal.
+.DEFAULT_GOAL :=
+
+export FFLAGS = flash-elf
+export TUI = 1
+# We need special handling of the watchdog if we want to speed up the flash
+# verification by using the MCU to compute the image checksum after flashing.
+# wdog-disable.bin is a precompiled binary which will disable the watchdog and
+# return control to the debugger (OpenOCD)
+export OPENOCD_PRE_VERIFY_CMDS += \
+  -c 'load_image $(RIOTCPU)/kinetis_common/dist/wdog-disable.bin 0x20000000 bin' \
+  -c 'resume 0x20000000'
+export OPENOCD_EXTRA_INIT
+export PRE_FLASH_CHECK_SCRIPT = $(RIOTCPU)/kinetis_common/dist/check-fcfield-elf.sh
+
+include $(RIOTBOARD)/$(BOARD)/Makefile.dep
+# setup serial terminal
+include $(RIOTBOARD)/Makefile.include.serial
+# this board uses openocd
+include $(RIOTBOARD)/Makefile.include.openocd
+# include cortex defaults
+include $(RIOTBOARD)/Makefile.include.cortexm_common
diff --git a/boards/frdm-k64f/board.c b/boards/frdm-k64f/board.c
new file mode 100644
index 0000000000..56b38649e1
--- /dev/null
+++ b/boards/frdm-k64f/board.c
@@ -0,0 +1,53 @@
+/*
+ * 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     board_frdm-k64f
+ * @{
+ *
+ * @file
+ * @brief       Board specific implementations for the FRDM-K64F
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ *
+ * @}
+ */
+
+#include "board.h"
+
+static void leds_init(void);
+
+void board_init(void)
+{
+    leds_init();
+    cpu_init();
+}
+
+/**
+ * @brief Initialize the boards on-board RGB-LED
+ *
+ */
+static void leds_init(void)
+{
+    /* enable clock */
+    LED_B_PORT_CLKEN();
+    LED_G_PORT_CLKEN();
+    LED_R_PORT_CLKEN();
+    /* configure pins as gpio */
+    LED_B_PORT->PCR[LED_B_PIN] = PORT_PCR_MUX(1);
+    LED_G_PORT->PCR[LED_G_PIN] = PORT_PCR_MUX(1);
+    LED_R_PORT->PCR[LED_R_PIN] = PORT_PCR_MUX(1);
+    LED_B_GPIO->PDDR |= (1 << LED_B_PIN);
+    LED_G_GPIO->PDDR |= (1 << LED_G_PIN);
+    LED_R_GPIO->PDDR |= (1 << LED_R_PIN);
+    /* turn all LEDs off */
+    LED_B_GPIO->PSOR |= (1 << LED_B_PIN);
+    LED_G_GPIO->PSOR |= (1 << LED_G_PIN);
+    LED_R_GPIO->PSOR |= (1 << LED_R_PIN);
+}
diff --git a/boards/frdm-k64f/dist/openocd.cfg b/boards/frdm-k64f/dist/openocd.cfg
new file mode 100644
index 0000000000..10b7b1c0d8
--- /dev/null
+++ b/boards/frdm-k64f/dist/openocd.cfg
@@ -0,0 +1,50 @@
+#
+# Freescale Kinetis k64f devices
+#
+source [find interface/cmsis-dap.cfg]
+
+#
+# k64f devices support both JTAG and SWD transports.
+#
+source [find target/swj-dp.tcl]
+
+if { [info exists CHIPNAME] } {
+    set _CHIPNAME $CHIPNAME
+} else {
+    set _CHIPNAME k64f
+}
+
+if { [info exists CPUTAPID] } {
+    set _CPUTAPID $CPUTAPID
+} else {
+    set _CPUTAPID 0x2ba01477
+}
+
+set _TARGETNAME $_CHIPNAME.cpu
+
+swj_newdap $_CHIPNAME cpu -irlen 4 -expected-id $_CPUTAPID
+
+target create $_TARGETNAME cortex_m -chain-position $_CHIPNAME.cpu
+
+$_CHIPNAME.cpu configure -event examine-start { puts "START..." ; }
+
+# It is important that "kinetis mdm check_security" is called for
+# 'examine-end' event and not 'eximine-start'. Calling it in 'examine-start'
+# causes "kinetis mdm check_security" to fail the first time openocd
+# calls it when it tries to connect after the CPU has been power-cycled.
+$_CHIPNAME.cpu configure -event examine-end {
+    kinetis mdm check_security
+}
+
+$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size 0x1000 -work-area-backup 0
+
+flash bank $_CHIPNAME.flash kinetis 0 0 0 0 $_TARGETNAME
+
+cortex_m reset_config sysresetreq
+#reset_config srst_only srst_nogate connect_assert_srst
+
+adapter_khz 1000
+
+$_TARGETNAME configure -event gdb-attach {
+  halt
+}
diff --git a/boards/frdm-k64f/include/board.h b/boards/frdm-k64f/include/board.h
new file mode 100644
index 0000000000..8b3b05e62d
--- /dev/null
+++ b/boards/frdm-k64f/include/board.h
@@ -0,0 +1,103 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * 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    board_frdm-k64f Freescale FRDM-K64F Board
+ * @ingroup     boards
+ * @brief       Board specific implementations for the FRDM-K64F
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the FRDM-K64F
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ */
+
+#ifndef __BOARD_H
+#define __BOARD_H
+
+#include "cpu.h"
+#include "periph_conf.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**
+ * Define the nominal CPU core clock in this board
+ */
+#define F_CPU               CLOCK_CORECLOCK
+
+/**
+ * @name Define UART device and baudrate for stdio
+ * @{
+ */
+#define STDIO               UART_0
+#define STDIO_RX_BUFSIZE    (64U)
+#define STDIO_BAUDRATE      (115200U)
+/** @} */
+
+/**
+ * @name LED pin definitions
+ * @{
+ */
+#define LED_R_PORT_CLKEN()    (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK)) /**< Clock Enable for PORTD*/
+#define LED_G_PORT_CLKEN()    (SIM->SCGC5 |= (SIM_SCGC5_PORTE_MASK)) /**< Clock Enable for PORTD*/
+#define LED_B_PORT_CLKEN()    (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK)) /**< Clock Enable for PORTA*/
+#define LED_R_PORT            PORTB /**< PORT for Red LED*/
+#define LED_R_GPIO            GPIOB /**< GPIO-Device for Red LED*/
+#define LED_G_PORT            PORTE /**< PORT for Green LED*/
+#define LED_G_GPIO            GPIOE /**< GPIO-Device for Green LED*/
+#define LED_B_PORT            PORTB /**< PORT for Blue LED*/
+#define LED_B_GPIO            GPIOB /**< GPIO-Device for Blue LED*/
+#define LED_R_PIN             22    /**< Red LED connected to PINx*/
+#define LED_G_PIN             26    /**< Green LED connected to PINx*/
+#define LED_B_PIN             21    /**< Blue LED connected to PINx*/
+/** @} */
+
+/**
+ * @name Macros for controlling the on-board LEDs.
+ * @{
+ */
+#define LED_B_ON            (LED_B_GPIO->PCOR |= (1 << LED_B_PIN))
+#define LED_B_OFF           (LED_B_GPIO->PSOR |= (1 << LED_B_PIN))
+#define LED_B_TOGGLE        (LED_B_GPIO->PTOR |= (1 << LED_B_PIN))
+#define LED_G_ON            (LED_G_GPIO->PCOR |= (1 << LED_G_PIN))
+#define LED_G_OFF           (LED_G_GPIO->PSOR |= (1 << LED_G_PIN))
+#define LED_G_TOGGLE        (LED_G_GPIO->PTOR |= (1 << LED_G_PIN))
+#define LED_R_ON            (LED_R_GPIO->PCOR |= (1 << LED_R_PIN))
+#define LED_R_OFF           (LED_R_GPIO->PSOR |= (1 << LED_R_PIN))
+#define LED_R_TOGGLE        (LED_R_GPIO->PTOR |= (1 << LED_R_PIN))
+
+/* for compatability to other boards */
+#define LED_GREEN_ON        LED_G_ON
+#define LED_GREEN_OFF       LED_G_OFF
+#define LED_GREEN_TOGGLE    LED_G_TOGGLE
+#define LED_RED_ON          LED_R_ON
+#define LED_RED_OFF         LED_R_OFF
+#define LED_RED_TOGGLE      LED_R_TOGGLE
+/** @} */
+
+/**
+ * Define the type for the radio packet length for the transceiver
+ */
+typedef uint8_t radio_packet_length_t;
+
+/**
+ * @brief Initialize board specific hardware, including clock, LEDs and std-IO
+ */
+void board_init(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /** __BOARD_H */
+/** @} */
diff --git a/boards/frdm-k64f/include/periph_conf.h b/boards/frdm-k64f/include/periph_conf.h
new file mode 100644
index 0000000000..ccdd824cfc
--- /dev/null
+++ b/boards/frdm-k64f/include/periph_conf.h
@@ -0,0 +1,348 @@
+/*
+ * Copyright (C) 2014 Freie Universität Berlin
+ * 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     board_frdm-k64f
+ * @{
+ *
+ * @file
+ * @name        Peripheral MCU configuration for the FRDM-K64F
+ *
+ * @author      Johann Fischer <j.fischer@phytec.de>
+ */
+
+#ifndef __PERIPH_CONF_H
+#define __PERIPH_CONF_H
+
+#include "cpu_conf.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**
+ * @name Clock system configuration
+ * @{
+ */
+#define KINETIS_CPU_USE_MCG          1
+
+#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        6           /* ERC devider = 1280 */
+#define KINETIS_MCG_ERC_RANGE        2
+#define KINETIS_MCG_ERC_FREQ         50000000
+#define KINETIS_MCG_PLL_PRDIV        19          /* divide factor = 20 */
+#define KINETIS_MCG_PLL_VDIV0        0           /* multiply factor = 24 */
+#define KINETIS_MCG_PLL_FREQ         60000000
+
+#define CLOCK_CORECLOCK              KINETIS_MCG_PLL_FREQ
+/** @} */
+
+
+/**
+ * @name Timer configuration
+ * @{
+ */
+#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
+/** @} */
+
+/**
+* @name UART configuration
+* @{
+*/
+#define UART_NUMOF                   (1U)
+#define UART_0_EN                    1
+#define UART_IRQ_PRIO                1
+#define UART_CLK                     CLOCK_CORECLOCK
+
+/* UART 0 device configuration */
+#define KINETIS_UART                 UART_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_RX_TX_IRQn
+#define UART_0_ISR                   isr_uart0_rx_tx
+/* UART 0 pin configuration */
+#define UART_0_PORT_CLKEN()          (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK))
+#define UART_0_PORT                  PORTB
+#define UART_0_RX_PIN                16
+#define UART_0_TX_PIN                17
+#define UART_0_AF                    3
+/** @} */
+
+/**
+ * @name ADC configuration
+ * @{
+ */
+#define ADC_NUMOF                    (1U)
+#define ADC_0_EN                     1
+#define ADC_MAX_CHANNELS             6
+
+/* ADC 0 configuration */
+#define ADC_0_DEV                    ADC1
+#define ADC_0_MODULE_CLOCK           CLOCK_CORECLOCK
+#define ADC_0_CHANNELS               6
+#define ADC_0_CLKEN()                (SIM->SCGC3 |= (SIM_SCGC3_ADC1_MASK))
+#define ADC_0_CLKDIS()               (SIM->SCGC3 &= ~(SIM_SCGC3_ADC1_MASK))
+#define ADC_0_PORT_CLKEN()           (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK | SIM_SCGC5_PORTC_MASK))
+/* ADC 0 channel 0 pin config */
+#define ADC_0_CH0_PORT               PORTB
+#define ADC_0_CH0_PIN                10
+#define ADC_0_CH0_PIN_AF             0
+#define ADC_0_CH0                    14
+/* ADC 0 channel 1 pin config */
+#define ADC_0_CH1_PORT               PORTB
+#define ADC_0_CH1_PIN                11
+#define ADC_0_CH1_PIN_AF             0
+#define ADC_0_CH1                    15
+/* ADC 0 channel 2 pin config */
+#define ADC_0_CH2_PORT               PORTC
+#define ADC_0_CH2_PIN                11
+#define ADC_0_CH2_PIN_AF             0
+#define ADC_0_CH2                    7
+/* ADC 0 channel 3 pin config */
+#define ADC_0_CH3_PORT               PORTC
+#define ADC_0_CH3_PIN                10
+#define ADC_0_CH3_PIN_AF             0
+#define ADC_0_CH3                    6
+/* ADC 0 channel 4 pin config */
+#define ADC_0_CH4_PORT               PORTC
+#define ADC_0_CH4_PIN                8
+#define ADC_0_CH4_PIN_AF             0
+#define ADC_0_CH4                    4
+/* ADC 0 channel 5 pin config */
+#define ADC_0_CH5_PORT               PORTC
+#define ADC_0_CH5_PIN                9
+#define ADC_0_CH5_PIN_AF             0
+#define ADC_0_CH5                    5
+/** @} */
+
+/**
+* @name PWM configuration
+* @{
+*/
+#define PWM_NUMOF                    (1U)
+#define PWM_0_EN                     1
+#define PWM_MAX_CHANNELS             8
+#define PWM_MAX_VALUE                0xffff
+
+/* PWM 0 device configuration */
+#define PWM_0_DEV                    FTM0
+#define PWM_0_CHANNELS               4
+#define PWM_0_CLK                    CLOCK_CORECLOCK
+#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_PORTA_MASK | SIM_SCGC5_PORTC_MASK))
+/* Arduino Connector D3 */
+#define PWM_0_PORT_CH0               PORTA
+#define PWM_0_PIN_CH0                1
+#define PWM_0_FTMCHAN_CH0            6
+#define PWM_0_PIN_AF_CH0             3
+/* Arduino Connector D5 */
+#define PWM_0_PORT_CH1               PORTA
+#define PWM_0_PIN_CH1                2
+#define PWM_0_FTMCHAN_CH1            7
+#define PWM_0_PIN_AF_CH1             3
+/* Arduino Connector D6 */
+#define PWM_0_PORT_CH2               PORTC
+#define PWM_0_PIN_CH2                2
+#define PWM_0_FTMCHAN_CH2            1
+#define PWM_0_PIN_AF_CH2             4
+/* Arduino Connector D7 */
+#define PWM_0_PORT_CH3               PORTC
+#define PWM_0_PIN_CH3                3
+#define PWM_0_FTMCHAN_CH3            2
+#define PWM_0_PIN_AF_CH3             4
+/** @} */
+
+
+/**
+* @name SPI configuration
+* @{
+*/
+#define SPI_NUMOF                    (1U)
+#define SPI_0_EN                     1
+#define SPI_IRQ_PRIO                 1
+#define KINETIS_SPI_USE_HW_CS        1
+
+/* 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                   CLOCK_CORECLOCK
+
+/* SPI 0 pin configuration */
+#define SPI_0_PORT                   PORTD
+#define SPI_0_PORT_CLKEN()           (SIM->SCGC5 |= (SIM_SCGC5_PORTD_MASK))
+#define SPI_0_AF                     2
+
+#define SPI_0_PCS0_PIN               0
+#define SPI_0_SCK_PIN                1
+#define SPI_0_SOUT_PIN               2
+#define SPI_0_SIN_PIN                3
+
+#define SPI_0_PCS0_ACTIVE_LOW        1
+/** @} */
+
+
+/**
+* @name I2C configuration
+* @{
+*/
+#define I2C_NUMOF                    (1U)
+#define I2C_CLK                      CLOCK_CORECLOCK
+#define I2C_0_EN                     1
+#define I2C_IRQ_PRIO                 1
+/* Low (10 kHz): MUL = 4, SCL divider = 2560, total: 10240 */
+#define KINETIS_I2C_F_ICR_LOW        (0x3D)
+#define KINETIS_I2C_F_MULT_LOW       (2)
+/* Normal (100 kHz): MUL = 2, SCL divider = 240, total: 480 */
+#define KINETIS_I2C_F_ICR_NORMAL     (0x1F)
+#define KINETIS_I2C_F_MULT_NORMAL    (1)
+/* Fast (400 kHz): MUL = 1, SCL divider = 128, total: 128 */
+#define KINETIS_I2C_F_ICR_FAST       (0x17)
+#define KINETIS_I2C_F_MULT_FAST      (0)
+/* Fast plus (1000 kHz): MUL = 1, SCL divider = 48, total: 48 */
+#define KINETIS_I2C_F_ICR_FAST_PLUS  (0x10)
+#define KINETIS_I2C_F_MULT_FAST_PLUS (0)
+
+/* I2C 0 device configuration */
+#define I2C_0_DEV                    I2C0
+#define I2C_0_CLKEN()                (SIM->SCGC4 |= (SIM_SCGC4_I2C0_MASK))
+#define I2C_0_CLKDIS()               (SIM->SCGC4 &= ~(SIM_SCGC4_I2C0_MASK))
+#define I2C_0_IRQ                    I2C0_IRQn
+#define I2C_0_IRQ_HANDLER            isr_i2c0
+/* 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                 5
+#define I2C_0_SDA_PIN                25
+#define I2C_0_SCL_PIN                24
+#define I2C_0_PORT_CFG               (PORT_PCR_MUX(I2C_0_PIN_AF) | PORT_PCR_ODE_MASK)
+/** @} */
+
+/**
+ * @name GPIO configuration
+ * @{
+ */
+#define GPIO_0_EN                    1
+#define GPIO_1_EN                    1
+#define GPIO_2_EN                    1
+#define GPIO_3_EN                    1
+#define GPIO_4_EN                    1
+#define GPIO_5_EN                    1
+#define GPIO_IRQ_PRIO                1
+#define ISR_PORT_A                   isr_porta
+#define ISR_PORT_B                   isr_portb
+#define ISR_PORT_C                   isr_portc
+#define ISR_PORT_D                   isr_portd
+
+/* GPIO channel 0 config */
+#define GPIO_0_DEV                   GPIOB   /* LED_R */
+#define GPIO_0_PORT                  PORTB
+#define GPIO_0_PORT_BASE             PORTB_BASE
+#define GPIO_0_PIN                   22
+#define GPIO_0_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK))
+#define GPIO_0_IRQ                   PORTB_IRQn
+/* GPIO channel 1 config */
+#define GPIO_1_DEV                   GPIOE   /* LED_G */
+#define GPIO_1_PORT                  PORTE
+#define GPIO_1_PORT_BASE             PORTE_BASE
+#define GPIO_1_PIN                   26
+#define GPIO_1_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTE_MASK))
+#define GPIO_1_IRQ                   PORTE_IRQn
+/* GPIO channel 2 config */
+#define GPIO_2_DEV                   GPIOB   /* LED_B */
+#define GPIO_2_PORT                  PORTB
+#define GPIO_2_PORT_BASE             PORTB_BASE
+#define GPIO_2_PIN                   21
+#define GPIO_2_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK))
+#define GPIO_2_IRQ                   PORTB_IRQn
+/* GPIO channel 3 config */
+#define GPIO_3_DEV                   GPIOC   /* SW2 */
+#define GPIO_3_PORT                  PORTC
+#define GPIO_3_PORT_BASE             PORTC_BASE
+#define GPIO_3_PIN                   6
+#define GPIO_3_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTC_MASK))
+#define GPIO_3_IRQ                   PORTC_IRQn
+/* GPIO channel 4 config */
+#define GPIO_4_DEV                   GPIOB   /* A0 (Arduino Headers) */
+#define GPIO_4_PORT                  PORTB
+#define GPIO_4_PORT_BASE             PORTB_BASE
+#define GPIO_4_PIN                   2
+#define GPIO_4_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK))
+#define GPIO_4_IRQ                   PORTB_IRQn
+/* GPIO channel 5 config */
+#define GPIO_5_DEV                   GPIOB   /* A1 (Arduino Headers) */
+#define GPIO_5_PORT                  PORTB
+#define GPIO_5_PORT_BASE             PORTB_BASE
+#define GPIO_5_PIN                   3
+#define GPIO_5_CLKEN()               (SIM->SCGC5 |= (SIM_SCGC5_PORTB_MASK))
+#define GPIO_5_IRQ                   PORTB_IRQn
+/** @} */
+
+/**
+* @name RTT and RTC configuration
+* @{
+*/
+#define RTT_NUMOF                    (1U)
+#define RTC_NUMOF                    (1U)
+#define RTT_DEV                      RTC
+#define RTT_IRQ                      RTC_IRQn
+#define RTT_IRQ_PRIO                 10
+#define RTT_UNLOCK()                 (SIM->SCGC6 |= (SIM_SCGC6_RTC_MASK))
+#define RTT_ISR                      isr_rtc
+#define RTT_FREQUENCY                (1)
+#define RTT_MAX_VALUE                (0xffffffff)
+/** @} */
+
+/**
+ * @name Random Number Generator configuration
+ * @{
+ */
+#define RANDOM_NUMOF                 (1U)
+#define KINETIS_RNGA                 RNG
+#define RANDOM_CLKEN()               (SIM->SCGC6 |= (1 << 9))
+#define RANDOM_CLKDIS()              (SIM->SCGC6 &= ~(1 << 9))
+
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __PERIPH_CONF_H */
+/** @} */
-- 
GitLab