diff --git a/cpu/cortex-m0_common/thread_arch.c b/cpu/cortex-m0_common/thread_arch.c index 29414d610..ab546f9a1 100644 --- a/cpu/cortex-m0_common/thread_arch.c +++ b/cpu/cortex-m0_common/thread_arch.c @@ -135,12 +135,14 @@ void thread_arch_stack_print(void) printf("current stack size: %i byte\n", count); } -NAKED NORETURN void thread_arch_start_threading(void) +__attribute__((naked)) void NORETURN thread_arch_start_threading(void) { /* enable IRQs to make sure the SVC interrupt can be triggered */ enableIRQ(); /* trigger the SVC interrupt that will schedule and load the next thread */ asm("svc 0x01"); + + UNREACHABLE(); } void thread_arch_yield(void) @@ -241,7 +243,7 @@ __attribute__((always_inline)) static __INLINE void context_restore(void) * 1) after system initialization for running the main thread * 2) after exiting from a thread */ -NAKED void isr_svc(void) +__attribute__((naked)) void isr_svc(void) { sched_run(); context_restore(); @@ -253,7 +255,7 @@ NAKED void isr_svc(void) * This interrupt saves the context, runs the scheduler and restores the context of the thread * that is run next. */ -NAKED void isr_pendsv(void) +__attribute__((naked)) void isr_pendsv(void) { context_save(); sched_run(); diff --git a/cpu/stm32f0/Makefile b/cpu/stm32f0/Makefile new file mode 100644 index 000000000..55e50d209 --- /dev/null +++ b/cpu/stm32f0/Makefile @@ -0,0 +1,7 @@ +# define the module that is build +MODULE = cpu + +# add a list of subdirectories, that should also be build +DIRS = periph $(CORTEX_COMMON) + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f0/Makefile.include b/cpu/stm32f0/Makefile.include new file mode 100644 index 000000000..c2bd10a42 --- /dev/null +++ b/cpu/stm32f0/Makefile.include @@ -0,0 +1,30 @@ +# this CPU implementation is using the new core/CPU interface +export CFLAGS += -DCOREIF_NG=1 + +# tell the build system that the CPU depends on the Cortex-M common files +export USEMODULE += cortex-m0_common + +# define path to cortex-m common module, which is needed for this CPU +export CORTEX_COMMON = $(RIOTCPU)/cortex-m0_common/ + +# define the linker script to use for this CPU. The CPU_MODEL variable is defined in the +# board's Makefile.include. This enables multiple STMF0 controllers with different memory to +# use the same code-base. +export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld + +#export the CPU model +MODEL = $(shell echo $(CPU_MODEL)|tr 'a-z' 'A-Z') +export CFLAGS += -DCPU_MODEL_$(MODEL) + +# include CPU specific includes +export INCLUDES += -I$(RIOTCPU)/$(CPU)/include + +# add the CPU specific system calls implementations for the linker +export UNDEF += $(BINDIR)cpu/syscalls.o +export UNDEF += $(BINDIR)cpu/startup.o + +# export the peripheral drivers to be linked into the final binary +export USEMODULE += periph + +# CPU depends on the cortex-m common module, so include it +include $(CORTEX_COMMON)Makefile.include diff --git a/cpu/stm32f0/cpu.c b/cpu/stm32f0/cpu.c new file mode 100644 index 000000000..4003ef51d --- /dev/null +++ b/cpu/stm32f0/cpu.c @@ -0,0 +1,111 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Implementation of the CPU initialization + * + * @author Hauke Petersen + * @} + */ + +#include "cpu.h" +#include "periph_conf.h" + + +static void clock_init(void); + +/** + * @brief Initialize the CPU, set IRQ priorities + */ +void cpu_init(void) +{ + /* initialize the clock system */ + clock_init(); + + /* set pendSV interrupt to lowest possible priority */ + NVIC_SetPriority(PendSV_IRQn, 0xff); +} + +/** + * @brief Configure the controllers clock system + * + * The clock initialization make the following assumptions: + * - the external HSE clock from an external oscillator is used as base clock + * - the internal PLL circuit is used for clock refinement + * + * Use the following formulas to calculate the needed values: + * + * SYSCLK = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_P + * USB, SDIO and RNG Clock = ((HSE_VALUE / CLOCK_PLL_M) * CLOCK_PLL_N) / CLOCK_PLL_Q + * + * The actual used values are specified in the board's `periph_conf.h` file. + * + * NOTE: currently there is not timeout for initialization of PLL and other locks + * -> when wrong values are chosen, the initialization could stall + */ +static void clock_init(void) +{ + /* configure the HSE clock */ + + /* enable the HSI clock */ + RCC->CR |= RCC_CR_HSION; + + /* reset clock configuration register */ + RCC->CFGR = 0; + RCC->CFGR2 = 0; + + /* disable HSE, CSS and PLL */ + RCC->CR &= ~(RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON | RCC_CR_PLLON); + + /* disable all clock interrupts */ + RCC->CIR = 0; + + /* enable the HSE clock */ + RCC->CR |= RCC_CR_HSEON; + + /* wait for HSE to be ready */ + while (!(RCC->CR & RCC_CR_HSERDY)); + + /* setup the peripheral bus prescalers */ + + /* set HCLK = SYSCLK, so no clock division here */ + RCC->CFGR |= RCC_CFGR_HPRE_DIV1; + /* set PCLK = HCLK, so its not divided */ + RCC->CFGR |= RCC_CFGR_PPRE_DIV1; + + /* configure the PLL */ + + /* reset PLL configuration bits */ + RCC->CFGR &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMUL); + /* set PLL configuration */ + RCC->CFGR |= RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR_PLLXTPRE_HSE_PREDIV_DIV1 | + (((CLOCK_PLL_MUL - 2) & 0xf) << 18); + + /* enable PLL again */ + RCC->CR |= RCC_CR_PLLON; + /* wait until PLL is stable */ + while(!(RCC->CR & RCC_CR_PLLRDY)); + + /* configure flash latency */ + + /* enable pre-fetch buffer and set flash latency to 1 cycle*/ + FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY; + + /* configure the sysclock and the peripheral clocks */ + + /* set sysclock to be driven by the PLL clock */ + RCC->CFGR &= ~RCC_CFGR_SW; + RCC->CFGR |= RCC_CFGR_SW_PLL; + + /* wait for sysclock to be stable */ + while (!(RCC->CFGR & RCC_CFGR_SWS_PLL)); +} diff --git a/cpu/stm32f0/hwtimer_arch.c b/cpu/stm32f0/hwtimer_arch.c new file mode 100644 index 000000000..f9905e1d0 --- /dev/null +++ b/cpu/stm32f0/hwtimer_arch.c @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Implementation of the kernel's hwtimer interface + * + * The hardware timer implementation uses the Cortex build-in system timer as back-end. + * + * @author Hauke Petersen + * + * @} + */ + +#include "arch/hwtimer_arch.h" +#include "periph/timer.h" +#include "board.h" +#include "thread.h" + + +void irq_handler(int channel); +void (*timeout_handler)(int); + + +void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu) +{ + timeout_handler = handler; + timer_init(HW_TIMER, 1, &irq_handler); +} + +void hwtimer_arch_enable_interrupt(void) +{ + timer_irq_enable(HW_TIMER); +} + +void hwtimer_arch_disable_interrupt(void) +{ + timer_irq_disable(HW_TIMER); +} + +void hwtimer_arch_set(unsigned long offset, short timer) +{ + timer_set(HW_TIMER, timer, offset); +} + +void hwtimer_arch_set_absolute(unsigned long value, short timer) +{ + timer_set_absolute(HW_TIMER, timer, value); +} + +void hwtimer_arch_unset(short timer) +{ + timer_clear(HW_TIMER, timer); +} + +unsigned long hwtimer_arch_now(void) +{ + return timer_read(HW_TIMER); +} + +void irq_handler(int channel) +{ + timeout_handler((short)(channel)); + thread_yield(); +} diff --git a/cpu/stm32f0/include/cpu-conf.h b/cpu/stm32f0/include/cpu-conf.h new file mode 100644 index 000000000..e7e89aa21 --- /dev/null +++ b/cpu/stm32f0/include/cpu-conf.h @@ -0,0 +1,59 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @defgroup cpu_stm32f0 STM32F0 + * @brief STM32F0 specific code + * @ingroup cpu + * @{ + * + * @file + * @brief Implementation specific CPU configuration options + * + * @author Hauke Petersen + */ + +#ifndef __CPU_CONF_H +#define __CPU_CONF_H + +#ifdef CPU_MODEL_STM32F051R8 +#include "stm32f051x8.h" +#endif + + +/** + * @name Kernel configuration + * + * The absolute minimum stack size is 140 byte (68 byte for the tcb + 72 byte + * for a complete context save). + * + * TODO: measure and adjust for the Cortex-M0 + * @{ + */ +#define KERNEL_CONF_STACKSIZE_PRINTF (512) + +#ifndef KERNEL_CONF_STACKSIZE_DEFAULT +#define KERNEL_CONF_STACKSIZE_DEFAULT (512) +#endif + +#define KERNEL_CONF_STACKSIZE_IDLE (192) +/** @} */ + +/** + * @name UART0 buffer size definition for compatibility reasons + * + * TODO: remove once the remodeling of the uart0 driver is done + * @{ + */ +#ifndef UART0_BUFSIZE +#define UART0_BUFSIZE (128) +#endif +/** @} */ + +#endif /* __CPU_CONF_H */ +/** @} */ diff --git a/cpu/stm32f0/include/hwtimer_cpu.h b/cpu/stm32f0/include/hwtimer_cpu.h new file mode 100644 index 000000000..b8a804933 --- /dev/null +++ b/cpu/stm32f0/include/hwtimer_cpu.h @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief CPU specific hwtimer configuration options + * + * @author Hauke Petersen + */ + +#ifndef __HWTIMER_CPU_H +#define __HWTIMER_CPU_H + +/** + * @name Hardware timer configuration + * @{ + */ +#define HWTIMER_MAXTIMERS 4 /**< the CPU implementation supports 4 HW timers */ +#define HWTIMER_SPEED 1000000 /**< the HW timer runs with 1MHz */ +#define HWTIMER_MAXTICKS (0xFFFFFFFF) /**< 32-bit timer */ +/** @} */ + +#endif /* __HWTIMER_CPU_H */ +/** @} */ diff --git a/cpu/stm32f0/include/stm32f051x8.h b/cpu/stm32f0/include/stm32f051x8.h new file mode 100644 index 000000000..98199b299 --- /dev/null +++ b/cpu/stm32f0/include/stm32f051x8.h @@ -0,0 +1,3841 @@ +/** + ****************************************************************************** + * @file stm32f051x8.h + * @author MCD Application Team + * @version V2.0.1 + * @date 18-June-2014 + * @brief CMSIS STM32F051x4/STM32F051x6/STM32F051x8 devices Peripheral Access + * Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2014 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS_Device + * @{ + */ + +/** @addtogroup stm32f051x8 + * @{ + */ + +#ifndef __STM32F051x8_H +#define __STM32F051x8_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M0 Processor and Core Peripherals + */ +#define __CM0_REV 0 /*!< Core Revision r0p0 */ +#define __MPU_PRESENT 0 /*!< STM32F0xx do not provide MPU */ +#define __NVIC_PRIO_BITS 2 /*!< STM32F0xx uses 2 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F051x4/STM32F051x6/STM32F051x8 device Interrupt Number Definition + */ +typedef enum +{ +/****** Cortex-M0 Processor Exceptions Numbers **************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M0 Hard Fault Interrupt */ + SVC_IRQn = -5, /*!< 11 Cortex-M0 SV Call Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M0 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M0 System Tick Interrupt */ + +/****** STM32F051x4/STM32F051x6/STM32F051x8 specific Interrupt Numbers **************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD Interrupt through EXTI Lines 16 */ + RTC_IRQn = 2, /*!< RTC Interrupt through EXTI Lines 17, 19 and 20 */ + FLASH_IRQn = 3, /*!< FLASH global Interrupt */ + RCC_IRQn = 4, /*!< RCC global Interrupt */ + EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupts */ + EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupts */ + EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupts */ + TSC_IRQn = 8, /*!< Touch Sensing Controller Interrupts */ + DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */ + DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupts */ + DMA1_Channel4_5_IRQn = 11, /*!< DMA1 Channel 4 and Channel 5 Interrupts */ + ADC1_COMP_IRQn = 12, /*!< ADC1 and COMP interrupts (ADC interrupt combined with EXTI Lines 21 and 22 */ + TIM1_BRK_UP_TRG_COM_IRQn = 13, /*!< TIM1 Break, Update, Trigger and Commutation Interrupts */ + TIM1_CC_IRQn = 14, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 15, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 16, /*!< TIM3 global Interrupt */ + TIM6_DAC_IRQn = 17, /*!< TIM6 global and DAC channel underrun error Interrupts */ + TIM14_IRQn = 19, /*!< TIM14 global Interrupt */ + TIM15_IRQn = 20, /*!< TIM15 global Interrupt */ + TIM16_IRQn = 21, /*!< TIM16 global Interrupt */ + TIM17_IRQn = 22, /*!< TIM17 global Interrupt */ + I2C1_IRQn = 23, /*!< I2C1 Event Interrupt & EXTI Line23 Interrupt (I2C1 wakeup) */ + I2C2_IRQn = 24, /*!< I2C2 Event Interrupt */ + SPI1_IRQn = 25, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 26, /*!< SPI2 global Interrupt */ + USART1_IRQn = 27, /*!< USART1 global Interrupt & EXTI Line25 Interrupt (USART1 wakeup) */ + USART2_IRQn = 28, /*!< USART2 global Interrupt */ + CEC_CAN_IRQn = 30 /*!< CEC and CAN global Interrupts & EXTI Line27 Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm0.h" /* Cortex-M0 processor and core peripherals */ +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC Interrupt and Status register, Address offset:0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable register, Address offset:0x04 */ + __IO uint32_t CR; /*!< ADC Control register, Address offset:0x08 */ + __IO uint32_t CFGR1; /*!< ADC Configuration register 1, Address offset:0x0C */ + __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset:0x10 */ + __IO uint32_t SMPR; /*!< ADC Sampling time register, Address offset:0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t TR; /*!< ADC watchdog threshold register, Address offset:0x20 */ + uint32_t RESERVED3; /*!< Reserved, 0x24 */ + __IO uint32_t CHSELR; /*!< ADC channel selection register, Address offset:0x28 */ + uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */ + __IO uint32_t DR; /*!< ADC data register, Address offset:0x40 */ +}ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; +}ADC_Common_TypeDef; + +/** + * @brief HDMI-CEC + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ + __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ + __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ + __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ + __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ + __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ +}CEC_TypeDef; + +/** + * @brief Comparator + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< Comparator 1 & 2 control Status register, Address offset: 0x00 */ +}COMP1_2_TypeDef; + +typedef struct +{ + __IO uint16_t CSR; /*!< Comparator control Status register, Address offset: 0x00 */ +}COMP_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +}CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +}DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +}DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +}DMA_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*! + * + * @} + */ + +#include "board.h" +#include "arch/io_arch.h" +#include "periph/uart.h" + + +int io_arch_puts(char *data, int size) +{ + int i = 0; + for (; i < size; i++) { + uart_write_blocking(STDIO, data[i]); + } + return i; +} diff --git a/cpu/stm32f0/lpm_arch.c b/cpu/stm32f0/lpm_arch.c new file mode 100644 index 000000000..dceb5b82a --- /dev/null +++ b/cpu/stm32f0/lpm_arch.c @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Implementation of the kernels power management interface + * + * @author Hauke Petersen + * + * @} + */ + +#include "arch/lpm_arch.h" + + +void lpm_arch_init(void) +{ + /* TODO */ +} + +enum lpm_mode lpm_arch_set(enum lpm_mode target) +{ + /* TODO */ + return 0; +} + +enum lpm_mode lpm_arch_get(void) +{ + /* TODO */ + return 0; +} + +void lpm_arch_awake(void) +{ + /* TODO*/ +} + +void lpm_arch_begin_awake(void) +{ + /* TODO */ +} + +void lpm_arch_end_awake(void) +{ + /* TODO */ +} diff --git a/cpu/stm32f0/periph/Makefile b/cpu/stm32f0/periph/Makefile new file mode 100644 index 000000000..6d1887b64 --- /dev/null +++ b/cpu/stm32f0/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f0/periph/gpio.c b/cpu/stm32f0/periph/gpio.c new file mode 100644 index 000000000..75ead8ad2 --- /dev/null +++ b/cpu/stm32f0/periph/gpio.c @@ -0,0 +1,716 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Low-level GPIO driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include "cpu.h" +#include "periph/gpio.h" +#include "periph_conf.h" + +typedef struct { + void (*cb)(void); +} gpio_state_t; + +static gpio_state_t config[GPIO_NUMOF]; + +int gpio_init_out(gpio_t dev, gpio_pp_t pullup) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + GPIO_0_CLKEN(); + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + GPIO_1_CLKEN(); + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + GPIO_2_CLKEN(); + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + GPIO_3_CLKEN(); + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + GPIO_4_CLKEN(); + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + GPIO_5_CLKEN(); + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + GPIO_6_CLKEN(); + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + GPIO_7_CLKEN(); + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + GPIO_8_CLKEN(); + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + GPIO_9_CLKEN(); + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + GPIO_10_CLKEN(); + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + GPIO_11_CLKEN(); + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + port->MODER &= ~(2 << (2 * pin)); /* set pin to output mode */ + port->MODER |= (1 << (2 * pin)); + port->OTYPER &= ~(1 << pin); /* set to push-pull configuration */ + port->OSPEEDR |= (3 << (2 * pin)); /* set to high speed */ + port->PUPDR &= ~(3 << (2 * pin)); /* configure push-pull resistors */ + port->PUPDR |= (pullup << (2 * pin)); + port->ODR &= ~(1 << pin); /* set pin to low signal */ + + return 0; /* all OK */ +} + +int gpio_init_in(gpio_t dev, gpio_pp_t pullup) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + GPIO_0_CLKEN(); + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + GPIO_1_CLKEN(); + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + GPIO_2_CLKEN(); + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + GPIO_3_CLKEN(); + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + GPIO_4_CLKEN(); + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + GPIO_5_CLKEN(); + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + GPIO_6_CLKEN(); + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + GPIO_7_CLKEN(); + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + GPIO_8_CLKEN(); + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + GPIO_9_CLKEN(); + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + GPIO_10_CLKEN(); + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + GPIO_11_CLKEN(); + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + port->MODER &= ~(3 << (2 * pin)); /* configure pin as input */ + port->PUPDR &= ~(3 << (2 * pin)); /* configure push-pull resistors */ + port->PUPDR |= (pullup << (2 * pin)); + + return 0; /* everything alright here */ +} + +int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, void (*cb)(void)) +{ + int res; + uint32_t pin; + + /* configure pin as input */ + res = gpio_init_in(dev, pullup); + if (res < 0) { + return res; + } + + /* set interrupt priority (its the same for all EXTI interrupts) */ + NVIC_SetPriority(EXTI0_1_IRQn, GPIO_IRQ_PRIO); + NVIC_SetPriority(EXTI2_3_IRQn, GPIO_IRQ_PRIO); + NVIC_SetPriority(EXTI4_15_IRQn, GPIO_IRQ_PRIO); + + /* enable clock of the SYSCFG module for EXTI configuration */ + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGCOMPEN; + + /* read pin number, set EXIT channel and enable global interrupt for EXTI channel */ + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + pin = GPIO_0_PIN; + GPIO_0_EXTI_CFG(); + NVIC_SetPriority(GPIO_0_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_0_IRQ); + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + pin = GPIO_1_PIN; + GPIO_1_EXTI_CFG(); + NVIC_SetPriority(GPIO_1_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_1_IRQ); + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + pin = GPIO_2_PIN; + GPIO_2_EXTI_CFG(); + NVIC_SetPriority(GPIO_2_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_2_IRQ); + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + pin = GPIO_3_PIN; + GPIO_3_EXTI_CFG(); + NVIC_SetPriority(GPIO_3_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_3_IRQ); + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + pin = GPIO_4_PIN; + GPIO_4_EXTI_CFG(); + NVIC_SetPriority(GPIO_4_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_4_IRQ); + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + pin = GPIO_5_PIN; + GPIO_5_EXTI_CFG(); + NVIC_SetPriority(GPIO_5_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_5_IRQ); + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + pin = GPIO_6_PIN; + GPIO_6_EXTI_CFG(); + NVIC_SetPriority(GPIO_6_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_6_IRQ); + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + pin = GPIO_7_PIN; + GPIO_7_EXTI_CFG(); + NVIC_SetPriority(GPIO_7_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_7_IRQ); + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + pin = GPIO_8_PIN; + GPIO_8_EXTI_CFG(); + NVIC_SetPriority(GPIO_8_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_8_IRQ); + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + pin = GPIO_9_PIN; + GPIO_9_EXTI_CFG(); + NVIC_SetPriority(GPIO_9_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_9_IRQ); + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + pin = GPIO_10_PIN; + GPIO_10_EXTI_CFG(); + NVIC_SetPriority(GPIO_10_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_10_IRQ); + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + pin = GPIO_11_PIN; + GPIO_11_EXTI_CFG(); + NVIC_SetPriority(GPIO_11_IRQ, GPIO_IRQ_PRIO); + NVIC_EnableIRQ(GPIO_11_IRQ); + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + /* set callback */ + config[dev].cb = cb; + + /* configure the event that triggers an interrupt */ + switch (flank) { + case GPIO_RISING: + EXTI->RTSR |= (1 << pin); + EXTI->FTSR &= ~(1 << pin); + break; + case GPIO_FALLING: + EXTI->RTSR &= ~(1 << pin); + EXTI->FTSR |= (1 << pin); + break; + case GPIO_BOTH: + EXTI->RTSR |= (1 << pin); + EXTI->FTSR |= (1 << pin); + break; + } + + /* unmask the pins interrupt channel */ + EXTI->IMR |= (1 << pin); + + return 0; +} + +int gpio_read(gpio_t dev) +{ + GPIO_TypeDef *port; + uint32_t pin; + + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + port = GPIO_0_PORT; + pin = GPIO_0_PIN; + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + port = GPIO_1_PORT; + pin = GPIO_1_PIN; + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + port = GPIO_2_PORT; + pin = GPIO_2_PIN; + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + port = GPIO_3_PORT; + pin = GPIO_3_PIN; + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + port = GPIO_4_PORT; + pin = GPIO_4_PIN; + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + port = GPIO_5_PORT; + pin = GPIO_5_PIN; + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + port = GPIO_6_PORT; + pin = GPIO_6_PIN; + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + port = GPIO_7_PORT; + pin = GPIO_7_PIN; + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + port = GPIO_8_PORT; + pin = GPIO_8_PIN; + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + port = GPIO_9_PORT; + pin = GPIO_9_PIN; + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + port = GPIO_10_PORT; + pin = GPIO_10_PIN; + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + port = GPIO_11_PORT; + pin = GPIO_11_PIN; + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + if (port->MODER & (1 << (pin * 2))) { /* if configured as output */ + return port->ODR & (1 << pin); /* read output data register */ + } else { + return port->IDR & (1 << pin); /* else read input data register */ + } +} + +int gpio_set(gpio_t dev) +{ + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + GPIO_0_PORT->ODR |= (1 << GPIO_0_PIN); + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + GPIO_1_PORT->ODR |= (1 << GPIO_1_PIN); + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + GPIO_2_PORT->ODR |= (1 << GPIO_2_PIN); + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + GPIO_3_PORT->ODR |= (1 << GPIO_3_PIN); + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + GPIO_4_PORT->ODR |= (1 << GPIO_4_PIN); + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + GPIO_5_PORT->ODR |= (1 << GPIO_5_PIN); + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + GPIO_6_PORT->ODR |= (1 << GPIO_6_PIN); + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + GPIO_7_PORT->ODR |= (1 << GPIO_7_PIN); + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + GPIO_8_PORT->ODR |= (1 << GPIO_8_PIN); + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + GPIO_9_PORT->ODR |= (1 << GPIO_9_PIN); + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + GPIO_10_PORT->ODR |= (1 << GPIO_10_PIN); + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + GPIO_11_PORT->ODR |= (1 << GPIO_11_PIN); + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + return 0; +} + +int gpio_clear(gpio_t dev) +{ + switch (dev) { +#ifdef GPIO_0_EN + case GPIO_0: + GPIO_0_PORT->ODR &= ~(1 << GPIO_0_PIN); + break; +#endif +#ifdef GPIO_1_EN + case GPIO_1: + GPIO_1_PORT->ODR &= ~(1 << GPIO_1_PIN); + break; +#endif +#ifdef GPIO_2_EN + case GPIO_2: + GPIO_2_PORT->ODR &= ~(1 << GPIO_2_PIN); + break; +#endif +#ifdef GPIO_3_EN + case GPIO_3: + GPIO_3_PORT->ODR &= ~(1 << GPIO_3_PIN); + break; +#endif +#ifdef GPIO_4_EN + case GPIO_4: + GPIO_4_PORT->ODR &= ~(1 << GPIO_4_PIN); + break; +#endif +#ifdef GPIO_5_EN + case GPIO_5: + GPIO_5_PORT->ODR &= ~(1 << GPIO_5_PIN); + break; +#endif +#ifdef GPIO_6_EN + case GPIO_6: + GPIO_6_PORT->ODR &= ~(1 << GPIO_6_PIN); + break; +#endif +#ifdef GPIO_7_EN + case GPIO_7: + GPIO_7_PORT->ODR &= ~(1 << GPIO_7_PIN); + break; +#endif +#ifdef GPIO_8_EN + case GPIO_8: + GPIO_8_PORT->ODR &= ~(1 << GPIO_8_PIN); + break; +#endif +#ifdef GPIO_9_EN + case GPIO_9: + GPIO_9_PORT->ODR &= ~(1 << GPIO_9_PIN); + break; +#endif +#ifdef GPIO_10_EN + case GPIO_10: + GPIO_10_PORT->ODR &= ~(1 << GPIO_10_PIN); + break; +#endif +#ifdef GPIO_11_EN + case GPIO_11: + GPIO_11_PORT->ODR &= ~(1 << GPIO_11_PIN); + break; +#endif + case GPIO_UNDEFINED: + default: + return -1; + } + + return 0; +} + +int gpio_toggle(gpio_t dev) +{ + if (gpio_read(dev)) { + return gpio_clear(dev); + } else { + return gpio_set(dev); + } +} + +int gpio_write(gpio_t dev, int value) +{ + if (value) { + return gpio_set(dev); + } else { + return gpio_clear(dev); + } +} + +__attribute__((naked)) void isr_exti0_1(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR0) { + EXTI->PR |= EXTI_PR_PR0; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_0].cb(); + } + else if (EXTI->PR & EXTI_PR_PR1) { + EXTI->PR |= EXTI_PR_PR1; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_1].cb(); + } + ISR_EXIT(); +} + +__attribute__((naked)) void isr_exti2_3(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR2) { + EXTI->PR |= EXTI_PR_PR2; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_2].cb(); + } + else if (EXTI->PR & EXTI_PR_PR3) { + EXTI->PR |= EXTI_PR_PR3; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_3].cb(); + } + ISR_EXIT(); +} + +__attribute__((naked)) void isr_exti4_15(void) +{ + ISR_ENTER(); + if (EXTI->PR & EXTI_PR_PR4) { + EXTI->PR |= EXTI_PR_PR4; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_4].cb(); + } + else if (EXTI->PR & EXTI_PR_PR5) { + EXTI->PR |= EXTI_PR_PR5; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_5].cb(); + } + else if (EXTI->PR & EXTI_PR_PR6) { + EXTI->PR |= EXTI_PR_PR6; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_6].cb(); + } + else if (EXTI->PR & EXTI_PR_PR7) { + EXTI->PR |= EXTI_PR_PR7; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_7].cb(); + } + else if (EXTI->PR & EXTI_PR_PR8) { + EXTI->PR |= EXTI_PR_PR8; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_8].cb(); + } + else if (EXTI->PR & EXTI_PR_PR9) { + EXTI->PR |= EXTI_PR_PR9; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_9].cb(); + } + else if (EXTI->PR & EXTI_PR_PR10) { + EXTI->PR |= EXTI_PR_PR10; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_10].cb(); + } + else if (EXTI->PR & EXTI_PR_PR11) { + EXTI->PR |= EXTI_PR_PR11; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_11].cb(); + } + else if (EXTI->PR & EXTI_PR_PR12) { + EXTI->PR |= EXTI_PR_PR12; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_12].cb(); + } + else if (EXTI->PR & EXTI_PR_PR13) { + EXTI->PR |= EXTI_PR_PR13; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_13].cb(); + } + else if (EXTI->PR & EXTI_PR_PR14) { + EXTI->PR |= EXTI_PR_PR14; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_14].cb(); + } + else if (EXTI->PR & EXTI_PR_PR15) { + EXTI->PR |= EXTI_PR_PR15; /* clear status bit by writing a 1 to it */ + config[GPIO_IRQ_15].cb(); + } + ISR_EXIT(); +} diff --git a/cpu/stm32f0/periph/timer.c b/cpu/stm32f0/periph/timer.c new file mode 100644 index 000000000..45df80e6d --- /dev/null +++ b/cpu/stm32f0/periph/timer.c @@ -0,0 +1,330 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Low-level timer driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "cpu.h" +#include "board.h" +#include "periph_conf.h" +#include "periph/timer.h" + + +static inline void irq_handler(tim_t timer, TIM_TypeDef *dev); + +typedef struct { + void (*cb)(int); +} timer_conf_t; + +/** + * Timer state memory + */ +timer_conf_t config[TIMER_NUMOF]; + + +int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int)) +{ + TIM_TypeDef *timer; + + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + /* enable timer peripheral clock */ + TIMER_0_CLKEN(); + /* set timer's IRQ priority */ + NVIC_SetPriority(TIMER_0_IRQ_CHAN, TIMER_0_IRQ_PRIO); + /* select timer */ + timer = TIMER_0_DEV; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + /* enable timer peripheral clock */ + TIMER_1_CLKEN(); + /* set timer's IRQ priority */ + NVIC_SetPriority(TIMER_1_IRQ_CHAN, TIMER_1_IRQ_PRIO); + /* select timer */ + timer = TIMER_1_DEV; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + + /* set callback function */ + config[dev].cb = callback; + + /* set timer to run in counter mode */ + timer->CR1 |= TIM_CR1_URS; + + /* set auto-reload and prescaler values and load new values */ + timer->ARR = TIMER_0_MAX_VALUE; + timer->PSC = TIMER_0_PRESCALER * ticks_per_us; + timer->EGR |= TIM_EGR_UG; + + /* enable the timer's interrupt */ + timer_irq_enable(dev); + + /* start the timer */ + timer_start(dev); + + return 0; +} + +int timer_set(tim_t dev, int channel, unsigned int timeout) +{ + int now = timer_read(dev); + return timer_set_absolute(dev, channel, now + timeout - 1); +} + +int timer_set_absolute(tim_t dev, int channel, unsigned int value) +{ + TIM_TypeDef *timer = NULL; + + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + timer = TIMER_0_DEV; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + timer = TIMER_1_DEV; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + + switch (channel) { + case 0: + timer->CCR1 = value; + timer->SR &= ~TIM_SR_CC1IF; + timer->DIER |= TIM_DIER_CC1IE; + break; + case 1: + timer->CCR2 = value; + timer->SR &= ~TIM_SR_CC2IF; + timer->DIER |= TIM_DIER_CC2IE; + break; + case 2: + timer->CCR3 = value; + timer->SR &= ~TIM_SR_CC3IF; + timer->DIER |= TIM_DIER_CC3IE; + break; + case 3: + timer->CCR4 = value; + timer->SR &= ~TIM_SR_CC4IF; + timer->DIER |= TIM_DIER_CC4IE; + break; + default: + return -1; + } + return 0; +} + +int timer_clear(tim_t dev, int channel) +{ + TIM_TypeDef *timer; + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + timer = TIMER_0_DEV; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + timer = TIMER_1_DEV; + break; +#endif + case TIMER_UNDEFINED: + default: + return -1; + } + switch (channel) { + case 0: + timer->DIER &= ~TIM_DIER_CC1IE; + break; + case 1: + timer->DIER &= ~TIM_DIER_CC2IE; + break; + case 2: + timer->DIER &= ~TIM_DIER_CC3IE; + break; + case 3: + timer->DIER &= ~TIM_DIER_CC4IE; + break; + default: + return -1; + } + return 0; +} + +unsigned int timer_read(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + return TIMER_0_DEV->CNT; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + return TIMER_1_DEV->CNT; + break; +#endif + case TIMER_UNDEFINED: + default: + return 0; + } +} + +void timer_start(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CR1 |= TIM_CR1_CEN; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CR1 |= TIM_CR1_CEN; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_stop(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CR1 &= ~TIM_CR1_CEN; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CR1 &= ~TIM_CR1_CEN; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_irq_enable(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + NVIC_EnableIRQ(TIMER_0_IRQ_CHAN); + break; +#endif +#if TIMER_1_EN + case TIMER_1: + NVIC_EnableIRQ(TIMER_1_IRQ_CHAN); + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_irq_disable(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + NVIC_DisableIRQ(TIMER_0_IRQ_CHAN); + break; +#endif +#if TIMER_1_EN + case TIMER_1: + NVIC_DisableIRQ(TIMER_1_IRQ_CHAN); + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +void timer_reset(tim_t dev) +{ + switch (dev) { +#if TIMER_0_EN + case TIMER_0: + TIMER_0_DEV->CNT = 0; + break; +#endif +#if TIMER_1_EN + case TIMER_1: + TIMER_1_DEV->CNT = 0; + break; +#endif + case TIMER_UNDEFINED: + break; + } +} + +#if TIMER_0_EN +__attribute__ ((naked)) void TIMER_0_ISR(void) +{ + ISR_ENTER(); + irq_handler(TIMER_0, TIMER_0_DEV); + ISR_EXIT(); +} +#endif + +#if TIMER_1_EN +__attribute__ ((naked)) void TIMER_1_ISR(void) +{ + ISR_ENTER(); + irq_handler(TIMER_1, TIMER_1_DEV); + ISR_EXIT(); +} +#endif + +static inline void irq_handler(tim_t timer, TIM_TypeDef *dev) +{ + if (dev->SR & TIM_SR_CC1IF) { + dev->DIER &= ~TIM_DIER_CC1IE; + dev->SR &= ~TIM_SR_CC1IF; + config[timer].cb(0); + } + else if (dev->SR & TIM_SR_CC2IF) { + dev->DIER &= ~TIM_DIER_CC2IE; + dev->SR &= ~TIM_SR_CC2IF; + config[timer].cb(1); + } + else if (dev->SR & TIM_SR_CC3IF) { + dev->DIER &= ~TIM_DIER_CC3IE; + dev->SR &= ~TIM_SR_CC3IF; + config[timer].cb(2); + } + else if (dev->SR & TIM_SR_CC4IF) { + dev->DIER &= ~TIM_DIER_CC4IE; + dev->SR &= ~TIM_SR_CC4IF; + config[timer].cb(3); + } +} diff --git a/cpu/stm32f0/periph/uart.c b/cpu/stm32f0/periph/uart.c new file mode 100644 index 000000000..39bdf6fae --- /dev/null +++ b/cpu/stm32f0/periph/uart.c @@ -0,0 +1,309 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Low-level UART driver implementation + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "cpu.h" +#include "board.h" +#include "periph_conf.h" +#include "periph/uart.h" + + +/** + * @brief Each UART device has to store two callbacks. + */ +typedef struct { + void (*rx_cb)(char); + void (*tx_cb)(void); +} uart_conf_t; + + +/** + * @brief Unified interrupt handler for all UART devices + * + * @param uartnum the number of the UART that triggered the ISR + * @param uart the UART device that triggered the ISR + */ +static inline void irq_handler(uart_t uartnum, USART_TypeDef *uart); + + +/** + * @brief Allocate memory to store the callback functions. + */ +static uart_conf_t config[UART_NUMOF]; + + +int uart_init(uart_t uart, uint32_t baudrate, void (*rx_cb)(char), void (*tx_cb)(void)) +{ + int res; + + /* initialize UART in blocking mode first */ + res = uart_init_blocking(uart, baudrate); + if (res < 0) { + return res; + } + + /* enable global interrupt and configure the interrupts priority */ + switch (uart) { +#if UART_0_EN + case UART_0: + NVIC_SetPriority(UART_0_IRQ, UART_IRQ_PRIO); + NVIC_EnableIRQ(UART_0_IRQ); + UART_0_DEV->CR1 |= USART_CR1_RXNEIE; + break; +#endif +#if UART_1_EN + case UART_1: + NVIC_SetPriority(UART_1_IRQ, UART_IRQ_PRIO); + NVIC_EnableIRQ(UART_1_IRQ); + UART_1_DEV->CR1 |= USART_CR1_RXNEIE; + break; +#endif + case UART_UNDEFINED: + default: + return -2; + } + + /* register callbacks */ + config[uart].rx_cb = rx_cb; + config[uart].tx_cb = tx_cb; + + return 0; +} + +int uart_init_blocking(uart_t uart, uint32_t baudrate) +{ + USART_TypeDef *dev; + GPIO_TypeDef *port; + uint32_t rx_pin, tx_pin; + uint8_t af; + float divider; + uint16_t mantissa; + uint8_t fraction; + + /* enable UART and port clocks and select devices */ + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + port = UART_0_PORT; + rx_pin = UART_0_RX_PIN; + tx_pin = UART_0_TX_PIN; + af = UART_0_AF; + /* enable clocks */ + UART_0_CLKEN(); + UART_0_PORT_CLKEN(); + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + port = UART_1_PORT; + tx_pin = UART_1_TX_PIN; + rx_pin = UART_1_RX_PIN; + af = UART_1_AF; + /* enable clocks */ + UART_1_CLKEN(); + UART_1_PORT_CLKEN(); + break; +#endif + case UART_UNDEFINED: + default: + return -2; + } + + /* configure RX and TX pins, set pin to use alternative function mode */ + port->MODER &= ~(3 << (rx_pin * 2) | 3 << (tx_pin * 2)); + port->MODER |= 2 << (rx_pin * 2) | 2 << (tx_pin * 2); + /* and assign alternative function */ + if (rx_pin < 8) { + port->AFR[0] &= ~(0xf << (rx_pin * 4)); + port->AFR[0] |= af << (rx_pin * 4); + } + else { + port->AFR[1] &= ~(0xf << ((rx_pin - 16) * 4)); + port->AFR[1] |= af << ((rx_pin - 16) * 4); + } + if (tx_pin < 8) { + port->AFR[0] &= ~(0xf << (tx_pin * 4)); + port->AFR[0] |= af << (tx_pin * 4); + } + else { + port->AFR[1] &= ~(0xf << ((tx_pin - 16) * 4)); + port->AFR[1] |= af << ((tx_pin - 16) * 4); + } + + /* configure UART to mode 8N1 with given baudrate */ + divider = ((float)F_CPU) / (16 * baudrate); + mantissa = (uint16_t)floorf(divider); + fraction = (uint8_t)floorf((divider - mantissa) * 16); + dev->BRR = 0; + dev->BRR |= ((mantissa & 0x0fff) << 4) | (0x0f & fraction); + + /* enable receive and transmit mode */ + dev->CR1 |= USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; + + return 0; +} + +void uart_tx_begin(uart_t uart) +{ + switch (uart) { +#if UART_1_EN + case UART_0: + UART_0_DEV->CR1 |= USART_CR1_TXEIE; + break; +#endif +#if UART_0_EN + case UART_1: + UART_1_DEV->CR1 |= USART_CR1_TXEIE; + break; +#endif + case UART_UNDEFINED: + break; + } +} + +#include +void uart_tx_end(uart_t uart) +{ + switch (uart) { +#if UART_0_EN + case UART_0: + UART_0_DEV->CR1 &= ~USART_CR1_TXEIE; + break; +#endif +#if UART_1_EN + case UART_1: + UART_1_DEV->CR1 &= ~USART_CR1_TXEIE; + break; +#endif + case UART_UNDEFINED: + break; + } +} + +int uart_write(uart_t uart, char data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -1; + } + + if (dev->ISR & USART_ISR_TXE) { + dev->TDR = (uint8_t)data; + } + + return 0; +} + +int uart_read_blocking(uart_t uart, char *data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -1; + } + + while (!(dev->ISR & USART_ISR_RXNE)); + *data = (char)dev->RDR; + + return 1; +} + +int uart_write_blocking(uart_t uart, char data) +{ + USART_TypeDef *dev; + + switch (uart) { +#if UART_0_EN + case UART_0: + dev = UART_0_DEV; + break; +#endif +#if UART_1_EN + case UART_1: + dev = UART_1_DEV; + break; +#endif + case UART_UNDEFINED: + default: + return -1; + } + + while (!(dev->ISR & USART_ISR_TXE)); + dev->TDR = (uint8_t)data; + + return 1; +} + +__attribute__((naked)) void UART_0_ISR(void) +{ + ISR_ENTER(); + irq_handler(UART_0, UART_0_DEV); + ISR_EXIT(); +} + +__attribute__((naked)) void UART_1_ISR(void) +{ + ISR_ENTER(); + irq_handler(UART_1, UART_1_DEV); + ISR_EXIT(); +} + +static inline void irq_handler(uint8_t uartnum, USART_TypeDef *dev) +{ + if (dev->ISR & USART_ISR_RXNE) { + char data = (char)dev->RDR; + config[uartnum].rx_cb(data); + } + else if (dev->ISR & USART_ISR_ORE) { + /* do nothing on overrun */ + dev->ICR |= USART_ICR_ORECF; + } + else if (dev->ISR & USART_ISR_TXE) { + config[uartnum].tx_cb(); + } +} diff --git a/cpu/stm32f0/reboot_arch.c b/cpu/stm32f0/reboot_arch.c new file mode 100644 index 000000000..2b249606a --- /dev/null +++ b/cpu/stm32f0/reboot_arch.c @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Implementation of the kernels reboot interface + * + * @author Hauke Petersen + * + * @} + */ + +#include + +#include "arch/reboot_arch.h" +#include "cpu.h" + + +int reboot_arch(int mode) +{ + printf("Going into reboot, mode %i\n", mode); + + NVIC_SystemReset(); + + return 0; +} diff --git a/cpu/stm32f0/startup.c b/cpu/stm32f0/startup.c new file mode 100644 index 000000000..d29d1ae69 --- /dev/null +++ b/cpu/stm32f0/startup.c @@ -0,0 +1,205 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief Startup code and interrupt vector definition + * + * @author Hauke Petersen + * + * @} + */ + +#include + + +/** + * memory markers as defined in the linker script + */ +extern uint32_t _sfixed; +extern uint32_t _efixed; +extern uint32_t _etext; +extern uint32_t _srelocate; +extern uint32_t _erelocate; +extern uint32_t _szero; +extern uint32_t _ezero; +extern uint32_t _sstack; +extern uint32_t _estack; + +/** + * @brief functions for initializing the board, std-lib and kernel + */ +extern void board_init(void); +extern void kernel_init(void); +extern void __libc_init_array(void); + +/** + * @brief This function is the entry point after a system reset + * + * After a system reset, the following steps are necessary and carried out: + * 1. load data section from flash to ram + * 2. overwrite uninitialized data section (BSS) with zeros + * 3. initialize the newlib + * 4. initialize the board (sync clock, setup std-IO) + * 5. initialize and start RIOTs kernel + */ +void reset_handler(void) +{ + uint32_t *dst; + uint32_t *src = &_etext; + + /* load data section from flash to ram */ + for (dst = &_srelocate; dst < &_erelocate; ) { + *(dst++) = *(src++); + } + + /* default bss section to zero */ + for (dst = &_szero; dst < &_ezero; ) { + *(dst++) = 0; + } + + /* initialize the board and startup the kernel */ + board_init(); + /* initialize std-c library (this should be done after board_init) */ + __libc_init_array(); + /* startup the kernel */ + kernel_init(); +} + +/** + * @brief Default handler is called in case no interrupt handler was defined + */ +void dummy_handler(void) +{ + while (1) {asm ("nop");} +} + +void isr_nmi(void) +{ + while (1) {asm ("nop");} +} + +void isr_mem_manage(void) +{ + while (1) {asm ("nop");} +} + +void isr_debug_mon(void) +{ + while (1) {asm ("nop");} +} + +void isr_hard_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_bus_fault(void) +{ + while (1) {asm ("nop");} +} + +void isr_usage_fault(void) +{ + while (1) {asm ("nop");} +} + +/* Cortex-M specific interrupt vectors */ +void isr_svc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_systick(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* STM32F051R8 specific interrupt vector */ +void isr_wwdg(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_pvd(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rtc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_flash(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_rcc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti0_1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti2_3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_exti4_15(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_ts(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_ch1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_ch2_3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_dma1_ch4_5(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_adc1_comp(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_brk_up_trg_com(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim1_cc(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim3(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim6_dac(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim14(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim15(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim16(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_tim17(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_i2c2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_spi2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart1(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_usart2(void) __attribute__ ((weak, alias("dummy_handler"))); +void isr_cec(void) __attribute__ ((weak, alias("dummy_handler"))); + +/* interrupt vector table */ +__attribute__ ((section(".vectors"))) +const void *interrupt_vector[] = { + /* Stack pointer */ + (void*) (&_estack), /* pointer to the top of the empty stack */ + /* Cortex-M handlers */ + (void*) reset_handler, /* entry point of the program */ + (void*) isr_nmi, /* non maskable interrupt handler */ + (void*) isr_hard_fault, /* if you end up here its not good */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) isr_svc, /* system call interrupt */ + (void*) (0UL), /* reserved */ + (void*) (0UL), /* reserved */ + (void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */ + (void*) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* STM specific peripheral handlers */ + (void*) isr_wwdg, /* windowed watchdog */ + (void*) isr_pvd, /* power control */ + (void*) isr_rtc, /* real time clock */ + (void*) isr_flash, /* flash memory controller */ + (void*) isr_rcc, /* reset and clock control */ + (void*) isr_exti0_1, /* external interrupt lines 0 and 1 */ + (void*) isr_exti2_3, /* external interrupt lines 2 and 3 */ + (void*) isr_exti4_15, /* external interrupt lines 4 to 15 */ + (void*) isr_ts, /* touch sensing input*/ + (void*) isr_dma1_ch1, /* direct memory access controller 1, channel 1*/ + (void*) isr_dma1_ch2_3, /* direct memory access controller 1, channel 2 and 3*/ + (void*) isr_dma1_ch4_5, /* direct memory access controller 1, channel 4 and 5*/ + (void*) isr_adc1_comp, /* analog digital converter */ + (void*) isr_tim1_brk_up_trg_com, /* timer 1 break, update, trigger and communication */ + (void*) isr_tim1_cc, /* timer 1 capture compare */ + (void*) isr_tim2, /* timer 2 */ + (void*) isr_tim3, /* timer 3 */ + (void*) isr_tim6_dac, /* timer 6 and digital to analog converter */ + (void*) (0UL), /* reserved */ + (void*) isr_tim14, /* timer 14 */ + (void*) isr_tim15, /* timer 15 */ + (void*) isr_tim16, /* timer 16 */ + (void*) isr_tim17, /* timer 17 */ + (void*) isr_i2c1, /* I2C 1 */ + (void*) isr_i2c2, /* I2C 2 */ + (void*) isr_spi1, /* SPI 1 */ + (void*) isr_spi2, /* SPI 2 */ + (void*) isr_usart1, /* USART 1 */ + (void*) isr_usart2, /* USART 2 */ + (void*) (0UL), /* reserved */ + (void*) isr_cec, /* consumer electronics control */ + (void*) (0UL) /* reserved */ +}; diff --git a/cpu/stm32f0/stm32f051r8_linkerscript.ld b/cpu/stm32f0/stm32f051r8_linkerscript.ld new file mode 100644 index 000000000..c48ffa56e --- /dev/null +++ b/cpu/stm32f0/stm32f051r8_linkerscript.ld @@ -0,0 +1,142 @@ +/* ---------------------------------------------------------------------------- + * SAM Software Package License + * ---------------------------------------------------------------------------- + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is met: + * + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. + * + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * ---------------------------------------------------------------------------- + */ + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +/* The stack size used by the application. NOTE: you need to adjust */ +STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0xa00 ; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(0x4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + } > ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(8); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} diff --git a/cpu/stm32f0/syscalls.c b/cpu/stm32f0/syscalls.c new file mode 100644 index 000000000..cc72c9655 --- /dev/null +++ b/cpu/stm32f0/syscalls.c @@ -0,0 +1,277 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f0 + * @{ + * + * @file + * @brief NewLib system calls implementations for STM32F0 + * + * @author Michael Baar + * @author Stefan Pfeiffer + * @author Hauke Petersen + * + * @} + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "thread.h" +#include "kernel.h" +#include "irq.h" +#include "board.h" +#include "periph/uart.h" + + +/** + * manage the heap + */ +extern uint32_t _end; /* address of last used memory cell */ +caddr_t heap_top = (caddr_t)&_end + 4; + +/** + * @brief Initialize NewLib, called by __libc_init_array() from the startup script + */ +void _init(void) +{ + uart_init_blocking(STDIO, 115200); +} + +/** + * @brief Free resources on NewLib de-initialization, not used for RIOT + */ +void _fini(void) +{ + // nothing to do here +} + +/** + * @brief Exit a program without cleaning up files + * + * If your system doesn't provide this, it is best to avoid linking with subroutines that + * require it (exit, system). + * + * @param n the exit code, 0 for all OK, >0 for not OK + */ +void _exit(int n) +{ + printf("#! exit %i: resetting\n", n); + NVIC_SystemReset(); + while(1); +} + +/** + * @brief Allocate memory from the heap. + * + * The current heap implementation is very rudimentary, it is only able to allocate + * memory. But it does not + * - check if the returned address is valid (no check if the memory very exists) + * - have any means to free memory again + * + * TODO: check if the requested memory is really available + * + * @return [description] + */ +caddr_t _sbrk_r(struct _reent *r, size_t incr) +{ + unsigned int state = disableIRQ(); + caddr_t res = heap_top; + heap_top += incr; + restoreIRQ(state); + return res; +} + +/** + * @brief Get the process-ID of the current thread + * + * @return the process ID of the current thread + */ +int _getpid(void) +{ + return sched_active_thread->pid; +} + +/** + * @brief Send a signal to a given thread + * + * @param r TODO + * @param pid TODO + * @param sig TODO + * + * @return TODO + */ +int _kill_r(struct _reent *r, int pid, int sig) +{ + r->_errno = ESRCH; /* not implemented yet */ + return -1; +} + +/** + * @brief Open a file + * + * @param r TODO + * @param name TODO + * @param mode TODO + * + * @return TODO + */ +int _open_r(struct _reent *r, const char *name, int mode) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Read from a file + * + * All input is read from STDIO. The function will block until a byte is actually read. + * + * Note: the read function does not buffer - data will be lost if the function is not + * called fast enough. + * + * TODO: implement more sophisticated read call. + * + * @param r TODO + * @param fd TODO + * @param buffer TODO + * @param int TODO + * + * @return TODO + */ +int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count) +{ + char c; + char *buff = (char*)buffer; + uart_read_blocking(STDIO, &c); + buff[0] = c; + return 1; +} + +/** + * @brief Write characters to a file + * + * All output is currently directed to STDIO, independent of the given file descriptor. + * The write call will further block until the byte is actually written to the UART. + * + * TODO: implement more sophisticated write call. + * + * @param r TODO + * @param fd TODO + * @param data TODO + * @param int TODO + * + * @return TODO + */ +int _write_r(struct _reent *r, int fd, const void *data, unsigned int count) +{ + char *c = (char*)data; + for (int i = 0; i < count; i++) { + uart_write_blocking(STDIO, c[i]); + } + return count; +} + +/** + * @brief Close a file + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _close_r(struct _reent *r, int fd) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Set position in a file + * + * @param r TODO + * @param fd TODO + * @param pos TODO + * @param dir TODO + * + * @return TODO + */ +_off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of an open file + * + * @param r TODO + * @param fd TODO + * @param stat TODO + * + * @return TODO + */ +int _fstat_r(struct _reent *r, int fd, struct stat * st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Status of a file (by name) + * + * @param r TODO + * @param name TODO + * @param stat TODO + * + * @return TODO + */ +int _stat_r(struct _reent *r, char *name, struct stat *st) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +} + +/** + * @brief Query whether output stream is a terminal + * + * @param r TODO + * @param fd TODO + * + * @return TODO + */ +int _isatty_r(struct _reent *r, int fd) +{ + r->_errno = 0; + if(fd == STDOUT_FILENO || fd == STDERR_FILENO) { + return 1; + } + else { + return 0; + } +} + +/** + * @brief Remove a file's directory entry + * + * @param r TODO + * @param path TODO + * + * @return TODO + */ +int _unlink_r(struct _reent *r, char* path) +{ + r->_errno = ENODEV; /* not implemented yet */ + return -1; +}