1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-12-28 16:01:18 +01:00

cpu: efm32_common: add peripheral drivers

This commit is contained in:
Bas Stottelaar 2017-11-13 16:08:08 +01:00
parent 5eaf1985c5
commit 0537e50614
24 changed files with 2576 additions and 0 deletions

View File

@ -0,0 +1,7 @@
# define the module that is build
MODULE = efm32_common
# add a list of subdirectories, that should also be build
DIRS = periph
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,7 @@
ifneq (,$(filter periph_rtc,$(USEMODULE)))
USEMODULE += periph_rtc_series$(CPU_SERIES)
endif
ifneq (,$(filter periph_rtt,$(USEMODULE)))
USEMODULE += periph_rtt_series$(CPU_SERIES)
endif

View File

@ -0,0 +1,3 @@
FEATURES_PROVIDED += periph_cpuid
FEATURES_PROVIDED += periph_flashpage
FEATURES_PROVIDED += periph_pm

View File

@ -0,0 +1,20 @@
# the em_device.h header requires a global define with the cpu model
export CFLAGS += -D$(shell echo $(CPU_MODEL) | tr 'a-z' 'A-Z')
# include emlib package
USEPKG += emlib
# include efm32 common
USEMODULE += efm32_common
# include common periph module
USEMODULE += periph_common
# include efm32 common periph drivers
USEMODULE += efm32_common_periph
# include layered power management
USEMODULE += pm_layered
# export the common include directory
export INCLUDES += -I$(RIOTCPU)/efm32_common/include

123
cpu/efm32_common/cpu.c Normal file
View File

@ -0,0 +1,123 @@
/*
* 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 cpu_efm32_common
* @{
*
* @file
* @brief Implementation of the CPU initialization
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/init.h"
#include "em_chip.h"
#include "em_cmu.h"
#include "em_emu.h"
#ifdef _SILICON_LABS_32B_SERIES_1
/**
* @brief Initialize integrated DC-DC regulator
*/
static void dcdc_init(void)
{
EMU_DCDCInit_TypeDef init_dcdc = EMU_DCDCINIT_DEFAULT;
EMU_DCDCInit(&init_dcdc);
}
#endif
/**
* @brief Configure clock sources and the CPU frequency
*
* On a EFM32 CPU, there are two options for selecting the main clock
* source, using an external clock source (HFXO), or using the internal RC
* oscillator (HFRCO, enabled by default).
*
* The clocks for the LFA, LFB, LFE and HFPER are also configured.
*/
static void clk_init(void)
{
CMU_HFXOInit_TypeDef init_hfxo = CMU_HFXOINIT_DEFAULT;
/* initialize HFXO with board-specific parameters before switching */
if (CLOCK_HF == cmuSelect_HFXO) {
CMU_HFXOInit(&init_hfxo);
}
/* set the HF clock source */
CMU_ClockSelectSet(cmuClock_HF, CLOCK_HF);
CMU_ClockDivSet(cmuClock_CORE, CLOCK_CORE_DIV);
/* disable the HFRCO if external crystal is used */
if (CLOCK_HF == cmuSelect_HFXO) {
CMU_OscillatorEnable(cmuOsc_HFRCO, false, false);
}
/* set the LFA clock source */
CMU_ClockSelectSet(cmuClock_LFA, CLOCK_LFA);
/* set the LFB clock source */
CMU_ClockSelectSet(cmuClock_LFB, CLOCK_LFB);
/* set the LFE clock source */
#ifdef _SILICON_LABS_32B_SERIES_1
CMU_ClockSelectSet(cmuClock_LFE, CLOCK_LFE);
#endif
}
/**
* @brief Initialize sleep modes
*
* The EFM32 has several energy saving modes (EM0 - EM4), of which deeper
* modes save more energy.s
*/
static void pm_init(void)
{
/* initialize EM2 and EM3 */
EMU_EM23Init_TypeDef init_em23 = EMU_EM23INIT_DEFAULT;
EMU_EM23Init(&init_em23);
#ifdef _SILICON_LABS_32B_SERIES_1
/* initialize EM4 */
EMU_EM4Init_TypeDef init_em4 = EMU_EM4INIT_DEFAULT;
EMU_EM4Init(&init_em4);
#endif
}
void cpu_init(void)
{
/* apply errata that may be applicable (see em_chip.h) */
CHIP_Init();
/* initialize the Cortex-M core */
cortexm_init();
#ifdef _SILICON_LABS_32B_SERIES_1
/* initialize dc-dc */
dcdc_init();
#endif
/* initialize clock sources and generic clocks */
clk_init();
/* initialize power management interface */
pm_init();
/* trigger static peripheral initialization */
periph_init();
}

5
cpu/efm32_common/doc.txt Normal file
View File

@ -0,0 +1,5 @@
/**
* @defgroup cpu_efm32_common Silicon Labs Exx32 MCU
* @ingroup cpu
* @brief Common implementations for the Exx32 family of CPUs
*/

View File

@ -0,0 +1,344 @@
/*
* 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 cpu_efm32_common
* @{
*
* @file
* @brief CPU specific definitions for internal peripheral handling
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Bas Stottelaar <basstottelaar@gmail.com>
*/
#ifndef PERIPH_CPU_H
#define PERIPH_CPU_H
#include "mutex.h"
#include "cpu_conf.h"
#include "em_adc.h"
#include "em_cmu.h"
#include "em_device.h"
#include "em_gpio.h"
#include "em_usart.h"
#ifdef _SILICON_LABS_32B_SERIES_0
#include "em_dac.h"
#endif
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Enable support for Low-power peripherals (if supported by CPU).
* @{
*/
#ifndef LOW_POWER_ENABLED
#define LOW_POWER_ENABLED (1)
#endif
/** @} */
/**
* @brief Internal macro for combining ADC resolution (x) with number of
* shifts (y).
*/
#define ADC_MODE(x, y) ((y << 4) | x)
/**
* @brief Internal define to note that resolution is not supported.
*/
#define ADC_MODE_UNDEF (0xff)
#ifndef DOXYGEN
/**
* @brief Possible ADC resolution settings
* @{
*/
#define HAVE_ADC_RES_T
typedef enum {
ADC_RES_6BIT = ADC_MODE(adcRes6Bit, 0), /**< ADC resolution: 6 bit */
ADC_RES_8BIT = ADC_MODE(adcRes8Bit, 0), /**< ADC resolution: 8 bit */
ADC_RES_10BIT = ADC_MODE(adcRes12Bit, 2), /**< ADC resolution: 10 bit (shifted from 12 bit) */
ADC_RES_12BIT = ADC_MODE(adcRes12Bit, 0), /**< ADC resolution: 12 bit */
ADC_RES_14BIT = ADC_MODE_UNDEF, /**< ADC resolution: 14 bit (unsupported) */
ADC_RES_16BIT = ADC_MODE_UNDEF, /**< ADC resolution: 16 bit (unsupported) */
} adc_res_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief ADC device configuration
*/
typedef struct {
ADC_TypeDef *dev; /**< ADC device used */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
} adc_conf_t;
/**
* @brief ADC channel configuration
*/
typedef struct {
uint8_t dev; /**< device index */
#ifdef _SILICON_LABS_32B_SERIES_0
ADC_SingleInput_TypeDef input; /**< input channel */
#else
ADC_PosSel_TypeDef input; /**< input channel */
#endif
ADC_Ref_TypeDef reference; /**< channel voltage reference */
ADC_AcqTime_TypeDef acq_time; /**< channel acquisition time */
} adc_chan_conf_t;
/**
* @brief Length of CPU ID in octets.
*/
#define CPUID_LEN (8U)
#if defined(DAC_COUNT) && DAC_COUNT > 0
/**
* @brief DAC device configuration
*/
typedef struct {
DAC_TypeDef *dev; /**< DAC device used */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
} dac_conf_t;
/**
* @brief DAC channel configuration
*/
typedef struct {
uint8_t dev; /**< device index */
uint8_t index; /**< channel index */
DAC_Ref_TypeDef ref; /**< channel voltage reference */
} dac_chan_conf_t;
#endif
/**
* @brief Define a custom type for GPIO pins.
* @{
*/
#define HAVE_GPIO_T
typedef uint32_t gpio_t;
/** @} */
/**
* @brief Definition of a fitting UNDEF value.
*/
#define GPIO_UNDEF (0xffffffff)
/**
* @brief Mandatory function for defining a GPIO pins.
*/
#define GPIO_PIN(x, y) ((gpio_t) ((x << 4) | y))
/**
* @brief Internal macro for combining pin mode (x) and pull-up/down (y).
*/
#define GPIO_MODE(x, y) ((x << 1) | y)
/**
* @brief Available ports on the EFM32.
*/
enum {
PA = gpioPortA, /**< port A */
PB = gpioPortB, /**< port B */
PC = gpioPortC, /**< port C */
PD = gpioPortD, /**< port D */
#if _GPIO_PORT_E_PIN_COUNT
PE = gpioPortE, /**< port E */
#endif
PF = gpioPortF /**< port F */
};
#ifndef DOXYGEN
/**
* @brief Override direction values.
* @{
*/
#define HAVE_GPIO_MODE_T
typedef enum {
GPIO_IN = GPIO_MODE(gpioModeInput, 0), /**< pin as input */
GPIO_IN_PD = GPIO_MODE(gpioModeInputPull, 0), /**< pin as input with pull-down */
GPIO_IN_PU = GPIO_MODE(gpioModeInputPull, 1), /**< pin as input with pull-up */
GPIO_OUT = GPIO_MODE(gpioModePushPull, 0), /**< pin as output */
GPIO_OD = GPIO_MODE(gpioModeWiredAnd, 1), /**< pin as open-drain */
GPIO_OD_PU = GPIO_MODE(gpioModeWiredAndPullUp, 1), /**< pin as open-drain with pull-up */
} gpio_mode_t;
/** @} */
/**
* @brief Override active flank configuration values.
* @{
*/
#define HAVE_GPIO_FLANK_T
typedef enum {
GPIO_FALLING = 2, /**< emit interrupt on falling flank */
GPIO_RISING = 1, /**< emit interrupt on rising flank */
GPIO_BOTH = 3 /**< emit interrupt on both flanks */
} gpio_flank_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief Override hardware crypto supported methods.
* @{
*/
#define HAVE_HWCRYPTO_AES128
#ifdef AES_CTRL_AES256
#define HAVE_HWCRYPTO_AES256
#endif
#ifdef _SILICON_LABS_32B_SERIES_1
#define HAVE_HWCRYPTO_SHA1
#define HAVE_HWCRYPTO_SHA256
#endif
/** @} */
#ifndef DOXYGEN
/**
* @brief Override I2C speed values.
* @{
*/
#define HAVE_I2C_SPEED_T
typedef enum {
I2C_SPEED_LOW = 10000, /**< low speed mode: ~10kbit/s */
I2C_SPEED_NORMAL = 100000, /**< normal mode: ~100kbit/s */
I2C_SPEED_FAST = 400000, /**< fast mode: ~400kbit/sj */
I2C_SPEED_FAST_PLUS = 1000000, /**< fast plus mode: ~1Mbit/s */
I2C_SPEED_HIGH = 3400000, /**< high speed mode: ~3.4Mbit/s */
} i2c_speed_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief I2C device configuration.
*/
typedef struct {
I2C_TypeDef *dev; /**< USART device used */
gpio_t sda_pin; /**< pin used for SDA */
gpio_t scl_pin; /**< pin used for SCL */
uint32_t loc; /**< location of I2C pins */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
IRQn_Type irq; /**< the devices base IRQ channel */
} i2c_conf_t;
/**
* @brief PWM channel configuration.
*/
typedef struct {
uint8_t index; /**< TIMER channel to use */
gpio_t pin; /**< pin used for pwm */
uint32_t loc; /**< location of the pin */
} pwm_chan_conf_t;
/**
* @brief PWM device configuration.
*/
typedef struct {
TIMER_TypeDef *dev; /**< TIMER device used */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
IRQn_Type irq; /**< the devices base IRQ channel */
uint8_t channels; /**< the number of available channels */
const pwm_chan_conf_t* channel; /**< pointer to first channel config */
} pwm_conf_t;
#ifndef DOXYGEN
/**
* @brief Override SPI clocks.
* @{
*/
#define HAVE_SPI_MODE_T
typedef enum {
SPI_MODE_0 = usartClockMode0,
SPI_MODE_1 = usartClockMode1,
SPI_MODE_2 = usartClockMode2,
SPI_MODE_3 = usartClockMode3
} spi_mode_t;
/** @} */
/**
* @brief Define a set of pre-defined SPI clock speeds.
* @{
*/
#define HAVE_SPI_CLK_T
typedef enum {
SPI_CLK_100KHZ = 100000, /**< drive the SPI bus with 100KHz */
SPI_CLK_400KHZ = 400000, /**< drive the SPI bus with 400KHz */
SPI_CLK_1MHZ = 1000000, /**< drive the SPI bus with 1MHz */
SPI_CLK_5MHZ = 5000000, /**< drive the SPI bus with 5MHz */
SPI_CLK_10MHZ = 10000000 /**< drive the SPI bus with 10MHz */
} spi_clk_t;
/** @} */
#endif /* ndef DOXYGEN */
/**
* @brief SPI device configuration.
*/
typedef struct {
USART_TypeDef *dev; /**< USART device used */
gpio_t mosi_pin; /**< pin used for MOSI */
gpio_t miso_pin; /**< pin used for MISO */
gpio_t clk_pin; /**< pin used for CLK */
uint32_t loc; /**< location of USART pins */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
IRQn_Type irq; /**< the devices base IRQ channel */
} spi_dev_t;
/**
* @brief Declare needed generic SPI functions.
* @{
*/
#define PERIPH_SPI_NEEDS_INIT_CS
#define PERIPH_SPI_NEEDS_TRANSFER_BYTE
#define PERIPH_SPI_NEEDS_TRANSFER_REG
#define PERIPH_SPI_NEEDS_TRANSFER_REGS
/** @} */
/**
* @brief Define timer configuration values
*
* @note The two timers must be adjacent to each other (e.g. TIMER0 and
* TIMER1, or TIMER2 and TIMER3, etc.).
* @{
*/
typedef struct {
TIMER_TypeDef *dev; /**< Timer device used */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
} timer_dev_t;
typedef struct {
timer_dev_t prescaler; /**< the lower numbered neighboring timer */
timer_dev_t timer; /**< the higher numbered timer */
IRQn_Type irq; /**< number of the higher timer IRQ channel */
} timer_conf_t;
/** @} */
/**
* @brief UART device configuration.
*/
typedef struct {
void *dev; /**< UART, USART or LEUART device used */
gpio_t rx_pin; /**< pin used for RX */
gpio_t tx_pin; /**< pin used for TX */
uint32_t loc; /**< location of USART pins */
CMU_Clock_TypeDef cmu; /**< the device CMU channel */
IRQn_Type irq; /**< the devices base IRQ channel */
} uart_conf_t;
/**
* @brief Number of usable power modes.
*/
#define PM_NUM_MODES (3U)
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CPU_H */
/** @} */

View File

@ -0,0 +1,3 @@
MODULE = efm32_common_periph
include $(RIOTMAKE)/periph.mk

View File

@ -0,0 +1,103 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_adc
* @{
*
* @file
* @brief Low-level ADC driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph_conf.h"
#include "periph/adc.h"
#include "em_cmu.h"
#include "em_adc.h"
static mutex_t adc_lock[ADC_DEV_NUMOF];
int adc_init(adc_t line)
{
/* check if line is valid */
if (line >= ADC_NUMOF) {
return -1;
}
uint8_t dev = adc_channel_config[line].dev;
assert(dev < ADC_DEV_NUMOF);
/* initialize lock */
mutex_init(&adc_lock[dev]);
/* enable clock */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(adc_config[dev].cmu, true);
/* reset and initialize peripheral */
ADC_Init_TypeDef init = ADC_INIT_DEFAULT;
init.timebase = ADC_TimebaseCalc(0);
init.prescale = ADC_PrescaleCalc(400000, 0);
ADC_Reset(adc_config[dev].dev);
ADC_Init(adc_config[dev].dev, &init);
return 0;
}
int adc_sample(adc_t line, adc_res_t res)
{
/* resolutions larger than 12 bits are not supported */
if (res == ADC_MODE_UNDEF) {
return -1;
}
uint8_t dev = adc_channel_config[line].dev;
/* lock device */
mutex_lock(&adc_lock[dev]);
/* setup channel */
ADC_InitSingle_TypeDef init = ADC_INITSINGLE_DEFAULT;
init.acqTime = adc_channel_config[line].acq_time;
init.reference = adc_channel_config[line].reference;
init.resolution = (ADC_Res_TypeDef) (res & 0xFF);
#ifdef _SILICON_LABS_32B_SERIES_0
init.input = adc_channel_config[line].input;
#else
init.posSel = adc_channel_config[line].input;
#endif
ADC_InitSingle(adc_config[dev].dev, &init);
/* start conversion and block until it completes */
ADC_Start(adc_config[dev].dev, adcStartSingle);
while (adc_config[dev].dev->STATUS & ADC_STATUS_SINGLEACT);
int result = ADC_DataSingleGet(adc_config[dev].dev);
/* for resolutions that are not really supported, shift the result (for
instance, 10 bit resolution is achieved by shifting a 12 bit sample). */
result = result >> (res >> 4);
/* unlock device */
mutex_unlock(&adc_lock[dev]);
return result;
}

View File

@ -0,0 +1,30 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_cpuid
* @{
*
* @file
* @brief Low-level CPUID driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "periph/cpuid.h"
#include "em_system.h"
void cpuid_get(void *id)
{
*(uint64_t *) id = SYSTEM_GetUnique();
}

View File

@ -0,0 +1,84 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_dac
* @{
*
* @file
* @brief Low-level DAC driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/dac.h"
#include "em_cmu.h"
#if defined(DAC_COUNT) && DAC_COUNT > 0
#include "em_dac.h"
#endif
int8_t dac_init(dac_t line)
{
/* check if device is valid */
if (line >= DAC_NUMOF) {
return -1;
}
uint8_t dev = dac_channel_config[line].dev;
/* enable clock */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(dac_config[dev].cmu, true);
/* reset and initialize peripheral */
DAC_Init_TypeDef init = DAC_INIT_DEFAULT;
DAC_Reset(dac_config[dev].dev);
DAC_Init(dac_config[dev].dev, &init);
/* initialize channel */
DAC_InitChannel_TypeDef init_channel = DAC_INITCHANNEL_DEFAULT;
init_channel.enable = true;
DAC_InitChannel(dac_config[dev].dev,
&init_channel,
dac_channel_config[line].index);
return 0;
}
void dac_set(dac_t line, uint16_t value)
{
uint8_t dev = dac_channel_config[line].dev;
DAC_ChannelOutputSet(dac_config[dev].dev,
dac_channel_config[line].index,
value & 0xfff);
}
void dac_poweron(dac_t line)
{
uint8_t dev = dac_channel_config[line].dev;
CMU_ClockEnable(dac_config[dev].cmu, true);
}
void dac_poweroff(dac_t line)
{
uint8_t dev = dac_channel_config[line].dev;
CMU_ClockEnable(dac_config[dev].cmu, false);
}

View File

@ -0,0 +1,40 @@
/*
* Copyright (C) 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 cpu_efm32_common
* @ingroup drivers_periph_flashpage
* @{
*
* @file
* @brief Low-level flash page driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "cpu.h"
#include "assert.h"
#include "periph/flashpage.h"
#include "em_msc.h"
void flashpage_write(int page, void *data)
{
assert(page < FLASHPAGE_NUMOF);
uint32_t *page_addr = (uint32_t *)flashpage_addr(page);
uint32_t *data_addr = (uint32_t *)data;
MSC_Init();
MSC_ErasePage(page_addr);
MSC_WriteWord(page_addr, data_addr, FLASHPAGE_SIZE);
MSC_Deinit();
}

View File

@ -0,0 +1,172 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_gpio
* @{
*
* @file
* @brief Low-level GPIO driver implementation
*
* @author Hauke Petersen <mail@haukepetersen.de>
* @author Ryan Kurte <ryankurte@gmail.com>
* @author Bas Stottelaar <basstottelaar@gmail.com>
*
* @}
*/
#include "cpu.h"
#include "periph/gpio.h"
#include "em_gpio.h"
/**
* @brief Number of external interrupt lines.
*/
#define NUMOF_IRQS (GPIO_PIN_MAX)
/**
* @brief Hold one interrupt context per interrupt line
*/
static gpio_isr_ctx_t isr_ctx[NUMOF_IRQS];
static inline GPIO_Port_TypeDef _port_num(gpio_t pin)
{
return ((pin & 0xf0) >> 4);
}
static inline uint32_t _pin_num(gpio_t pin)
{
return (pin & 0x0f);
}
static inline uint32_t _pin_mask(gpio_t pin)
{
return (1 << _pin_num(pin));
}
int gpio_init(gpio_t pin, gpio_mode_t mode)
{
/* check for valid pin */
if (pin == GPIO_UNDEF) {
return -1;
}
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(cmuClock_GPIO, true);
/* configure pin */
GPIO_PinModeSet(_port_num(pin), _pin_num(pin), mode >> 1, mode & 0x1);
#ifdef _SILICON_LABS_32B_SERIES_0
GPIO_DriveModeSet(_port_num(pin), gpioDriveModeStandard);
#endif
return 0;
}
int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
gpio_cb_t cb, void *arg)
{
int result = gpio_init(pin, mode);
if (result != 0) {
return result;
}
/* just in case, disable the interrupt for this pin */
GPIO_IntDisable(_pin_num(pin));
/* store interrupt callback */
isr_ctx[_pin_num(pin)].cb = cb;
isr_ctx[_pin_num(pin)].arg = arg;
/* enable interrupts */
GPIO_IntConfig(_port_num(pin), _pin_num(pin),
flank & GPIO_RISING, flank & GPIO_FALLING, true);
NVIC_ClearPendingIRQ(GPIO_EVEN_IRQn);
NVIC_ClearPendingIRQ(GPIO_ODD_IRQn);
NVIC_EnableIRQ(GPIO_EVEN_IRQn);
NVIC_EnableIRQ(GPIO_ODD_IRQn);
return 0;
}
void gpio_irq_enable(gpio_t pin)
{
GPIO_IntEnable(_pin_mask(pin));
}
void gpio_irq_disable(gpio_t pin)
{
GPIO_IntDisable(_pin_mask(pin));
}
int gpio_read(gpio_t pin)
{
return GPIO_PinInGet(_port_num(pin), _pin_num(pin));
}
void gpio_set(gpio_t pin)
{
GPIO_PinOutSet(_port_num(pin), _pin_num(pin));
}
void gpio_clear(gpio_t pin)
{
GPIO_PinOutClear(_port_num(pin), _pin_num(pin));
}
void gpio_toggle(gpio_t pin)
{
GPIO_PinOutToggle(_port_num(pin), _pin_num(pin));
}
void gpio_write(gpio_t pin, int value)
{
if (value) {
GPIO_PinOutSet(_port_num(pin), _pin_num(pin));
}
else {
GPIO_PinOutClear(_port_num(pin), _pin_num(pin));
}
}
/**
* @brief Actual interrupt handler for both even and odd pin index numbers.
*/
static void gpio_irq(void)
{
for (int i = 0; i < NUMOF_IRQS; i++) {
if (GPIO_IntGet() & (1 << i)) {
isr_ctx[i].cb(isr_ctx[i].arg);
GPIO_IntClear(1 << i);
}
}
cortexm_isr_end();
}
/**
* @brief External interrupt handler for even pin index numbers
*/
void isr_gpio_even(void)
{
gpio_irq();
}
/**
* @brief External interrupt handler for odd pin index numbers
*/
void isr_gpio_odd(void)
{
gpio_irq();
}

View File

@ -0,0 +1,64 @@
/*
* Copyright (C) 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 cpu_efm32_common
* @ingroup drivers_periph_hwrng
* @{
*
* @file
* @brief Low-level I2C driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/hwrng.h"
#include "em_cmu.h"
#include <string.h>
void hwrng_init(void)
{
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(cmuClock_TRNG0, true);
/* reset and initialize peripheral */
TRNG0->CONTROL = TRNG_CONTROL_ENABLE |
TRNG_CONTROL_REPCOUNTIEN |
TRNG_CONTROL_APT64IEN |
TRNG_CONTROL_APT4096IEN |
TRNG_CONTROL_PREIEN |
TRNG_CONTROL_ALMIEN;
/* wait for TRNG to become available */
while (TRNG0->FIFOLEVEL == 0) {}
}
void hwrng_read(void *buf, unsigned int num)
{
uint32_t *out_buf = (uint32_t *) buf;
uint32_t tmp;
/* read known good available data */
while (num >= 4) {
*out_buf++ = TRNG0->FIFO;
num -= 4;
}
/* read remaining data (not multiple of 4) */
if (num) {
tmp = TRNG0->FIFO;
memcpy((uint8_t *)out_buf, (const uint8_t *) &tmp, num);
}
}

View File

@ -0,0 +1,256 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_i2c
* @{
*
* @file
* @brief Low-level I2C driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph_conf.h"
#include "periph/i2c.h"
#include "periph/gpio.h"
/* emlib uses the same flags, undefine fist */
#undef I2C_FLAG_WRITE
#undef I2C_FLAG_READ
#include "em_cmu.h"
#include "em_i2c.h"
static volatile I2C_TransferReturn_TypeDef i2c_progress[I2C_NUMOF];
static mutex_t i2c_lock[I2C_NUMOF];
/**
* @brief Start and track an I2C transfer.
*/
static void _transfer(i2c_t dev, I2C_TransferSeq_TypeDef *transfer)
{
bool busy = true;
/* start the i2c transaction */
i2c_progress[dev] = I2C_TransferInit(i2c_config[dev].dev, transfer);
/* the transfer progresses via the interrupt handler */
while (busy) {
unsigned int cpsr = irq_disable();
if (i2c_progress[dev] == i2cTransferInProgress) {
cortexm_sleep_until_event();
}
else {
busy = false;
}
irq_restore(cpsr);
}
}
int i2c_init_master(i2c_t dev, i2c_speed_t speed)
{
/* check if device is valid */
if (dev >= I2C_NUMOF) {
return -1;
}
/* initialize lock */
mutex_init(&i2c_lock[dev]);
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(i2c_config[dev].cmu, true);
/* configure the pins */
gpio_init(i2c_config[dev].scl_pin, GPIO_OD);
gpio_init(i2c_config[dev].sda_pin, GPIO_OD);
/* ensure slave is in a known state, which it may not be after a reset */
for (int i = 0; i < 9; i++) {
gpio_set(i2c_config[dev].scl_pin);
gpio_clear(i2c_config[dev].scl_pin);
}
/* reset and initialize the peripheral */
I2C_Init_TypeDef init = I2C_INIT_DEFAULT;
init.enable = false;
init.freq = (uint32_t) speed;
I2C_Reset(i2c_config[dev].dev);
I2C_Init(i2c_config[dev].dev, &init);
/* configure pin functions */
#ifdef _SILICON_LABS_32B_SERIES_0
i2c_config[dev].dev->ROUTE = (i2c_config[dev].loc |
I2C_ROUTE_SDAPEN | I2C_ROUTE_SCLPEN);
#else
i2c_config[dev].dev->ROUTEPEN = I2C_ROUTEPEN_SDAPEN | I2C_ROUTEPEN_SCLPEN;
i2c_config[dev].dev->ROUTELOC0 = i2c_config[dev].loc;
#endif
/* enable interrupts */
NVIC_ClearPendingIRQ(i2c_config[dev].irq);
NVIC_EnableIRQ(i2c_config[dev].irq);
/* enable peripheral */
I2C_Enable(i2c_config[dev].dev, true);
return 0;
}
int i2c_acquire(i2c_t dev)
{
mutex_lock(&i2c_lock[dev]);
return 0;
}
int i2c_release(i2c_t dev)
{
mutex_unlock(&i2c_lock[dev]);
return 0;
}
int i2c_read_byte(i2c_t dev, uint8_t address, void *data)
{
return i2c_read_bytes(dev, address, data, 1);
}
int i2c_read_bytes(i2c_t dev, uint8_t address, void *data, int length)
{
I2C_TransferSeq_TypeDef transfer;
transfer.addr = (address << 1);
transfer.flags = I2C_FLAG_READ;
transfer.buf[0].data = (uint8_t *) data;
transfer.buf[0].len = length;
/* start a transfer */
_transfer(dev, &transfer);
if (i2c_progress[dev] != i2cTransferDone) {
return -2;
}
return length;
}
int i2c_read_reg(i2c_t dev, uint8_t address, uint8_t reg, void *data)
{
return i2c_read_regs(dev, address, reg, data, 1);
}
int i2c_read_regs(i2c_t dev, uint8_t address, uint8_t reg,
void *data, int length)
{
I2C_TransferSeq_TypeDef transfer;
transfer.addr = (address << 1);
transfer.flags = I2C_FLAG_WRITE_READ;
transfer.buf[0].data = &reg;
transfer.buf[0].len = 1;
transfer.buf[1].data = (uint8_t *) data;
transfer.buf[1].len = length;
/* start a transfer */
_transfer(dev, &transfer);
if (i2c_progress[dev] != i2cTransferDone) {
return -2;
}
return length;
}
int i2c_write_byte(i2c_t dev, uint8_t address, uint8_t data)
{
return i2c_write_bytes(dev, address, &data, 1);
}
int i2c_write_bytes(i2c_t dev, uint8_t address, const void *data, int length)
{
I2C_TransferSeq_TypeDef transfer;
transfer.addr = (address << 1);
transfer.flags = I2C_FLAG_WRITE;
transfer.buf[0].data = (uint8_t *) data;
transfer.buf[0].len = length;
/* start a transfer */
_transfer(dev, &transfer);
if (i2c_progress[dev] != i2cTransferDone) {
return -2;
}
return length;
}
int i2c_write_reg(i2c_t dev, uint8_t address, uint8_t reg, uint8_t data)
{
return i2c_write_regs(dev, address, reg, &data, 1);
}
int i2c_write_regs(i2c_t dev, uint8_t address, uint8_t reg,
const void *data, int length)
{
I2C_TransferSeq_TypeDef transfer;
transfer.addr = (address << 1);
transfer.flags = I2C_FLAG_WRITE_WRITE;
transfer.buf[0].data = &reg;
transfer.buf[0].len = 1;
transfer.buf[1].data = (uint8_t *) data;
transfer.buf[1].len = length;
/* start a transfer */
_transfer(dev, &transfer);
if (i2c_progress[dev] != i2cTransferDone) {
return -2;
}
return length;
}
void i2c_poweron(i2c_t dev)
{
CMU_ClockEnable(i2c_config[dev].cmu, true);
}
void i2c_poweroff(i2c_t dev)
{
CMU_ClockEnable(i2c_config[dev].cmu, false);
}
#ifdef I2C_0_ISR
void I2C_0_ISR(void)
{
i2c_progress[0] = I2C_Transfer(i2c_config[0].dev);
cortexm_isr_end();
}
#endif
#ifdef I2C_1_ISR
void I2C_1_ISR(void)
{
i2c_progress[1] = I2C_Transfer(i2c_config[1].dev);
cortexm_isr_end();
}
#endif

View File

@ -0,0 +1,41 @@
/*
* Copyright (C) 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 cpu_efm32_common
* @ingroup drivers_periph_pm
* @{
*
* @file
* @brief Implementation of the power management peripheral
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "periph/pm.h"
#include "em_emu.h"
void pm_set(unsigned mode)
{
switch (mode) {
case 0:
/* after exiting EM3, clocks are restored */
EMU_EnterEM3(true);
break;
case 1:
/* after exiting EM2, clocks are restored */
EMU_EnterEM2(true);
break;
case 2:
/* wait for next event or interrupt */
EMU_EnterEM1();
break;
}
}

View File

@ -0,0 +1,126 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_pwm
* @{
*
* @file
* @brief Low-level PWM peripheral driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/gpio.h"
#include "periph/pwm.h"
#include "em_cmu.h"
#include "em_timer.h"
#include "em_timer_utils.h"
uint32_t pwm_init(pwm_t dev, pwm_mode_t mode, uint32_t freq, uint16_t res)
{
/* check if device is valid */
if (dev >= PWM_NUMOF) {
return -1;
}
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(pwm_config[dev].cmu, true);
/* calculate the prescaler by determining the best prescaler */
uint32_t freq_timer = CMU_ClockFreqGet(pwm_config[dev].cmu);
TIMER_Prescale_TypeDef prescaler = TIMER_PrescalerCalc(freq * res,
freq_timer);
if (prescaler > timerPrescale1024) {
return -2;
}
/* reset and initialize peripheral */
TIMER_Init_TypeDef init = TIMER_INIT_DEFAULT;
init.enable = false;
init.prescale = prescaler;
TIMER_Reset(pwm_config[dev].dev);
TIMER_Init(pwm_config[dev].dev, &init);
TIMER_TopSet(pwm_config[dev].dev, res);
/* initialize channels */
TIMER_InitCC_TypeDef init_channel = TIMER_INITCC_DEFAULT;
init_channel.mode = timerCCModePWM;
for (int i = 0; i < pwm_config[dev].channels; i++) {
pwm_chan_conf_t channel = pwm_config[dev].channel[i];
/* configure the pin */
gpio_init(channel.pin, GPIO_OUT);
/* configure pin function */
#ifdef _SILICON_LABS_32B_SERIES_0
pwm_config[dev].dev->ROUTE |= (channel.loc |
TIMER_Channel2Route(channel.index));
#else
pwm_config[dev].dev->ROUTELOC0 |= channel.loc;
pwm_config[dev].dev->ROUTEPEN |= TIMER_Channel2Route(channel.index);
#endif
/* setup channel */
TIMER_InitCC(pwm_config[dev].dev, channel.index, &init_channel);
}
/* enable peripheral */
TIMER_Enable(pwm_config[dev].dev, true);
return freq_timer / TIMER_Prescaler2Div(prescaler) / res;
}
uint8_t pwm_channels(pwm_t dev)
{
assert(dev < PWM_NUMOF);
return pwm_config[dev].channels;
}
void pwm_set(pwm_t dev, uint8_t channel, uint16_t value)
{
assert(dev < PWM_NUMOF);
TIMER_CompareBufSet(pwm_config[dev].dev,
pwm_config[dev].channel[channel].index,
value);
}
void pwm_start(pwm_t dev)
{
assert(dev < PWM_NUMOF);
TIMER_Enable(pwm_config[dev].dev, true);
}
void pwm_stop(pwm_t dev)
{
assert(dev < PWM_NUMOF);
TIMER_Enable(pwm_config[dev].dev, false);
}
void pwm_poweron(pwm_t dev)
{
assert(dev < PWM_NUMOF);
CMU_ClockEnable(pwm_config[dev].cmu, true);
}
void pwm_poweroff(pwm_t dev)
{
assert(dev < PWM_NUMOF);
CMU_ClockEnable(pwm_config[dev].cmu, false);
}

View File

@ -0,0 +1,177 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_rtc
* @{
*
* @file
* @brief RTC peripheral driver implementation
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include <time.h>
#include "cpu.h"
#include "periph_conf.h"
#include "periph/rtc.h"
#include "em_cmu.h"
#include "em_rtc.h"
#define RTC_MAX_VALUE (0xFFFFFF)
#define RTC_SHIFT_VALUE (24U)
typedef struct {
rtc_alarm_cb_t alarm_cb; /**< callback called from RTC interrupt */
void *alarm_arg; /**< argument passed to the callback */
uint32_t alarm; /**< scheduled alarm (may be defered) */
uint8_t overflows; /**< number of overflows */
} rtc_state_t;
static rtc_state_t rtc_state;
/**
* @brief Actual implementation of rtc_set_alarm
*/
static void _set_alarm(void)
{
uint32_t overflows = (rtc_state.alarm >> RTC_SHIFT_VALUE);
/* check if alarm is in reach of RTC counter, which basically means that
the first 8 bits created by software now match */
if (overflows == rtc_state.overflows) {
/* disable interrupt so it doesn't accidentally trigger */
RTC_IntDisable(RTC_IEN_COMP0);
/* set compare register */
RTC_CompareSet(0, rtc_state.alarm & RTC_MAX_VALUE);
/* (re-)enable the interrupt */
RTC_IntClear(RTC_IEN_COMP0);
RTC_IntEnable(RTC_IEN_COMP0);
}
}
void rtc_init(void)
{
/* prescaler of 32768 = 1 s of resolution and overflow each 194 days */
CMU_ClockDivSet(cmuClock_RTC, cmuClkDiv_32768);
/* enable clocks */
CMU_ClockEnable(cmuClock_CORELE, true);
CMU_ClockEnable(cmuClock_RTC, true);
/* initialize the state */
rtc_state.overflows = 0;
/* reset and initialze the peripheral */
RTC_Init_TypeDef init = RTC_INIT_DEFAULT;
init.enable = false;
init.comp0Top = false;
RTC_Reset();
RTC_Init(&init);
/* enable interrupts */
RTC_IntEnable(RTC_IEN_OF);
NVIC_ClearPendingIRQ(RTC_IRQn);
NVIC_EnableIRQ(RTC_IRQn);
/* enable peripheral */
RTC_Enable(true);
}
int rtc_set_time(struct tm *time)
{
uint32_t timestamp = mktime(time);
rtc_state.overflows = (timestamp >> RTC_SHIFT_VALUE);
RTC->CNT = timestamp & RTC_MAX_VALUE;
return 0;
}
int rtc_get_time(struct tm *time)
{
uint32_t timestamp = RTC_CounterGet();
timestamp = timestamp + (rtc_state.overflows << RTC_SHIFT_VALUE);
gmtime_r((time_t *) &timestamp, time);
return 0;
}
int rtc_set_alarm(struct tm *time, rtc_alarm_cb_t cb, void *arg)
{
rtc_state.alarm_cb = cb;
rtc_state.alarm_arg = arg;
rtc_state.alarm = mktime(time);
/* alarm may not be in reach of current time, so defer if needed */
_set_alarm();
return 0;
}
int rtc_get_alarm(struct tm *time)
{
gmtime_r((time_t *) &rtc_state.alarm, time);
return 0;
}
void rtc_clear_alarm(void)
{
rtc_state.alarm_cb = NULL;
rtc_state.alarm_arg = NULL;
rtc_state.alarm = 0;
RTC_IntDisable(RTC_IEN_COMP0);
}
void rtc_poweron(void)
{
CMU_ClockEnable(cmuClock_RTC, true);
}
void rtc_poweroff(void)
{
CMU_ClockEnable(cmuClock_RTC, false);
}
void isr_rtc(void)
{
if ((RTC_IntGet() & RTC_IF_COMP0)) {
if (rtc_state.alarm_cb != NULL) {
rtc_state.alarm_cb(rtc_state.alarm_arg);
}
/* clear interrupt */
RTC_IntClear(RTC_IFC_COMP0);
}
if (RTC_IntGet() & RTC_IF_OF) {
rtc_state.overflows++;
/* check if alarm should be enabled now */
if (rtc_state.alarm_cb) {
_set_alarm();
}
/* clear interrupt */
RTC_IntClear(RTC_IFC_OF);
}
cortexm_isr_end();
}

View File

@ -0,0 +1,174 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_rtc
* @{
*
* @file
* @brief RTC peripheral driver implementation for EFM32 Series 1 MCUs
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include <time.h>
#include "cpu.h"
#include "periph_conf.h"
#include "periph/rtc.h"
#include "em_cmu.h"
#include "em_rtcc.h"
#include "em_rtcc_utils.h"
#define RTC_YEAR_OFFSET (100) /**< RTCC has only two-digit notation */
typedef struct {
rtc_alarm_cb_t alarm_cb; /**< callback called from RTC interrupt */
void *alarm_arg; /**< argument passed to the callback */
uint32_t alarm_year; /**< alarm year */
} rtc_state_t;
static rtc_state_t rtc_state;
void rtc_init(void)
{
/* enable clocks */
CMU_ClockEnable(cmuClock_CORELE, true);
CMU_ClockEnable(cmuClock_RTCC, true);
/* reset and initialize peripheral */
RTCC_Init_TypeDef init = RTCC_INIT_DEFAULT;
init.enable = false;
init.presc = rtccCntPresc_32768;
init.cntMode = rtccCntModeCalendar;
RTCC_Reset();
RTCC_Init(&init);
/* initialize alarm channel */
RTCC_CCChConf_TypeDef init_channel = RTCC_CH_INIT_COMPARE_DEFAULT;
RTCC_ChannelInit(0, &init_channel);
/* enable interrupt */
NVIC_ClearPendingIRQ(RTCC_IRQn);
NVIC_EnableIRQ(RTCC_IRQn);
/* enable peripheral */
RTCC_Enable(true);
}
int rtc_set_time(struct tm *time)
{
RTCC_DateSet(
RTCC_Year2BCD(time->tm_year - RTC_YEAR_OFFSET) |
RTCC_Month2BCD(time->tm_mon) |
RTCC_DayOfMonth2BCD(time->tm_mday) |
RTCC_DayOfWeek2BCD(time->tm_wday));
RTCC_TimeSet(
RTCC_Hour2BCD(time->tm_hour) |
RTCC_Minute2BCD(time->tm_min) |
RTCC_Second2BCD(time->tm_sec));
return 0;
}
int rtc_get_time(struct tm *time)
{
uint32_t datestamp = RTCC_DateGet();
uint32_t timestamp = RTCC_TimeGet();
time->tm_year = RTCC_BCD2Year(datestamp) + RTC_YEAR_OFFSET;
time->tm_mon = RTCC_BCD2Month(datestamp);
time->tm_mday = RTCC_BCD2DayOfMonth(datestamp);
time->tm_wday = RTCC_BCD2DayOfWeek(datestamp);
time->tm_hour = RTCC_BCD2Hour(timestamp);
time->tm_min = RTCC_BCD2Minute(timestamp);
time->tm_sec = RTCC_BCD2Second(timestamp);
return 0;
}
int rtc_set_alarm(struct tm *time, rtc_alarm_cb_t cb, void *arg)
{
rtc_state.alarm_cb = cb;
rtc_state.alarm_arg = arg;
rtc_state.alarm_year = time->tm_year;
/* disable interrupt so it doesn't accidentally trigger */
RTCC_IntDisable(RTCC_IEN_CC0);
/* set compare registers */
RTCC_ChannelDateSet(0,
RTCC_Channel_Month2BCD(time->tm_mon) |
RTCC_Channel_Day2BCD(time->tm_mday));
RTCC_ChannelTimeSet(0,
RTCC_Channel_Hour2BCD(time->tm_hour) |
RTCC_Channel_Minute2BCD(time->tm_min) |
RTCC_Channel_Second2BCD(time->tm_sec));
/* enable the interrupt */
RTCC_IntClear(RTCC_IFC_CC0);
RTCC_IntEnable(RTCC_IEN_CC0);
return 0;
}
int rtc_get_alarm(struct tm *time)
{
uint32_t datestamp = RTCC_ChannelDateGet(0);
uint32_t timestamp = RTCC_ChannelTimeGet(0);
time->tm_year = rtc_state.alarm_year;
time->tm_mon = RTCC_Channel_BCD2Month(datestamp);
time->tm_mday = RTCC_Channel_BCD2Day(datestamp);
time->tm_hour = RTCC_Channel_BCD2Hour(timestamp);
time->tm_min = RTCC_Channel_BCD2Minute(timestamp);
time->tm_sec = RTCC_Channel_BCD2Second(timestamp);
return 0;
}
void rtc_clear_alarm(void)
{
rtc_state.alarm_cb = NULL;
rtc_state.alarm_arg = NULL;
rtc_state.alarm_year = 0;
RTCC_IntDisable(RTCC_IEN_CC0);
}
void rtc_poweron(void)
{
CMU_ClockEnable(cmuClock_RTCC, true);
}
void rtc_poweroff(void)
{
CMU_ClockEnable(cmuClock_RTCC, false);
}
void isr_rtcc(void)
{
if (RTCC_IntGet() & RTCC_IF_CC0) {
if (rtc_state.alarm_cb != NULL) {
/* check if year matches, otherwise alarm would go off each year */
if (RTCC_BCD2Year(RTCC_DateGet()) + RTC_YEAR_OFFSET == rtc_state.alarm_year) {
rtc_state.alarm_cb(rtc_state.alarm_arg);
}
}
RTCC_IntClear(RTCC_IFC_CC0);
}
cortexm_isr_end();
}

View File

@ -0,0 +1,151 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_rtt
* @{
*
* @file
* @brief RTT peripheral driver implementation
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/rtt.h"
#include "em_cmu.h"
#include "em_rtc.h"
typedef struct {
rtt_cb_t alarm_cb; /**< callback called from RTC alarm */
void *alarm_arg; /**< argument passed to the callback */
rtt_cb_t overflow_cb; /**< callback called when RTC overflows */
void *overflow_arg; /**< argument passed to the callback */
} rtt_state_t;
static rtt_state_t rtt_state;
void rtt_init(void)
{
/* prescaler of 32768 = 1 s of resolution and overflow each 194 days */
CMU_ClockDivSet(cmuClock_RTC, cmuClkDiv_32768);
/* enable clocks */
CMU_ClockEnable(cmuClock_CORELE, true);
CMU_ClockEnable(cmuClock_RTC, true);
/* reset and initialize peripheral */
RTC_Init_TypeDef init = RTC_INIT_DEFAULT;
init.enable = false;
init.comp0Top = false;
RTC_Reset();
RTC_Init(&init);
/* enable interrupts */
RTC_IntEnable(RTC_IEN_OF);
NVIC_ClearPendingIRQ(RTC_IRQn);
NVIC_EnableIRQ(RTC_IRQn);
/* enable peripheral */
RTC_Enable(true);
}
void rtt_set_overflow_cb(rtt_cb_t cb, void *arg)
{
rtt_state.overflow_cb = cb;
rtt_state.overflow_arg = arg;
RTC_IntClear(RTC_IFC_OF);
RTC_IntEnable(RTC_IEN_OF);
}
void rtt_clear_overflow_cb(void)
{
rtt_state.overflow_cb = NULL;
rtt_state.overflow_arg = NULL;
RTC_IntDisable(RTC_IEN_OF);
}
uint32_t rtt_get_counter(void)
{
return RTC_CounterGet();
}
void rtt_set_counter(uint32_t counter)
{
RTC->CNT = counter & RTT_MAX_VALUE;
}
void rtt_set_alarm(uint32_t alarm, rtt_cb_t cb, void *arg)
{
rtt_state.alarm_cb = cb;
rtt_state.alarm_arg = arg;
/* disable interrupt so it doesn't accidentally trigger */
RTC_IntDisable(RTC_IEN_COMP0);
/* set compare register */
RTC_CompareSet(0, alarm & RTT_MAX_VALUE);
/* enable the interrupt */
RTC_IntClear(RTC_IFC_COMP0);
RTC_IntEnable(RTC_IEN_COMP0);
}
uint32_t rtt_get_alarm(void)
{
return RTC_CompareGet(0);
}
void rtt_clear_alarm(void)
{
rtt_state.alarm_cb = NULL;
rtt_state.alarm_arg = NULL;
/* disable the interrupt */
RTC_IntDisable(RTC_IEN_COMP0);
}
void rtt_poweron(void)
{
CMU_ClockEnable(cmuClock_RTC, true);
}
void rtt_poweroff(void)
{
CMU_ClockEnable(cmuClock_RTC, false);
}
void isr_rtc(void)
{
if ((RTC_IntGet() & RTC_IF_COMP0)) {
if (rtt_state.alarm_cb != NULL) {
rtt_state.alarm_cb(rtt_state.alarm_arg);
}
/* clear interrupt */
RTC_IntClear(RTC_IFC_COMP0);
}
if (RTC_IntGet() & RTC_IF_OF) {
if (rtt_state.overflow_cb != NULL) {
rtt_state.overflow_cb(rtt_state.overflow_arg);
}
/* clear interrupt */
RTC_IntClear(RTC_IFC_OF);
}
cortexm_isr_end();
}

View File

@ -0,0 +1,152 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_rtt
* @{
*
* @file
* @brief RTT peripheral driver implementation for EFM32 Series 1 MCUs
*
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/rtt.h"
#include "em_cmu.h"
#include "em_rtcc.h"
typedef struct {
rtt_cb_t alarm_cb; /**< callback called from RTC alarm */
void *alarm_arg; /**< argument passed to the callback */
rtt_cb_t overflow_cb; /**< callback called when RTC overflows */
void *overflow_arg; /**< argument passed to the callback */
} rtt_state_t;
static rtt_state_t rtt_state;
void rtt_init(void)
{
/* enable clocks */
CMU_ClockEnable(cmuClock_CORELE, true);
CMU_ClockEnable(cmuClock_RTCC, true);
/* reset and initialize peripheral */
RTCC_Init_TypeDef init = RTCC_INIT_DEFAULT;
init.enable = false;
init.presc = rtccCntPresc_32768;
RTCC_Reset();
RTCC_Init(&init);
/* initialize alarm channel */
RTCC_CCChConf_TypeDef init_channel = RTCC_CH_INIT_COMPARE_DEFAULT;
RTCC_ChannelInit(0, &init_channel);
/* enable interrupts */
NVIC_ClearPendingIRQ(RTCC_IRQn);
NVIC_EnableIRQ(RTCC_IRQn);
/* enable peripheral */
RTCC_Enable(true);
}
void rtt_set_overflow_cb(rtt_cb_t cb, void *arg)
{
rtt_state.overflow_cb = cb;
rtt_state.overflow_arg = arg;
RTCC_IntClear(RTCC_IFC_OF);
RTCC_IntEnable(RTCC_IEN_OF);
}
void rtt_clear_overflow_cb(void)
{
rtt_state.overflow_cb = NULL;
rtt_state.overflow_arg = NULL;
RTCC_IntDisable(RTCC_IEN_OF);
}
uint32_t rtt_get_counter(void)
{
return RTCC_CounterGet();
}
void rtt_set_counter(uint32_t counter)
{
RTCC->CNT = counter & RTT_MAX_VALUE;
}
void rtt_set_alarm(uint32_t alarm, rtt_cb_t cb, void *arg)
{
rtt_state.alarm_cb = cb;
rtt_state.alarm_arg = arg;
/* disable interrupt so it doesn't accidentally trigger */
RTCC_IntDisable(RTCC_IEN_CC0);
/* set compare register */
RTCC_ChannelCCVSet(0, alarm & RTT_MAX_VALUE);
/* enable the interrupt */
RTCC_IntClear(RTCC_IFC_CC0);
RTCC_IntEnable(RTCC_IEN_CC0);
}
uint32_t rtt_get_alarm(void)
{
return RTCC_ChannelCCVGet(0);
}
void rtt_clear_alarm(void)
{
rtt_state.alarm_cb = NULL;
rtt_state.alarm_arg = NULL;
/* disable the interrupt */
RTCC_IntDisable(RTCC_IEN_CC0);
}
void rtt_poweron(void)
{
CMU_ClockEnable(cmuClock_RTCC, true);
}
void rtt_poweroff(void)
{
CMU_ClockEnable(cmuClock_RTCC, false);
}
void isr_rtcc(void)
{
if ((RTCC_IntGet() & RTCC_IF_CC0)) {
if (rtt_state.alarm_cb != NULL) {
rtt_state.alarm_cb(rtt_state.alarm_arg);
}
/* clear interrupt */
RTCC_IntClear(RTCC_IFC_CC0);
}
if (RTCC_IntGet() & RTCC_IF_OF) {
if (rtt_state.overflow_cb != NULL) {
rtt_state.overflow_cb(rtt_state.overflow_arg);
}
/* clear interrupt */
RTCC_IntClear(RTCC_IFC_OF);
}
cortexm_isr_end();
}

View File

@ -0,0 +1,121 @@
/*
* Copyright (C) 2014-2016 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_efm32_common
* @ingroup drivers_periph_spi
* @{
*
* @file
* @brief Low-level SPI driver implementation
*
* @author Ryan Kurte <ryankurte@gmail.com>
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @author Christian Amsüss <c@amsuess.com>
* @}
*/
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "mutex.h"
#include "periph_conf.h"
#include "periph/gpio.h"
#include "periph/spi.h"
#include "em_device.h"
#include "em_cmu.h"
#include "em_usart.h"
static mutex_t spi_lock[SPI_NUMOF];
void spi_init(spi_t bus)
{
assert(bus < SPI_NUMOF);
/* initialize lock */
mutex_init(&spi_lock[bus]);
/* initialize pins */
spi_init_pins(bus);
}
void spi_init_pins(spi_t bus)
{
/* configure the pins */
gpio_init(spi_config[bus].clk_pin, GPIO_OUT);
gpio_init(spi_config[bus].mosi_pin, GPIO_OUT);
gpio_init(spi_config[bus].miso_pin, GPIO_IN_PD);
}
int spi_acquire(spi_t bus, spi_cs_t cs, spi_mode_t mode, spi_clk_t clk)
{
(void)cs;
mutex_lock(&spi_lock[bus]);
/* power on spi bus */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(spi_config[bus].cmu, true);
USART_InitSync_TypeDef init = USART_INITSYNC_DEFAULT;
init.baudrate = (uint32_t) clk;
init.clockMode = (USART_ClockMode_TypeDef) mode;
init.msbf = true;
USART_InitSync(spi_config[bus].dev, &init);
/* configure pin functions */
#ifdef _SILICON_LABS_32B_SERIES_0
spi_config[bus].dev->ROUTE = (spi_config[bus].loc |
USART_ROUTE_RXPEN |
USART_ROUTE_TXPEN |
USART_ROUTE_CLKPEN);
#else
spi_config[bus].dev->ROUTELOC0 = spi_config[bus].loc;
spi_config[bus].dev->ROUTEPEN = (USART_ROUTEPEN_RXPEN |
USART_ROUTEPEN_TXPEN |
USART_ROUTEPEN_CLKPEN);
#endif
return SPI_OK;
}
void spi_release(spi_t bus)
{
/* power off spi bus */
CMU_ClockEnable(spi_config[bus].cmu, false);
mutex_unlock(&spi_lock[bus]);
}
void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont,
const void *out, void *in, size_t len)
{
uint8_t *out_buf = (uint8_t *)out;
uint8_t *in_buf = (uint8_t *)in;
if (cs != SPI_CS_UNDEF) {
gpio_clear((gpio_t)cs);
}
for (size_t i = 0; i < len; i++) {
uint8_t ret = USART_SpiTransfer(spi_config[bus].dev,
out != NULL ? out_buf[i] : 0);
if (in != NULL) {
in_buf[i] = ret;
}
}
if ((!cont) && (cs != SPI_CS_UNDEF)) {
gpio_set((gpio_t)cs);
}
}

View File

@ -0,0 +1,160 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_timer
* @{
*
* @file
* @brief Low-level timer driver implementation
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "periph/timer.h"
#include "periph_conf.h"
#include "em_cmu.h"
#include "em_timer.h"
#include "em_timer_utils.h"
/**
* @brief This timer implementation has three available channels
*/
#define CC_CHANNELS (3U)
/**
* @brief Timer state memory
*/
static timer_isr_ctx_t isr_ctx[TIMER_NUMOF];
int timer_init(tim_t dev, unsigned long freq, timer_cb_t callback, void *arg)
{
TIMER_TypeDef *pre, *tim;
/* test if given timer device is valid */
if (dev >= TIMER_NUMOF) {
return -1;
}
/* save callback */
isr_ctx[dev].cb = callback;
isr_ctx[dev].arg = arg;
/* get timers */
pre = timer_config[dev].prescaler.dev;
tim = timer_config[dev].timer.dev;
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(timer_config[dev].prescaler.cmu, true);
CMU_ClockEnable(timer_config[dev].timer.cmu, true);
/* reset and initialize peripherals */
TIMER_Init_TypeDef init_pre = TIMER_INIT_DEFAULT;
TIMER_Init_TypeDef init_tim = TIMER_INIT_DEFAULT;
init_pre.enable = false;
init_pre.prescale = timerPrescale1;
init_tim.enable = false;
init_tim.clkSel = timerClkSelCascade;
TIMER_Reset(tim);
TIMER_Reset(pre);
TIMER_Init(tim, &init_tim);
TIMER_Init(pre, &init_pre);
/* configure the prescaler top value */
uint32_t freq_timer = CMU_ClockFreqGet(timer_config[dev].prescaler.cmu);
uint32_t top = (
freq_timer / TIMER_Prescaler2Div(init_pre.prescale) / freq) - 1;
TIMER_TopSet(pre, top);
TIMER_TopSet(tim, 0xffff);
/* enable interrupts for the channels */
TIMER_IntClear(tim, TIMER_IFC_CC0 | TIMER_IFC_CC1 | TIMER_IFC_CC2);
TIMER_IntEnable(tim, TIMER_IEN_CC0 | TIMER_IEN_CC1 | TIMER_IEN_CC2);
NVIC_ClearPendingIRQ(timer_config[dev].irq);
NVIC_EnableIRQ(timer_config[dev].irq);
/* start the timers */
TIMER_Enable(tim, true);
TIMER_Enable(pre, true);
return 0;
}
int timer_set(tim_t dev, int channel, unsigned int timeout)
{
return timer_set_absolute(dev, channel, timer_read(dev) + timeout);
}
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
{
TIMER_TypeDef *tim;
if (channel < 0 || channel >= (int) CC_CHANNELS) {
return -1;
}
if (value > 0xffff) {
return -1;
}
tim = timer_config[dev].timer.dev;
tim->CC[channel].CCV = (uint16_t)value;
tim->CC[channel].CTRL = TIMER_CC_CTRL_MODE_OUTPUTCOMPARE;
return 0;
}
int timer_clear(tim_t dev, int channel)
{
timer_config[dev].timer.dev->CC[channel].CTRL = _TIMER_CC_CTRL_MODE_OFF;
return 0;
}
unsigned int timer_read(tim_t dev)
{
return (unsigned int) TIMER_CounterGet(timer_config[dev].timer.dev);
}
void timer_stop(tim_t dev)
{
TIMER_Enable(timer_config[dev].timer.dev, false);
}
void timer_start(tim_t dev)
{
TIMER_Enable(timer_config[dev].timer.dev, true);
}
#ifdef TIMER_0_ISR
void TIMER_0_ISR(void)
{
TIMER_TypeDef *tim = timer_config[0].timer.dev;
for (int i = 0; i < (int) CC_CHANNELS; i++) {
if (tim->IF & (TIMER_IF_CC0 << i)) {
tim->CC[i].CTRL = _TIMER_CC_CTRL_MODE_OFF;
tim->IFC = (TIMER_IFC_CC0 << i);
isr_ctx[0].cb(isr_ctx[0].arg, i);
}
}
cortexm_isr_end();
}
#endif /* TIMER_0_ISR */

View File

@ -0,0 +1,213 @@
/*
* 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 cpu_efm32_common
* @ingroup drivers_periph_uart
* @{
*
* @file
* @brief Low-level UART driver implementation.
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Ryan Kurte <ryankurte@gmail.com>
* @author Bas Stottelaar <basstottelaar@gmail.com>
* @}
*/
#include "cpu.h"
#include "periph/uart.h"
#include "periph/gpio.h"
#include "em_usart.h"
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
#include "em_leuart.h"
#endif
/**
* @brief Allocate memory to store the callback functions
*/
static uart_isr_ctx_t isr_ctx[UART_NUMOF];
/**
* @brief Check if device is a U(S)ART device.
*/
static inline bool _is_usart(uart_t dev)
{
return ((uint32_t) uart_config[dev].dev) < LEUART0_BASE;
}
int uart_init(uart_t dev, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
/* check if device is valid */
if (dev >= UART_NUMOF) {
return -1;
}
/* save interrupt callback context */
isr_ctx[dev].rx_cb = rx_cb;
isr_ctx[dev].arg = arg;
/* initialize the pins */
gpio_init(uart_config[dev].rx_pin, GPIO_IN);
gpio_init(uart_config[dev].tx_pin, GPIO_OUT);
/* initialize the UART/USART/LEUART device */
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
if (_is_usart(dev)) {
#endif
USART_TypeDef *uart = (USART_TypeDef *) uart_config[dev].dev;
/* enable clocks */
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(uart_config[dev].cmu, true);
/* reset and initialize peripheral */
USART_InitAsync_TypeDef init = USART_INITASYNC_DEFAULT;
init.enable = usartDisable;
init.baudrate = baudrate;
USART_InitAsync(uart, &init);
/* configure pin functions */
#ifdef _SILICON_LABS_32B_SERIES_0
uart->ROUTE = (uart_config[dev].loc |
USART_ROUTE_RXPEN |
USART_ROUTE_TXPEN);
#else
uart->ROUTELOC0 = uart_config[dev].loc;
uart->ROUTEPEN = USART_ROUTEPEN_RXPEN | USART_ROUTEPEN_TXPEN;
#endif
/* enable receive interrupt */
USART_IntEnable(uart, USART_IEN_RXDATAV);
/* enable peripheral */
USART_Enable(uart, usartEnable);
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
} else {
LEUART_TypeDef *leuart = (LEUART_TypeDef *) uart_config[dev].dev;
/* enable clocks */
CMU_ClockEnable(cmuClock_CORELE, true);
CMU_ClockEnable(uart_config[dev].cmu, true);
/* reset and initialize peripheral */
LEUART_Init_TypeDef init = LEUART_INIT_DEFAULT;
init.enable = leuartDisable;
init.baudrate = baudrate;
LEUART_Init(leuart, &init);
/* configure pin functions */
#ifdef _SILICON_LABS_32B_SERIES_0
leuart->ROUTE = (uart_config[dev].loc |
LEUART_ROUTE_RXPEN |
LEUART_ROUTE_TXPEN);
#else
leuart->ROUTELOC0 = uart_config[dev].loc;
leuart->ROUTEPEN = LEUART_ROUTEPEN_RXPEN | LEUART_ROUTEPEN_TXPEN;
#endif
/* enable receive interrupt */
LEUART_IntEnable(leuart, LEUART_IEN_RXDATAV);
/* enable peripheral */
LEUART_Enable(leuart, leuartEnable);
}
#endif
/* enable the interrupt */
NVIC_ClearPendingIRQ(uart_config[dev].irq);
NVIC_EnableIRQ(uart_config[dev].irq);
return 0;
}
void uart_write(uart_t dev, const uint8_t *data, size_t len)
{
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
if (_is_usart(dev)) {
#endif
while (len--) {
USART_Tx(uart_config[dev].dev, *(data++));
}
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
} else {
while (len--) {
LEUART_Tx(uart_config[dev].dev, *(data++));
}
}
#endif
}
void uart_poweron(uart_t dev)
{
CMU_ClockEnable(uart_config[dev].cmu, true);
}
void uart_poweroff(uart_t dev)
{
CMU_ClockEnable(uart_config[dev].cmu, false);
}
static void rx_irq(uart_t dev)
{
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
if (_is_usart(dev)) {
#endif
if (USART_IntGet(uart_config[dev].dev) & USART_IF_RXDATAV) {
isr_ctx[dev].rx_cb(isr_ctx[dev].arg, USART_RxDataGet(uart_config[dev].dev));
}
#if LOW_POWER_ENABLED && defined(LEUART_COUNT) && LEUART_COUNT > 0
} else {
if (LEUART_IntGet(uart_config[dev].dev) & LEUART_IF_RXDATAV) {
isr_ctx[dev].rx_cb(isr_ctx[dev].arg, LEUART_RxDataGet(uart_config[dev].dev));
}
}
#endif
cortexm_isr_end();
}
#ifdef UART_0_ISR_RX
void UART_0_ISR_RX(void)
{
rx_irq(0);
}
#endif
#ifdef UART_1_ISR_RX
void UART_1_ISR_RX(void)
{
rx_irq(1);
}
#endif
#ifdef UART_2_ISR_RX
void UART_2_ISR_RX(void)
{
rx_irq(2);
}
#endif
#ifdef UART_3_ISR_RX
void UART_3_ISR_RX(void)
{
rx_irq(3);
}
#endif
#ifdef UART_4_ISR_RX
void UART_4_ISR_RX(void)
{
rx_irq(4);
}
#endif