From a45d6263543b8681ad3c2bdca83582ad3cb7bcd4 Mon Sep 17 00:00:00 2001
From: Bas Stottelaar <basstottelaar@gmail.com>
Date: Mon, 13 Nov 2017 16:09:23 +0100
Subject: [PATCH] boards: sltb001a: add support for thunderboard sense

---
 boards/sltb001a/Makefile              |   4 +
 boards/sltb001a/Makefile.dep          |  10 ++
 boards/sltb001a/Makefile.features     |  14 ++
 boards/sltb001a/Makefile.include      |  14 ++
 boards/sltb001a/board.c               | 110 +++++++++++++
 boards/sltb001a/include/board.h       | 212 +++++++++++++++++++++++++
 boards/sltb001a/include/gpio_params.h |  63 ++++++++
 boards/sltb001a/include/periph_conf.h | 215 ++++++++++++++++++++++++++
 8 files changed, 642 insertions(+)
 create mode 100644 boards/sltb001a/Makefile
 create mode 100644 boards/sltb001a/Makefile.dep
 create mode 100644 boards/sltb001a/Makefile.features
 create mode 100644 boards/sltb001a/Makefile.include
 create mode 100644 boards/sltb001a/board.c
 create mode 100644 boards/sltb001a/include/board.h
 create mode 100644 boards/sltb001a/include/gpio_params.h
 create mode 100644 boards/sltb001a/include/periph_conf.h

diff --git a/boards/sltb001a/Makefile b/boards/sltb001a/Makefile
new file mode 100644
index 0000000000..6529affda2
--- /dev/null
+++ b/boards/sltb001a/Makefile
@@ -0,0 +1,4 @@
+# tell the Makefile.base which module to build
+MODULE = board
+
+include $(RIOTBASE)/Makefile.base
diff --git a/boards/sltb001a/Makefile.dep b/boards/sltb001a/Makefile.dep
new file mode 100644
index 0000000000..351a0725e8
--- /dev/null
+++ b/boards/sltb001a/Makefile.dep
@@ -0,0 +1,10 @@
+ifneq (,$(filter saul_default,$(USEMODULE)))
+    USEMODULE += saul_gpio
+    USEMODULE += bmp280
+    USEMODULE += si7021
+endif
+
+# i2c is required for environmental sensors
+USEMODULE += periph_i2c
+
+include $(RIOTCPU)/efr32mg1p/Makefile.dep
diff --git a/boards/sltb001a/Makefile.features b/boards/sltb001a/Makefile.features
new file mode 100644
index 0000000000..7fb29867ee
--- /dev/null
+++ b/boards/sltb001a/Makefile.features
@@ -0,0 +1,14 @@
+# Put defined MCU peripherals here (in alphabetical order)
+FEATURES_PROVIDED += periph_adc
+FEATURES_PROVIDED += periph_gpio
+FEATURES_PROVIDED += periph_i2c
+FEATURES_PROVIDED += periph_rtc
+FEATURES_PROVIDED += periph_rtt
+FEATURES_PROVIDED += periph_spi
+FEATURES_PROVIDED += periph_timer
+FEATURES_PROVIDED += periph_uart
+
+# The board MPU family (used for grouping by the CI system)
+FEATURES_MCU_GROUP = cortex_m4_2
+
+include $(RIOTCPU)/efr32mg1p/Makefile.features
diff --git a/boards/sltb001a/Makefile.include b/boards/sltb001a/Makefile.include
new file mode 100644
index 0000000000..2b891d80f9
--- /dev/null
+++ b/boards/sltb001a/Makefile.include
@@ -0,0 +1,14 @@
+# define the cpu used by SLTB001A
+export CPU = efr32mg1p
+export CPU_MODEL = efr32mg1p132f256gm48
+
+# set default port depending on operating system
+PORT_LINUX ?= /dev/ttyACM0
+PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*)))
+
+# setup JLink for flashing
+export JLINK_DEVICE := EFR32MG1PxxxF256
+include $(RIOTMAKE)/tools/jlink.inc.mk
+
+# setup serial terminal
+include $(RIOTMAKE)/tools/serial.inc.mk
diff --git a/boards/sltb001a/board.c b/boards/sltb001a/board.c
new file mode 100644
index 0000000000..c4ec0fe0f9
--- /dev/null
+++ b/boards/sltb001a/board.c
@@ -0,0 +1,110 @@
+/*
+ * Copyright (C) 2015-2017 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     boards_sltb001a
+ * @{
+ *
+ * @file
+ * @brief       Board specific implementations SLTB001A board
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Bas Stottelaar <basstottelaar@gmail.com>
+ *
+ * @}
+ */
+
+#include "board.h"
+#include "cpu.h"
+
+#include "periph/gpio.h"
+#include "periph/i2c.h"
+
+#if BMP280_ENABLED || CCS811_ENABLED || ICM_20648_ENABLED || \
+    SI1133_ENABLED || SI7021_ENABLED || SI7210A_ENABLED || \
+    RGB_LED1_ENABLED || RGB_LED2_ENABLED || RGB_LED3_ENABLED || \
+    RGB_LED4_ENABLED
+static inline void board_usleep(uint32_t delay)
+{
+    /* decrement + compare take two cycles, therefore divide by two */
+    uint32_t count = (delay * (SystemCoreClock / 1000 / 1000)) / 2;
+
+    while (count--) {}
+}
+
+static void board_pic_init(void)
+{
+    gpio_init(PIC_INT_WAKE_PIN, GPIO_OD);
+    gpio_set(PIC_INT_WAKE_PIN);
+
+    i2c_init_master(PIC_I2C, I2C_SPEED_NORMAL);
+}
+
+static void board_pic_write(uint8_t addr, uint8_t value)
+{
+    /* toggle the pin for 4 us */
+    gpio_clear(PIC_INT_WAKE_PIN);
+    board_usleep(4);
+
+    /* write to gpio expander */
+    i2c_acquire(PIC_I2C);
+    uint8_t bytes[] = { addr, value };
+    i2c_write_bytes(PIC_I2C, PIC_I2C_ADDR, bytes, 2);
+    i2c_release(PIC_I2C);
+
+    /* put PIC in sleep mode again */
+    gpio_set(PIC_INT_WAKE_PIN);
+}
+#endif
+
+void board_init(void)
+{
+    /* initialize the CPU */
+    cpu_init();
+
+    /* initialize the LEDs */
+    gpio_init(LED0_PIN, GPIO_OUT);
+    gpio_init(LED1_PIN, GPIO_OUT);
+
+    /* initialize the push buttons */
+    gpio_init(PB0_PIN, GPIO_IN);
+    gpio_init(PB1_PIN, GPIO_IN);
+
+    /* initialize the environmental sensors (multiple ones) */
+#if BMP280_ENABLED || CCS811_ENABLED || ICM_20648_ENABLED || \
+    SI1133_ENABLED || SI7021_ENABLED || SI7210A_ENABLED || \
+    RGB_LED1_ENABLED || RGB_LED2_ENABLED || RGB_LED3_ENABLED || \
+    RGB_LED4_ENABLED
+    board_pic_init();
+#endif
+
+    /* enable the CCS811 air quality/gas sensor */
+#if CCS811_ENABLED
+    board_pic_write(CCS811_PIC_ADDR, (1 << CCS811_PIC_EN_BIT) | (1 << CCS811_PIC_WAKE_BIT));
+#endif
+
+    /* enable the IMU sensor */
+#if ICM_20648_ENABLED
+    board_pic_write(ICM20648_PIC_ADDR, 1 << ICM20648_PIC_EN_BIT);
+#endif
+
+    /* enable the environmental sensors */
+#if BMP280_ENABLED || SI1133_ENABLED || SI7021_ENABLED || SI7210A_ENABLED
+    board_pic_write(ENV_SENSE_PIC_ADDR, 1 << ENV_SENSE_PIC_BIT);
+#endif
+
+    /* enable the RGB leds */
+#if RGB_LED1_ENABLED || RGB_LED2_ENABLED || RGB_LED3_ENABLED || RGB_LED4_ENABLED
+    board_pic_write(RGB_LED_ADDR,
+        (1 << RGB_LED_EN_BIT) |
+        (RGB_LED1_ENABLED << RGB_LED1_EN_BIT) |
+        (RGB_LED2_ENABLED << RGB_LED2_EN_BIT) |
+        (RGB_LED3_ENABLED << RGB_LED3_EN_BIT) |
+        (RGB_LED4_ENABLED << RGB_LED4_EN_BIT));
+#endif
+}
diff --git a/boards/sltb001a/include/board.h b/boards/sltb001a/include/board.h
new file mode 100644
index 0000000000..4fd5322b97
--- /dev/null
+++ b/boards/sltb001a/include/board.h
@@ -0,0 +1,212 @@
+/*
+ * Copyright (C) 2015-2017 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @defgroup    boards_sltb001a Silicon Labs SLTB001A starter kit
+ * @ingroup     boards
+ * @brief       Support for the Silicon Labs SLTB001A starter kit
+ * @{
+ *
+ * @file
+ * @brief       Board specific definitions for the SLTB001A starter kit
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Bas Stottelaar <basstottelaar@gmail.com>
+ */
+
+#ifndef BOARD_H
+#define BOARD_H
+
+#include "cpu.h"
+
+#include "periph_conf.h"
+#include "periph/gpio.h"
+#include "periph/spi.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @name    Xtimer configuration
+ *
+ * The timer runs at 250 KHz to increase accuracy.
+ * @{
+ */
+#define XTIMER_HZ           (250000UL)
+#define XTIMER_WIDTH        (16)
+/** @} */
+
+/**
+ * @name    Push button pin definitions
+ * @{
+ */
+#define PB0_PIN             GPIO_PIN(PD, 14)
+#define PB1_PIN             GPIO_PIN(PD, 15)
+/** @} */
+
+/**
+ * @name    LED pin definitions
+ * @{
+ */
+#define LED0_PIN            GPIO_PIN(PD, 12)
+#define LED1_PIN            GPIO_PIN(PD, 11)
+/** @} */
+
+/**
+ * @name    Macros for controlling the on-board LEDs
+ * @{
+ */
+#define LED0_ON             gpio_set(LED0_PIN)
+#define LED0_OFF            gpio_clear(LED0_PIN)
+#define LED0_TOGGLE         gpio_toggle(LED0_PIN)
+#define LED1_ON             gpio_set(LED1_PIN)
+#define LED1_OFF            gpio_clear(LED1_PIN)
+#define LED1_TOGGLE         gpio_toggle(LED1_PIN)
+/** @} */
+
+/**
+ * @name    Environmental sensors configuration
+ *
+ * Pin for enabling environmental sensors (BMP280, Si1133, Si7021, Si7210A).
+ * @{
+ */
+#define ENV_SENSE_PIC_ADDR  (0x01)
+#define ENV_SENSE_PIC_BIT   (0)
+/** @} */
+
+/**
+ * @name    Pressure sensor configuration
+ *
+ * Connection to the on-board pressure sensor (BMP280).
+ * @{
+ */
+#ifndef BMP280_ENABLED
+#define BMP280_ENABLED          (1)
+#endif
+#define BMP280_I2C              I2C_DEV(0)
+
+#define BMX280_PARAM_I2C_DEV    BMP280_I2C
+/** @} */
+
+/**
+ * @name    Air quality/gas sensor configuration
+ *
+ * Connection to the on-board air quality/gas sensor (CCS811).
+ * @{
+ */
+#ifndef CCS811_ENABLED
+#define CCS811_ENABLED      (0)
+#endif
+#define CCS811_I2C          I2C_DEV(0)
+#define CCS811_PIC_ADDR     (0x03)
+#define CCS811_PIC_EN_BIT   (0x00)
+#define CCS811_PIC_WAKE_BIT (0x01)
+/** @} */
+
+/**
+ * @name    IMU sensor configuration
+ *
+ * Connection to the on-board IMU sensor (ICM-20648).
+ * @{
+ */
+#ifndef ICM20648_ENABLED
+#define ICM20648_ENABLED    (0)
+#endif
+#define ICM20648_SPI        SPI_DEV(0)
+#define ICM20648_PIC_ADDR   (0x00)
+#define ICM20648_PIC_EN_BIT (0x00)
+/** @} */
+
+/**
+ * @name    Power and Interrupt controller
+ *
+ * Pin for communication with the Power and Interrupt Controller.
+ * @{
+ */
+#define PIC_INT_WAKE_PIN    GPIO_PIN(PD, 10)
+#define PIC_I2C             I2C_DEV(0)
+#define PIC_I2C_ADDR        (0x48)
+/** @} */
+
+/**
+ * @name    RGB leds configuration
+ *
+ * There are four RGB leds on the board.
+ * @{
+ */
+#ifndef RGB_LED1_ENABLED
+#define RGB_LED1_ENABLED    (1)
+#endif
+#ifndef RGB_LED2_ENABLED
+#define RGB_LED2_ENABLED    (1)
+#endif
+#ifndef RGB_LED3_ENABLED
+#define RGB_LED3_ENABLED    (1)
+#endif
+#ifndef RGB_LED4_ENABLED
+#define RGB_LED4_ENABLED    (1)
+#endif
+#define RGB_LED_ADDR        (0x04)
+#define RGB_LED_EN_BIT      (0x00)
+#define RGB_LED1_EN_BIT     (0x07)
+#define RGB_LED2_EN_BIT     (0x06)
+#define RGB_LED3_EN_BIT     (0x05)
+#define RGB_LED4_EN_BIT     (0x04)
+/** @} */
+
+/**
+ * @name    UV/Ambient sensor configuration
+ *
+ * Connection to the on-board UV/ambient light sensor (Si1133).
+ * @{
+ */
+#ifndef SI1133_ENABLED
+#define SI1133_ENABLED      (0)
+#endif
+#define SI1133_I2C          I2C_DEV(0)
+/** @} */
+
+/**
+ * @name    Temperature sensor configuration
+ *
+ * Connection to the on-board temperature/humidity sensor (Si7021).
+ * @{
+ */
+#ifndef SI7021_ENABLED
+#define SI7021_ENABLED          (1)
+#endif
+#define SI7021_I2C              I2C_DEV(0)
+
+#define SI70XX_PARAM_I2C_DEV    SI7021_I2C
+/** @} */
+
+/**
+ * @name    Hall-effect sensor configuration
+ *
+ * Connection to the on-board hall-effect sensor (Si7210A). Available on Rev. A02
+ * boards only.
+ * @{
+ */
+#ifndef SI7210A_ENABLED
+#define SI7210A_ENABLED     (0)
+#endif
+#define SI7210A_I2C         I2C_DEV(0)
+/** @} */
+
+/**
+ * @brief   Initialize the board (GPIO, sensors, clocks).
+ */
+void board_init(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* BOARD_H */
+/** @} */
diff --git a/boards/sltb001a/include/gpio_params.h b/boards/sltb001a/include/gpio_params.h
new file mode 100644
index 0000000000..fde408fbe3
--- /dev/null
+++ b/boards/sltb001a/include/gpio_params.h
@@ -0,0 +1,63 @@
+/*
+ * Copyright (C) 2016-2017 Bas Stottelaar <basstottelaar@gmail.com>
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     boards_sltb001a
+ * @{
+ *
+ * @file
+ * @brief       Board specific configuration of direct mapped GPIOs
+ *
+ * @author      Bas Stottelaar <basstottelaar@gmail.com>
+ */
+
+#ifndef GPIO_PARAMS_H
+#define GPIO_PARAMS_H
+
+#include "board.h"
+#include "saul/periph.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief    GPIO pin configuration
+ */
+static const  saul_gpio_params_t saul_gpio_params[] =
+{
+    {
+        .name = "LED 0",
+        .pin = LED0_PIN,
+        .mode = GPIO_OUT
+    },
+    {
+        .name = "LED 1",
+        .pin = LED1_PIN,
+        .mode = GPIO_OUT
+    },
+    {
+        .name = "Button 1",
+        .pin = PB0_PIN,
+        .mode = GPIO_IN_PU,
+        .flags = SAUL_GPIO_INVERTED
+    },
+    {
+        .name = "Button 2",
+        .pin = PB1_PIN,
+        .mode = GPIO_IN_PU,
+        .flags = SAUL_GPIO_INVERTED
+    }
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* GPIO_PARAMS_H */
+/** @} */
diff --git a/boards/sltb001a/include/periph_conf.h b/boards/sltb001a/include/periph_conf.h
new file mode 100644
index 0000000000..b54d77f406
--- /dev/null
+++ b/boards/sltb001a/include/periph_conf.h
@@ -0,0 +1,215 @@
+/*
+ * Copyright (C) 2015-2017 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     boards_sltb001a
+ * @{
+ *
+ * @file
+ * @brief       Configuration of CPU peripherals for the SLTB001A starter kit
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ * @author      Bas Stottelaar <basstottelaar@gmail.com>
+ */
+
+#ifndef PERIPH_CONF_H
+#define PERIPH_CONF_H
+
+#include "cpu.h"
+
+#include "periph_cpu.h"
+
+#include "em_cmu.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief   Internal macro to calculate *_NUMOF based on config.
+ */
+#define PERIPH_NUMOF(config)    (sizeof(config) / sizeof(config[0]))
+
+/**
+ * @name    Clock configuration
+ * @{
+ */
+#ifndef CLOCK_HF
+#define CLOCK_HF            cmuSelect_HFXO
+#endif
+#ifndef CLOCK_CORE_DIV
+#define CLOCK_CORE_DIV      cmuClkDiv_1
+#endif
+#ifndef CLOCK_LFA
+#define CLOCK_LFA           cmuSelect_LFXO
+#endif
+#ifndef CLOCK_LFB
+#define CLOCK_LFB           cmuSelect_LFXO
+#endif
+#ifndef CLOCK_LFE
+#define CLOCK_LFE           cmuSelect_LFXO
+#endif
+/** @} */
+
+/**
+ * @name    ADC configuration
+ * @{
+ */
+static const adc_conf_t adc_config[] = {
+    {
+        .dev = ADC0,
+        .cmu = cmuClock_ADC0,
+    }
+};
+
+static const adc_chan_conf_t adc_channel_config[] = {
+    {
+        .dev = 0,
+        .input = adcPosSelTEMP,
+        .reference = adcRef1V25,
+        .acq_time = adcAcqTime8
+    },
+    {
+        .dev = 0,
+        .input = adcPosSelAVDD,
+        .reference = adcRef5V,
+        .acq_time = adcAcqTime8
+    }
+};
+
+#define ADC_DEV_NUMOF       PERIPH_NUMOF(adc_config)
+#define ADC_NUMOF           PERIPH_NUMOF(adc_channel_config)
+/** @} */
+
+/**
+ * @name    I2C configuration
+ * @{
+ */
+static const i2c_conf_t i2c_config[] = {
+    {
+        .dev = I2C0,
+        .sda_pin = GPIO_PIN(PC, 10),
+        .scl_pin = GPIO_PIN(PC, 11),
+        .loc = I2C_ROUTELOC0_SDALOC_LOC15 |
+               I2C_ROUTELOC0_SCLLOC_LOC15,
+        .cmu = cmuClock_I2C0,
+        .irq = I2C0_IRQn
+
+    }
+};
+
+#define I2C_NUMOF           PERIPH_NUMOF(i2c_config)
+#define I2C_0_ISR           isr_i2c0
+/** @} */
+
+/**
+ * @brief   RTC configuration
+ */
+#define RTC_NUMOF           (1U)
+
+/**
+ * @name    RTT configuration
+ * @{
+ */
+#define RTT_NUMOF           (1U)
+
+#define RTT_MAX_VALUE       (0xFFFFFFFF)
+#define RTT_FREQUENCY       (1U)
+/** @} */
+
+/**
+ * @name    SPI configuration
+ * @{
+ */
+static const spi_dev_t spi_config[] = {
+    {
+        .dev = USART1,
+        .mosi_pin = GPIO_PIN(PC, 6),
+        .miso_pin = GPIO_PIN(PC, 7),
+        .clk_pin = GPIO_PIN(PC, 8),
+        .loc = USART_ROUTELOC0_RXLOC_LOC11 |
+               USART_ROUTELOC0_TXLOC_LOC11 |
+               USART_ROUTELOC0_CLKLOC_LOC11,
+        .cmu = cmuClock_USART1,
+        .irq = USART1_RX_IRQn
+    }
+};
+
+#define SPI_NUMOF           PERIPH_NUMOF(spi_config)
+/** @} */
+
+/**
+ * @name    Timer configuration
+ *
+ * The implementation uses two timers in cascade mode.
+ * @{
+ */
+static const timer_conf_t timer_config[] = {
+    {
+        {
+            .dev = TIMER0,
+            .cmu = cmuClock_TIMER0
+        },
+        {
+            .dev = TIMER1,
+            .cmu = cmuClock_TIMER1
+        },
+        .irq = TIMER1_IRQn
+    }
+};
+
+#define TIMER_NUMOF         PERIPH_NUMOF(timer_config)
+#define TIMER_0_ISR         isr_timer1
+/** @} */
+
+/**
+ * @name    UART configuration
+ * @{
+ */
+static const uart_conf_t uart_config[] = {
+    {
+        .dev = USART0,
+        .rx_pin = GPIO_PIN(PA, 1),
+        .tx_pin = GPIO_PIN(PA, 0),
+        .loc = USART_ROUTELOC0_RXLOC_LOC0 |
+               USART_ROUTELOC0_TXLOC_LOC0,
+        .cmu = cmuClock_USART0,
+        .irq = USART0_RX_IRQn
+    },
+    {
+        .dev = USART1,
+        .rx_pin = GPIO_PIN(PC, 6),
+        .tx_pin = GPIO_PIN(PC, 7),
+        .loc = USART_ROUTELOC0_RXLOC_LOC11 |
+               USART_ROUTELOC0_TXLOC_LOC11,
+        .cmu = cmuClock_USART1,
+        .irq = USART1_RX_IRQn
+    },
+    {
+        .dev = LEUART0,
+        .rx_pin = GPIO_PIN(PD, 11),
+        .tx_pin = GPIO_PIN(PD, 10),
+        .loc = LEUART_ROUTELOC0_RXLOC_LOC18 |
+               LEUART_ROUTELOC0_TXLOC_LOC18,
+        .cmu = cmuClock_LEUART0,
+        .irq = LEUART0_IRQn
+    }
+};
+
+#define UART_NUMOF          PERIPH_NUMOF(uart_config)
+#define UART_0_ISR_RX       isr_usart0_rx
+#define UART_1_ISR_RX       isr_usart1_rx
+#define UART_2_ISR_RX       isr_leuart0
+/** @} */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PERIPH_CONF_H */
+/** @} */
-- 
GitLab