From b8dd144e033293999183c7ba3e30b5075e737751 Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Mon, 18 May 2015 18:47:17 +0200 Subject: [PATCH 1/8] cpu: unified cortexm_common folder - removed coretx-m[0|3|4] - moved their content to cortexm_common - adjusted cortex Makefiles to this new name - adjusted cortex Makefiles new structure --- ...common => Makefile.include.cortexm_common} | 13 +- ...common => Makefile.include.cortexm_common} | 36 +- cpu/cortex-m0_common/Makefile | 4 - cpu/cortex-m0_common/Makefile.include | 2 - cpu/cortex-m0_common/include/cpu.h | 59 -- cpu/cortex-m0_common/irq_arch.c | 58 -- cpu/cortex-m0_common/thread_arch.c | 262 ------ cpu/cortex-m3_common/Makefile.include | 3 - cpu/cortex-m3_common/atomic_arch.c | 46 - cpu/cortex-m3_common/include/core_cmFunc.h | 651 ------------- cpu/cortex-m3_common/include/core_cmInstr.h | 887 ------------------ cpu/cortex-m3_common/irq_arch.c | 58 -- cpu/cortex-m3_common/panic.c | 34 - cpu/cortex-m3_common/reboot_arch.c | 34 - cpu/cortex-m3_common/thread_arch.c | 227 ----- cpu/cortex-m4_common/Makefile | 4 - cpu/cortex-m4_common/Makefile.include | 2 - cpu/cortex-m4_common/include/core_cmFunc.h | 651 ------------- cpu/cortex-m4_common/include/core_cmInstr.h | 887 ------------------ cpu/cortex-m4_common/include/cpu.h | 64 -- cpu/cortex-m4_common/panic.c | 34 - cpu/cortex-m4_common/reboot_arch.c | 34 - cpu/cortex-m4_common/thread_arch.c | 256 ----- .../Makefile | 0 cpu/cortexm_common/Makefile.include | 2 + .../atomic_arch.c | 6 +- .../include/core_cm0.h | 0 .../include/core_cm0plus.h | 0 .../include/core_cm3.h | 0 .../include/core_cm4.h | 0 .../include/core_cmFunc.h | 0 .../include/core_cmInstr.h | 0 .../include/core_cmSimd.h | 0 .../include/cpu.h | 30 +- .../irq_arch.c | 4 +- .../panic.c | 2 +- .../reboot_arch.c | 4 +- cpu/cortexm_common/thread_arch.c | 353 +++++++ 38 files changed, 399 insertions(+), 4308 deletions(-) rename boards/{Makefile.include.cortex_common => Makefile.include.cortexm_common} (74%) rename cpu/{Makefile.include.cortex_common => Makefile.include.cortexm_common} (69%) delete mode 100644 cpu/cortex-m0_common/Makefile delete mode 100644 cpu/cortex-m0_common/Makefile.include delete mode 100644 cpu/cortex-m0_common/include/cpu.h delete mode 100644 cpu/cortex-m0_common/irq_arch.c delete mode 100644 cpu/cortex-m0_common/thread_arch.c delete mode 100644 cpu/cortex-m3_common/Makefile.include delete mode 100644 cpu/cortex-m3_common/atomic_arch.c delete mode 100644 cpu/cortex-m3_common/include/core_cmFunc.h delete mode 100644 cpu/cortex-m3_common/include/core_cmInstr.h delete mode 100644 cpu/cortex-m3_common/irq_arch.c delete mode 100644 cpu/cortex-m3_common/panic.c delete mode 100644 cpu/cortex-m3_common/reboot_arch.c delete mode 100644 cpu/cortex-m3_common/thread_arch.c delete mode 100644 cpu/cortex-m4_common/Makefile delete mode 100644 cpu/cortex-m4_common/Makefile.include delete mode 100644 cpu/cortex-m4_common/include/core_cmFunc.h delete mode 100644 cpu/cortex-m4_common/include/core_cmInstr.h delete mode 100644 cpu/cortex-m4_common/include/cpu.h delete mode 100644 cpu/cortex-m4_common/panic.c delete mode 100644 cpu/cortex-m4_common/reboot_arch.c delete mode 100644 cpu/cortex-m4_common/thread_arch.c rename cpu/{cortex-m3_common => cortexm_common}/Makefile (100%) create mode 100644 cpu/cortexm_common/Makefile.include rename cpu/{cortex-m4_common => cortexm_common}/atomic_arch.c (87%) rename cpu/{cortex-m0_common => cortexm_common}/include/core_cm0.h (100%) rename cpu/{cortex-m0_common => cortexm_common}/include/core_cm0plus.h (100%) rename cpu/{cortex-m3_common => cortexm_common}/include/core_cm3.h (100%) rename cpu/{cortex-m4_common => cortexm_common}/include/core_cm4.h (100%) rename cpu/{cortex-m0_common => cortexm_common}/include/core_cmFunc.h (100%) rename cpu/{cortex-m0_common => cortexm_common}/include/core_cmInstr.h (100%) rename cpu/{cortex-m4_common => cortexm_common}/include/core_cmSimd.h (100%) rename cpu/{cortex-m3_common => cortexm_common}/include/cpu.h (59%) rename cpu/{cortex-m4_common => cortexm_common}/irq_arch.c (91%) rename cpu/{cortex-m0_common => cortexm_common}/panic.c (95%) rename cpu/{cortex-m0_common => cortexm_common}/reboot_arch.c (88%) create mode 100644 cpu/cortexm_common/thread_arch.c diff --git a/boards/Makefile.include.cortex_common b/boards/Makefile.include.cortexm_common similarity index 74% rename from boards/Makefile.include.cortex_common rename to boards/Makefile.include.cortexm_common index 521638cf8b..3c8b492e7e 100644 --- a/boards/Makefile.include.cortex_common +++ b/boards/Makefile.include.cortexm_common @@ -2,9 +2,6 @@ export PREFIX = arm-none-eabi- include $(RIOTBOARD)/Makefile.include.gnu -# use cortex name of CPU folder, but enable board Makefile to override -export MCPU ?= $(CORTEX) - # define build specific options export CFLAGS_CPU = -mcpu=$(MCPU) -mlittle-endian -mthumb -mno-thumb-interwork $(CFLAGS_FPU) export CFLAGS_STYLE = -std=gnu99 -Wall -Wstrict-prototypes @@ -14,14 +11,8 @@ export CFLAGS_OPT ?= -Os export CFLAGS += $(CFLAGS_CPU) $(CFLAGS_STYLE) $(CFLAGS_LINK) $(CFLAGS_DBG) $(CFLAGS_OPT) export ASFLAGS += $(CFLAGS_CPU) $(CFLAGS_DEBUG) -export LINKFLAGS += -L$(RIOTCPU)/$(CPU) -export LINKFLAGS += $(CFLAGS_DEBUG) $(CFLAGS_CPU) $(CFLAGS_STYLE) -static -lgcc -nostartfiles -T$(LINKERSCRIPT) - -export OFLAGS ?= -O ihex -export FFLAGS ?= flash -export DEBUGGER_FLAGS ?= debug -export DEBUGSERVER_FLAGS ?= debug-server -export RESET_FLAGS ?= reset +export LINKFLAGS += -L$(RIOTCPU)/$(CPU) -T$(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld +export LINKFLAGS += $(CFLAGS_DEBUG) $(CFLAGS_CPU) $(CFLAGS_STYLE) -static -lgcc -nostartfiles # use the nano-specs of the NewLib when available ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null - * @author Hauke Petersen - */ - -#ifndef __CPU_H -#define __CPU_H - -#include "cpu_conf.h" - - -/** - * For downwards compatibility with old RIOT code. - * TODO: remove once core was adjusted - */ -#include "irq.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * @brief Deprecated interrupt control function for backward compatibility - * @{ - */ -#define eINT enableIRQ -#define dINT disableIRQ -/** @} */ - -/** - * @brief Initialization of the CPU - */ -void cpu_init(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __CPU_H */ -/** @} */ diff --git a/cpu/cortex-m0_common/irq_arch.c b/cpu/cortex-m0_common/irq_arch.c deleted file mode 100644 index e31920e389..0000000000 --- a/cpu/cortex-m0_common/irq_arch.c +++ /dev/null @@ -1,58 +0,0 @@ -/* - * 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_cortexm0_common - * @{ - * - * @file - * @brief Implementation of the kernels irq interface - * - * @author Hauke Petersen - * - * @} - */ - -#include -#include "arch/irq_arch.h" -#include "cpu.h" - -/** - * @brief Disable all maskable interrupts - */ -unsigned int irq_arch_disable(void) -{ - uint32_t mask = __get_PRIMASK(); - __disable_irq(); - return mask; -} - -/** - * @brief Enable all maskable interrupts - */ -unsigned int irq_arch_enable(void) -{ - __enable_irq(); - return __get_PRIMASK(); -} - -/** - * @brief Restore the state of the IRQ flags - */ -void irq_arch_restore(unsigned int state) -{ - __set_PRIMASK(state); -} - -/** - * @brief See if the current context is inside an ISR - */ -int irq_arch_in(void) -{ - return (__get_IPSR() & 0xFF); -} diff --git a/cpu/cortex-m0_common/thread_arch.c b/cpu/cortex-m0_common/thread_arch.c deleted file mode 100644 index 32535ecf59..0000000000 --- a/cpu/cortex-m0_common/thread_arch.c +++ /dev/null @@ -1,262 +0,0 @@ -/* - * 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_cortexm0_common - * @{ - * - * @file - * @brief Implementation of the kernel's architecture dependent thread interface - * - * @author Stefan Pfeiffer - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "arch/thread_arch.h" -#include "sched.h" -#include "thread.h" -#include "irq.h" -#include "cpu.h" -#include "kernel_internal.h" - -/** - * @name noticeable marker marking the beginning of a stack segment - * - * This marker is used e.g. by *thread_arch_start_threading* to identify the stacks start. - */ -#define STACK_MARKER (0x77777777) - -/** - * @name Initial program status register value for a newly created thread - */ -#define INITIAL_XPSR (0x01000000) - -/** - * @name ARM Cortex-M specific exception return value, that triggers the return to the task mode - * stack pointer - */ -#define EXCEPT_RET_TASK_MODE (0xfffffffd) - - -static void context_save(void); -static void context_restore(void); - -/** - * THe cortex-M0 knows stacks and handles register backups, so use the following layout: - * - * ---------------------------------------------------------------------------------------------------- - * | LR | R8 | R9 | R10 | R11 | R4 | R5 | R6 | R7 | R0 | R1 | R2 | R3 | R12 | LR | PC | xPSR | MARKER | - * ---------------------------------------------------------------------------------------------------- - * | | - * lowest address highest address - * - */ -char *thread_arch_stack_init(thread_task_func_t task_func, - void *arg, - void *stack_start, - int stack_size) -{ - uint32_t *stk; - stk = (uint32_t *)((uintptr_t)stack_start + stack_size); - - /* marker */ - stk--; - *stk = (uint32_t)STACK_MARKER; - - /* FIXME xPSR */ - stk--; - *stk = (uint32_t)INITIAL_XPSR; - - /* program counter */ - stk--; - *stk = (uint32_t)task_func; - - /* link register, jumped to when thread exits */ - stk--; - *stk = (uint32_t)sched_task_exit; - - /* r12 */ - stk--; - *stk = (uint32_t)0; - - /* r3 - r1 */ - for (int i = 3; i >= 1; i--) { - stk--; - *stk = i; - } - - /* r0 -> thread function parameter */ - stk--; - *stk = (uint32_t)arg; - - /* r7 - r4 */ - for (int i = 7; i >= 4; i--) { - stk--; - *stk = i; - } - - /* r11 - r8 */ - for (int i = 11; i >= 8; i--) { - stk--; - *stk = i; - } - - /* lr means exception return code */ - stk--; - *stk = (uint32_t)EXCEPT_RET_TASK_MODE; /*return to task-mode main stack pointer */ - - return (char*) stk; -} - -void thread_arch_stack_print(void) -{ - int count = 0; - uint32_t *sp = (uint32_t *)sched_active_thread->sp; - - printf("printing the current stack of thread %" PRIkernel_pid "\n", thread_getpid()); - printf(" address: data:\n"); - - do { - printf(" 0x%08x: 0x%08x\n", (unsigned int)sp, (unsigned int)*sp); - sp++; - count++; - } while (*sp != STACK_MARKER); - - printf("current stack size: %i byte\n", count); -} - -__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) -{ - /* trigger the PENDSV interrupt, which runs the scheduler */ - SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; -} - -/** - * @brief save the current thread's context to the current thread's stack - * - * This function is always called in interrupt context. For this the initial state is the following: - * - * active stack-pointer: MSP - * - * top of application stack: - * -------- highest address - * | xPSR | - * -------- - * | PC | - * -------- - * | LR | - * -------- - * | R12 | - * -------- - * | R3 | - * -------- - * | R2 | - * -------- - * | R1 | - * -------- - * | R0 | <- current value of PSP - * -------- lowest address - * - * With other words, registers R0-R3, R12, LR, PC and xPSR are already saved to the thread's stack. - * This leaves registers R4-R11 to be pushed to the thread's stack for a complete context save. - * - * This function now further pushes the remaining registers to the application stack (PSP) - */ -__attribute__((always_inline)) static __INLINE void context_save(void) -{ - /* {r0-r3,r12,LR,PC,xPSR} were saved automatically on exception entry */ - - /* set stack pointer to PSP while keeping the MSP value */ - asm("mrs r0, psp"); - asm("mov r12, sp"); - asm("mov sp, r0"); - /* save registers R11-R4 */ - asm("mov r0, r8"); - asm("mov r1, r9"); - asm("mov r2, r10"); - asm("mov r3, r11"); - asm("push {r0-r7}"); - /* save link register */ - asm("mov r0, lr"); - asm("push {r0}"); - /* switch back stack pointers */ - asm("mov r0, sp"); - asm("mov sp, r12"); - /* store the new psp to the tcb->sp */ - asm("ldr r1, =sched_active_thread" ); - asm("ldr r1, [r1]"); - asm("str r0, [r1]"); -} - -__attribute__((always_inline)) static __INLINE void context_restore(void) -{ - /* save MSR stack pointer for later restore */ - asm("mov lr, sp"); - /* get the PSP stack pointer of the current thread */ - asm("ldr r0, =sched_active_thread"); - asm("ldr r0, [r0]"); - asm("ldr r0, [r0]"); - asm("mov sp, r0"); - /* restore exception return value (LR) from stack */ - asm("pop {r0}"); - asm("mov r12, r0"); - /* restore registers R4-R11 from the PSP stack */ - asm("pop {r0-r7}"); - asm("mov r8, r0"); - asm("mov r9, r1"); - asm("mov r10, r2"); - asm("mov r11, r3"); - /* restore the application mode stack pointer PSP */ - asm("mov r0, sp"); - asm("msr psp, r0"); - asm("mov sp, lr"); - /* return from exception mode to application mode */ - asm("bx r12"); - - /* {r0-r3,r12,LR,PC,xPSR} are restored automatically on exception return */ -} - -/** - * @brief The SVC interrupt is used for dispatching a thread if no context exists. - * - * Starting a thread from non-existing context is needed in two situations: - * 1) after system initialization for running the main thread - * 2) after exiting from a thread - */ -__attribute__((naked)) void isr_svc(void) -{ - sched_run(); - context_restore(); -} - -/** - * @brief The PENDSV interrupt is used for context switching - * - * This interrupt saves the context, runs the scheduler and restores the context of the thread - * that is run next. - */ -__attribute__((naked)) void isr_pendsv(void) -{ - context_save(); - sched_run(); - context_restore(); -} diff --git a/cpu/cortex-m3_common/Makefile.include b/cpu/cortex-m3_common/Makefile.include deleted file mode 100644 index 9c11428577..0000000000 --- a/cpu/cortex-m3_common/Makefile.include +++ /dev/null @@ -1,3 +0,0 @@ - -# include module specific includes -export INCLUDES += -I$(RIOTCPU)/cortex-m3_common/include diff --git a/cpu/cortex-m3_common/atomic_arch.c b/cpu/cortex-m3_common/atomic_arch.c deleted file mode 100644 index 1ee7f4fc50..0000000000 --- a/cpu/cortex-m3_common/atomic_arch.c +++ /dev/null @@ -1,46 +0,0 @@ -/* - * 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_cortexm3_common - * @{ - * - * @file - * @brief Implementation of the kernels atomic interface - * - * @author Stefan Pfeiffer - * @author Hauke Petersen - * @author Joakim Gebart - * - * @} - */ - -#include -#include "atomic.h" -#include "irq.h" -#include "cpu.h" - -int atomic_cas(atomic_int_t *var, int old, int now) -{ - int tmp; - int status; - - /* Load exclusive */ - tmp = __LDREXW((volatile uint32_t *)(&ATOMIC_VALUE(*var))); - - if (tmp != old) { - /* Clear memory exclusivity */ - __CLREX(); - return 0; - } - - /* Try to write the new value */ - status = __STREXW(now, (volatile uint32_t *)(&ATOMIC_VALUE(*var))); - - return (status == 0); -} diff --git a/cpu/cortex-m3_common/include/core_cmFunc.h b/cpu/cortex-m3_common/include/core_cmFunc.h deleted file mode 100644 index 1bfdd24726..0000000000 --- a/cpu/cortex-m3_common/include/core_cmFunc.h +++ /dev/null @@ -1,651 +0,0 @@ -/**************************************************************************//** - * @file core_cmFunc.h - * @brief CMSIS Cortex-M Core Function Access Header File - * @version V4.00 - * @date 28. August 2014 - * - * @note - * - ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#ifndef __CORE_CMFUNC_H -#define __CORE_CMFUNC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ -/* ARM armcc specific functions */ - -#if (__ARMCC_VERSION < 400677) - #error "Please use ARM Compiler Toolchain V4.0.677 or later!" -#endif - -/* intrinsic void __enable_irq(); */ -/* intrinsic void __disable_irq(); */ - -/** \brief Get Control Register - - This function returns the content of the Control Register. - - \return Control Register value - */ -__STATIC_INLINE uint32_t __get_CONTROL(void) -{ - register uint32_t __regControl __ASM("control"); - return(__regControl); -} - - -/** \brief Set Control Register - - This function writes the given value to the Control Register. - - \param [in] control Control Register value to set - */ -__STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - register uint32_t __regControl __ASM("control"); - __regControl = control; -} - - -/** \brief Get IPSR Register - - This function returns the content of the IPSR Register. - - \return IPSR Register value - */ -__STATIC_INLINE uint32_t __get_IPSR(void) -{ - register uint32_t __regIPSR __ASM("ipsr"); - return(__regIPSR); -} - - -/** \brief Get APSR Register - - This function returns the content of the APSR Register. - - \return APSR Register value - */ -__STATIC_INLINE uint32_t __get_APSR(void) -{ - register uint32_t __regAPSR __ASM("apsr"); - return(__regAPSR); -} - - -/** \brief Get xPSR Register - - This function returns the content of the xPSR Register. - - \return xPSR Register value - */ -__STATIC_INLINE uint32_t __get_xPSR(void) -{ - register uint32_t __regXPSR __ASM("xpsr"); - return(__regXPSR); -} - - -/** \brief Get Process Stack Pointer - - This function returns the current value of the Process Stack Pointer (PSP). - - \return PSP Register value - */ -__STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - return(__regProcessStackPointer); -} - - -/** \brief Set Process Stack Pointer - - This function assigns the given value to the Process Stack Pointer (PSP). - - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - __regProcessStackPointer = topOfProcStack; -} - - -/** \brief Get Main Stack Pointer - - This function returns the current value of the Main Stack Pointer (MSP). - - \return MSP Register value - */ -__STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - return(__regMainStackPointer); -} - - -/** \brief Set Main Stack Pointer - - This function assigns the given value to the Main Stack Pointer (MSP). - - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - __regMainStackPointer = topOfMainStack; -} - - -/** \brief Get Priority Mask - - This function returns the current state of the priority mask bit from the Priority Mask Register. - - \return Priority Mask value - */ -__STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - register uint32_t __regPriMask __ASM("primask"); - return(__regPriMask); -} - - -/** \brief Set Priority Mask - - This function assigns the given value to the Priority Mask Register. - - \param [in] priMask Priority Mask - */ -__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - register uint32_t __regPriMask __ASM("primask"); - __regPriMask = (priMask); -} - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Enable FIQ - - This function enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq - - -/** \brief Disable FIQ - - This function disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq - - -/** \brief Get Base Priority - - This function returns the current value of the Base Priority register. - - \return Base Priority register value - */ -__STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - register uint32_t __regBasePri __ASM("basepri"); - return(__regBasePri); -} - - -/** \brief Set Base Priority - - This function assigns the given value to the Base Priority register. - - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) -{ - register uint32_t __regBasePri __ASM("basepri"); - __regBasePri = (basePri & 0xff); -} - - -/** \brief Get Fault Mask - - This function returns the current value of the Fault Mask register. - - \return Fault Mask register value - */ -__STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - return(__regFaultMask); -} - - -/** \brief Set Fault Mask - - This function assigns the given value to the Fault Mask register. - - \param [in] faultMask Fault Mask value to set - */ -__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - __regFaultMask = (faultMask & (uint32_t)1); -} - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) - -/** \brief Get FPSCR - - This function returns the current value of the Floating Point Status/Control register. - - \return Floating Point Status/Control register value - */ -__STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - register uint32_t __regfpscr __ASM("fpscr"); - return(__regfpscr); -#else - return(0); -#endif -} - - -/** \brief Set FPSCR - - This function assigns the given value to the Floating Point Status/Control register. - - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - register uint32_t __regfpscr __ASM("fpscr"); - __regfpscr = (fpscr); -#endif -} - -#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ - - -#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ -/* GNU gcc specific functions */ - -/** \brief Enable IRQ Interrupts - - This function enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** \brief Disable IRQ Interrupts - - This function disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** \brief Get Control Register - - This function returns the content of the Control Register. - - \return Control Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Control Register - - This function writes the given value to the Control Register. - - \param [in] control Control Register value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -/** \brief Get IPSR Register - - This function returns the content of the IPSR Register. - - \return IPSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get APSR Register - - This function returns the content of the APSR Register. - - \return APSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get xPSR Register - - This function returns the content of the xPSR Register. - - \return xPSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get Process Stack Pointer - - This function returns the current value of the Process Stack Pointer (PSP). - - \return PSP Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Process Stack Pointer - - This function assigns the given value to the Process Stack Pointer (PSP). - - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); -} - - -/** \brief Get Main Stack Pointer - - This function returns the current value of the Main Stack Pointer (MSP). - - \return MSP Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Main Stack Pointer - - This function assigns the given value to the Main Stack Pointer (MSP). - - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); -} - - -/** \brief Get Priority Mask - - This function returns the current state of the priority mask bit from the Priority Mask Register. - - \return Priority Mask value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Priority Mask - - This function assigns the given value to the Priority Mask Register. - - \param [in] priMask Priority Mask - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (__CORTEX_M >= 0x03) - -/** \brief Enable FIQ - - This function enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** \brief Disable FIQ - - This function disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** \brief Get Base Priority - - This function returns the current value of the Base Priority register. - - \return Base Priority register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); - return(result); -} - - -/** \brief Set Base Priority - - This function assigns the given value to the Base Priority register. - - \param [in] basePri Base Priority value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); -} - - -/** \brief Get Fault Mask - - This function returns the current value of the Fault Mask register. - - \return Fault Mask register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -/** \brief Set Fault Mask - - This function assigns the given value to the Fault Mask register. - - \param [in] faultMask Fault Mask value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - -#endif /* (__CORTEX_M >= 0x03) */ - - -#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) - -/** \brief Get FPSCR - - This function returns the current value of the Floating Point Status/Control register. - - \return Floating Point Status/Control register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - uint32_t result; - - /* Empty asm statement works as a scheduling barrier */ - __ASM volatile (""); - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} - - -/** \brief Set FPSCR - - This function assigns the given value to the Floating Point Status/Control register. - - \param [in] fpscr Floating Point Status/Control value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - /* Empty asm statement works as a scheduling barrier */ - __ASM volatile (""); - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} - -#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ - - -#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ -/* IAR iccarm specific functions */ -#include - - -#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ -/* TI CCS specific functions */ -#include - - -#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ -/* TASKING carm specific functions */ -/* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - -#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ -/* Cosmic specific functions */ -#include - -#endif - -/*@} end of CMSIS_Core_RegAccFunctions */ - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMFUNC_H */ diff --git a/cpu/cortex-m3_common/include/core_cmInstr.h b/cpu/cortex-m3_common/include/core_cmInstr.h deleted file mode 100644 index d32c3588c9..0000000000 --- a/cpu/cortex-m3_common/include/core_cmInstr.h +++ /dev/null @@ -1,887 +0,0 @@ -/**************************************************************************//** - * @file core_cmInstr.h - * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V4.00 - * @date 28. August 2014 - * - * @note - * - ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#ifndef __CORE_CMINSTR_H -#define __CORE_CMINSTR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ -/* ARM armcc specific functions */ - -#if (__ARMCC_VERSION < 400677) - #error "Please use ARM Compiler Toolchain V4.0.677 or later!" -#endif - - -/** \brief No Operation - - No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __nop - - -/** \brief Wait For Interrupt - - Wait For Interrupt is a hint instruction that suspends execution - until one of a number of events occurs. - */ -#define __WFI __wfi - - -/** \brief Wait For Event - - Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __wfe - - -/** \brief Send Event - - Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __sev - - -/** \brief Instruction Synchronization Barrier - - Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or - memory, after the instruction has been completed. - */ -#define __ISB() __isb(0xF) - - -/** \brief Data Synchronization Barrier - - This function acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __dsb(0xF) - - -/** \brief Data Memory Barrier - - This function ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __dmb(0xF) - - -/** \brief Reverse byte order (32 bit) - - This function reverses the byte order in integer value. - - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __rev - - -/** \brief Reverse byte order (16 bit) - - This function reverses the byte order in two unsigned short values. - - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) -{ - rev16 r0, r0 - bx lr -} -#endif - -/** \brief Reverse byte order in signed short value - - This function reverses the byte order in a signed short value with sign extension to integer. - - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value) -{ - revsh r0, r0 - bx lr -} -#endif - - -/** \brief Rotate Right in unsigned value (32 bit) - - This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - - \param [in] value Value to rotate - \param [in] value Number of Bits to rotate - \return Rotated value - */ -#define __ROR __ror - - -/** \brief Breakpoint - - This function causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __breakpoint(value) - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Reverse bit order of value - - This function reverses the bit order of the given value. - - \param [in] value Value to reverse - \return Reversed value - */ -#define __RBIT __rbit - - -/** \brief LDR Exclusive (8 bit) - - This function executes a exclusive LDR instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) - - -/** \brief LDR Exclusive (16 bit) - - This function executes a exclusive LDR instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) - - -/** \brief LDR Exclusive (32 bit) - - This function executes a exclusive LDR instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) - - -/** \brief STR Exclusive (8 bit) - - This function executes a exclusive STR instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB(value, ptr) __strex(value, ptr) - - -/** \brief STR Exclusive (16 bit) - - This function executes a exclusive STR instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH(value, ptr) __strex(value, ptr) - - -/** \brief STR Exclusive (32 bit) - - This function executes a exclusive STR instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW(value, ptr) __strex(value, ptr) - - -/** \brief Remove the exclusive lock - - This function removes the exclusive lock which is created by LDREX. - - */ -#define __CLREX __clrex - - -/** \brief Signed Saturate - - This function saturates a signed value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __ssat - - -/** \brief Unsigned Saturate - - This function saturates an unsigned value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __usat - - -/** \brief Count leading zeros - - This function counts the number of leading zeros of a data value. - - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __clz - - -/** \brief Rotate Right with Extend (32 bit) - - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. - - \param [in] value Value to rotate - \return Rotated value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) -{ - rrx r0, r0 - bx lr -} -#endif - - -/** \brief LDRT Unprivileged (8 bit) - - This function executes a Unprivileged LDRT instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) - - -/** \brief LDRT Unprivileged (16 bit) - - This function executes a Unprivileged LDRT instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) - - -/** \brief LDRT Unprivileged (32 bit) - - This function executes a Unprivileged LDRT instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) - - -/** \brief STRT Unprivileged (8 bit) - - This function executes a Unprivileged STRT instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRBT(value, ptr) __strt(value, ptr) - - -/** \brief STRT Unprivileged (16 bit) - - This function executes a Unprivileged STRT instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRHT(value, ptr) __strt(value, ptr) - - -/** \brief STRT Unprivileged (32 bit) - - This function executes a Unprivileged STRT instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRT(value, ptr) __strt(value, ptr) - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ -/* GNU gcc specific functions */ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constrant "l" - * Otherwise, use general registers, specified by constrant "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** \brief No Operation - - No Operation does nothing. This instruction can be used for code alignment purposes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) -{ - __ASM volatile ("nop"); -} - - -/** \brief Wait For Interrupt - - Wait For Interrupt is a hint instruction that suspends execution - until one of a number of events occurs. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) -{ - __ASM volatile ("wfi"); -} - - -/** \brief Wait For Event - - Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) -{ - __ASM volatile ("wfe"); -} - - -/** \brief Send Event - - Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) -{ - __ASM volatile ("sev"); -} - - -/** \brief Instruction Synchronization Barrier - - Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or - memory, after the instruction has been completed. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) -{ - __ASM volatile ("isb"); -} - - -/** \brief Data Synchronization Barrier - - This function acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) -{ - __ASM volatile ("dsb"); -} - - -/** \brief Data Memory Barrier - - This function ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) -{ - __ASM volatile ("dmb"); -} - - -/** \brief Reverse byte order (32 bit) - - This function reverses the byte order in integer value. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -#endif -} - - -/** \brief Reverse byte order (16 bit) - - This function reverses the byte order in two unsigned short values. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** \brief Reverse byte order in signed short value - - This function reverses the byte order in a signed short value with sign extension to integer. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (short)__builtin_bswap16(value); -#else - uint32_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -#endif -} - - -/** \brief Rotate Right in unsigned value (32 bit) - - This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - - \param [in] value Value to rotate - \param [in] value Number of Bits to rotate - \return Rotated value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - return (op1 >> op2) | (op1 << (32 - op2)); -} - - -/** \brief Breakpoint - - This function causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Reverse bit order of value - - This function reverses the bit order of the given value. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - - -/** \brief LDR Exclusive (8 bit) - - This function executes a exclusive LDR instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDR Exclusive (16 bit) - - This function executes a exclusive LDR instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDR Exclusive (32 bit) - - This function executes a exclusive LDR instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** \brief STR Exclusive (8 bit) - - This function executes a exclusive STR instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** \brief STR Exclusive (16 bit) - - This function executes a exclusive STR instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** \brief STR Exclusive (32 bit) - - This function executes a exclusive STR instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** \brief Remove the exclusive lock - - This function removes the exclusive lock which is created by LDREX. - - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - - -/** \brief Signed Saturate - - This function saturates a signed value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** \brief Unsigned Saturate - - This function saturates an unsigned value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** \brief Count leading zeros - - This function counts the number of leading zeros of a data value. - - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief Rotate Right with Extend (32 bit) - - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. - - \param [in] value Value to rotate - \return Rotated value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** \brief LDRT Unprivileged (8 bit) - - This function executes a Unprivileged LDRT instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDRT Unprivileged (16 bit) - - This function executes a Unprivileged LDRT instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDRT Unprivileged (32 bit) - - This function executes a Unprivileged LDRT instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** \brief STRT Unprivileged (8 bit) - - This function executes a Unprivileged STRT instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); -} - - -/** \brief STRT Unprivileged (16 bit) - - This function executes a Unprivileged STRT instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); -} - - -/** \brief STRT Unprivileged (32 bit) - - This function executes a Unprivileged STRT instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*addr) : "r" (value) ); -} - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ -/* IAR iccarm specific functions */ -#include - - -#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ -/* TI CCS specific functions */ -#include - - -#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ -/* TASKING carm specific functions */ -/* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - -#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ -/* Cosmic specific functions */ -#include - -#endif - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMINSTR_H */ diff --git a/cpu/cortex-m3_common/irq_arch.c b/cpu/cortex-m3_common/irq_arch.c deleted file mode 100644 index c1a3bf6c68..0000000000 --- a/cpu/cortex-m3_common/irq_arch.c +++ /dev/null @@ -1,58 +0,0 @@ -/* - * 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_cortexm3_common - * @{ - * - * @file - * @brief Implementation of the kernels irq interface - * - * @author Hauke Petersen - * - * @} - */ - -#include -#include "arch/irq_arch.h" -#include "cpu.h" - -/** - * @brief Disable all maskable interrupts - */ -unsigned int irq_arch_disable(void) -{ - uint32_t mask = __get_PRIMASK(); - __disable_irq(); - return mask; -} - -/** - * @brief Enable all maskable interrupts - */ -unsigned int irq_arch_enable(void) -{ - __enable_irq(); - return __get_PRIMASK(); -} - -/** - * @brief Restore the state of the IRQ flags - */ -void irq_arch_restore(unsigned int state) -{ - __set_PRIMASK(state); -} - -/** - * @brief See if the current context is inside an ISR - */ -int irq_arch_in(void) -{ - return (__get_IPSR() & 0xFF); -} diff --git a/cpu/cortex-m3_common/panic.c b/cpu/cortex-m3_common/panic.c deleted file mode 100644 index 4f9aef455e..0000000000 --- a/cpu/cortex-m3_common/panic.c +++ /dev/null @@ -1,34 +0,0 @@ -/* - * Copyright (C) 2014-2015 INRIA - * Copyright (C) 2015 Eistec AB - * - * This file is subject to the terms and conditions of the GNU Lesser General - * Public License v2.1. See the file LICENSE in the top level directory for more - * details. - */ - -/** - * @ingroup cortex-m3_common - * @{ - * - * @file - * @brief Crash handling functions implementation for ARM Cortex-based MCUs - * - * @author Oliver Hahm - * @author Joakim Gebart - */ - -#include "cpu.h" -#include "lpm.h" - -void panic_arch(void) -{ -#if DEVELHELP - /* The bkpt instruction will signal to the debugger to break here. */ - __ASM("bkpt #0"); - /* enter infinite loop, into deepest possible sleep mode */ - while (1) { - lpm_set(LPM_OFF); - } -#endif -} diff --git a/cpu/cortex-m3_common/reboot_arch.c b/cpu/cortex-m3_common/reboot_arch.c deleted file mode 100644 index fc6046c855..0000000000 --- a/cpu/cortex-m3_common/reboot_arch.c +++ /dev/null @@ -1,34 +0,0 @@ -/* - * 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_cortexm3_common - * @{ - * - * @file - * @brief Implementation of the kernels reboot interface - * - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "arch/reboot_arch.h" -#include "cpu.h" -#include "hwtimer.h" - -int reboot_arch(int mode) -{ - printf("Going into reboot, mode %i\n", mode); - /* wait 1 ms to make sure the printf is finished */ - hwtimer_wait(HWTIMER_TICKS(1000)); - NVIC_SystemReset(); - return -1; -} diff --git a/cpu/cortex-m3_common/thread_arch.c b/cpu/cortex-m3_common/thread_arch.c deleted file mode 100644 index 1a54c2a046..0000000000 --- a/cpu/cortex-m3_common/thread_arch.c +++ /dev/null @@ -1,227 +0,0 @@ -/* - * 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_cortexm3_common - * @{ - * - * @file - * @brief Implementation of the kernel's architecture dependent thread interface - * - * @author Stefan Pfeiffer - * @author Hauke Petersen - * - * @} - */ - -#include -#include - -#include "arch/thread_arch.h" -#include "thread.h" -#include "sched.h" -#include "irq.h" -#include "cpu.h" -#include "kernel_internal.h" - -/** - * @name noticeable marker marking the beginning of a stack segment - * - * This marker is used e.g. by *thread_arch_start_threading* to identify the stacks start. - */ -#define STACK_MARKER (0x77777777) - -/** - * @name ARM Cortex-M specific exception return value, that triggers the return to the task mode - * stack pointer - */ -#define EXCEPT_RET_TASK_MODE (0xfffffffd) - -static void context_save(void); -static void context_restore(void) NORETURN; - -/** - * Cortex-M3 knows stacks and handles register backups, so use different stack frame layout - * - * Layout without floating point registers: - * -------------------------------------- - * | R0 | R1 | R2 | R3 | LR | PC | xPSR | - * -------------------------------------- - * - */ -char *thread_arch_stack_init(thread_task_func_t task_func, void *arg, void *stack_start, int stack_size) -{ - uint32_t *stk; - stk = (uint32_t *)((uintptr_t)stack_start + stack_size); - - /* adjust to 32 bit boundary by clearing the last two bits in the address */ - stk = (uint32_t *)(((uint32_t)stk) & ~((uint32_t)0x3)); - - /* Stack start marker */ - stk--; - *stk = STACK_MARKER; - - /* Make sure the stack is double word aligned (8 bytes) */ - /* This is required in order to conform with Procedure Call Standard for the - * ARM® Architecture (AAPCS) */ - /* http://infocenter.arm.com/help/topic/com.arm.doc.ihi0042e/IHI0042E_aapcs.pdf */ - if (((uint32_t) stk % 8) != 0) { - /* add a single word padding */ - --stk; - *stk = ~((uint32_t)STACK_MARKER); - } - - /* ****************************** */ - /* Automatically popped registers */ - /* ****************************** */ - - /* The following eight stacked registers are popped by the hardware upon - * return from exception. (bx instruction in context_restore) */ - - /* xPSR */ - stk--; - /* Setting bit 9 (0x200) of xPSR will cause the initial stack pointer for - * the process to be aligned on a 32-bit, non-64-bit, boundary. Don't do that. */ - /* Default xPSR, only the Thumb mode-bit is set */ - *stk = 0x01000000; - - /* pc */ - stk--; - /* initial program counter */ - *stk = (uint32_t) task_func; - - /* lr */ - stk--; - /* link register, return address when a thread exits. */ - *stk = (uint32_t) sched_task_exit; - - /* r12 */ - stk--; - *stk = 0; - - /* r1 - r3 */ - for (int i = 3; i >= 1; i--) { - stk--; - *stk = i; - } - - /* r0 */ - stk--; - /* thread function parameter */ - *stk = (uint32_t) arg; - - /* 8 hardware-handled registers in total */ - - /* ************************* */ - /* Manually popped registers */ - /* ************************* */ - - /* The following registers are not handled by hardware in return from - * exception, but manually by context_restore. */ - - /* r11 - r4 */ - for (int i = 11; i >= 4; i--) { - stk--; - *stk = i; - } - - /* exception return code */ - stk--; - *stk = EXCEPT_RET_TASK_MODE; /* return to task-mode process stack pointer */ - - /* 9 manually handled registers in total. */ - - /* The returned stack pointer will be aligned on a 32 bit boundary not on a - * 64 bit boundary because of the odd number of registers above (8+9). - * This is not a problem since the initial stack pointer upon process entry - * _will_ be 64 bit aligned (because of the cleared bit 9 in the stacked - * xPSR and aligned stacking of the hardware-handled registers). */ - - return (char*) stk; - -} - -void thread_arch_stack_print(void) -{ - int count = 0; - uint32_t *sp = (uint32_t *)sched_active_thread->sp; - - printf("printing the current stack of thread %" PRIkernel_pid "\n", thread_getpid()); - printf(" address: data:\n"); - - do { - printf(" 0x%08x: 0x%08x\n", (unsigned int)sp, (unsigned int)*sp); - sp++; - count++; - } while (*sp != STACK_MARKER); - - printf("current stack size: %i byte\n", count); -} - -__attribute__((naked)) void thread_arch_start_threading(void) -{ - /* enable IRQs to make sure the SVC interrupt is reachable */ - enableIRQ(); - /* trigger the SVC interrupt which will get and execute the next thread */ - asm("svc 0x01"); -} - -void thread_arch_yield(void) -{ - /* trigger the PENDSV interrupt to run scheduler and schedule new thread if applicable */ - SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; -} - -__attribute__((always_inline)) static __INLINE void context_save(void) -{ - /* {r0-r3,r12,LR,PC,xPSR} are saved automatically on exception entry */ - - /* save unsaved registers onto the stack */ - asm("mrs r0, psp" ); /* get stack pointer from user mode */ - asm("stmdb r0!,{r4-r11}" ); /* save regs */ - asm("stmdb r0!,{lr}" ); /* exception return value */ - asm("ldr r1, =sched_active_thread" ); /* load address of current TCB */ - asm("ldr r1, [r1]" ); /* dereference TCB */ - asm("str r0, [r1]" ); /* write r0 to tcb->sp */ -} - -__attribute__((always_inline)) static __INLINE void context_restore(void) -{ - /* restore registers from stack */ - asm("ldr r0, =sched_active_thread" ); /* load address of current TCB */ - asm("ldr r0, [r0]" ); /* dereference TCB */ - asm("ldr r1, [r0]" ); /* load tcb->sp to register 1 */ - asm("ldmia r1!, {r0}" ); /* restore exception return value from stack */ - asm("ldmia r1!, {r4-r11}" ); /* restore other registers */ - asm("msr psp, r1" ); /* restore PSP register (user mode SP) */ - asm("bx r0" ); /* load exception return value to PC */ - - /* {r0-r3,r12,LR,PC,xPSR} are restored automatically on exception return */ - - UNREACHABLE(); -} - -/** - * @brief The svc is used for running the scheduler and scheduling a new task during start-up or - * after a thread has exited - */ -__attribute__((naked)) void isr_svc(void) -{ - sched_run(); - context_restore(); -} - -/** - * @brief All task switching activity is carried out int the pendSV interrupt - */ -__attribute__((naked)) void isr_pendsv(void) -{ - context_save(); - sched_run(); - context_restore(); -} diff --git a/cpu/cortex-m4_common/Makefile b/cpu/cortex-m4_common/Makefile deleted file mode 100644 index 24b8a7b2ff..0000000000 --- a/cpu/cortex-m4_common/Makefile +++ /dev/null @@ -1,4 +0,0 @@ -# define the module that is build -MODULE = cortex-m4_common - -include $(RIOTBASE)/Makefile.base diff --git a/cpu/cortex-m4_common/Makefile.include b/cpu/cortex-m4_common/Makefile.include deleted file mode 100644 index 8047738cf4..0000000000 --- a/cpu/cortex-m4_common/Makefile.include +++ /dev/null @@ -1,2 +0,0 @@ -# include module specific includes -export INCLUDES += -I$(RIOTCPU)/cortex-m4_common/include diff --git a/cpu/cortex-m4_common/include/core_cmFunc.h b/cpu/cortex-m4_common/include/core_cmFunc.h deleted file mode 100644 index 1bfdd24726..0000000000 --- a/cpu/cortex-m4_common/include/core_cmFunc.h +++ /dev/null @@ -1,651 +0,0 @@ -/**************************************************************************//** - * @file core_cmFunc.h - * @brief CMSIS Cortex-M Core Function Access Header File - * @version V4.00 - * @date 28. August 2014 - * - * @note - * - ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#ifndef __CORE_CMFUNC_H -#define __CORE_CMFUNC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ -/* ARM armcc specific functions */ - -#if (__ARMCC_VERSION < 400677) - #error "Please use ARM Compiler Toolchain V4.0.677 or later!" -#endif - -/* intrinsic void __enable_irq(); */ -/* intrinsic void __disable_irq(); */ - -/** \brief Get Control Register - - This function returns the content of the Control Register. - - \return Control Register value - */ -__STATIC_INLINE uint32_t __get_CONTROL(void) -{ - register uint32_t __regControl __ASM("control"); - return(__regControl); -} - - -/** \brief Set Control Register - - This function writes the given value to the Control Register. - - \param [in] control Control Register value to set - */ -__STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - register uint32_t __regControl __ASM("control"); - __regControl = control; -} - - -/** \brief Get IPSR Register - - This function returns the content of the IPSR Register. - - \return IPSR Register value - */ -__STATIC_INLINE uint32_t __get_IPSR(void) -{ - register uint32_t __regIPSR __ASM("ipsr"); - return(__regIPSR); -} - - -/** \brief Get APSR Register - - This function returns the content of the APSR Register. - - \return APSR Register value - */ -__STATIC_INLINE uint32_t __get_APSR(void) -{ - register uint32_t __regAPSR __ASM("apsr"); - return(__regAPSR); -} - - -/** \brief Get xPSR Register - - This function returns the content of the xPSR Register. - - \return xPSR Register value - */ -__STATIC_INLINE uint32_t __get_xPSR(void) -{ - register uint32_t __regXPSR __ASM("xpsr"); - return(__regXPSR); -} - - -/** \brief Get Process Stack Pointer - - This function returns the current value of the Process Stack Pointer (PSP). - - \return PSP Register value - */ -__STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - return(__regProcessStackPointer); -} - - -/** \brief Set Process Stack Pointer - - This function assigns the given value to the Process Stack Pointer (PSP). - - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - __regProcessStackPointer = topOfProcStack; -} - - -/** \brief Get Main Stack Pointer - - This function returns the current value of the Main Stack Pointer (MSP). - - \return MSP Register value - */ -__STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - return(__regMainStackPointer); -} - - -/** \brief Set Main Stack Pointer - - This function assigns the given value to the Main Stack Pointer (MSP). - - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - __regMainStackPointer = topOfMainStack; -} - - -/** \brief Get Priority Mask - - This function returns the current state of the priority mask bit from the Priority Mask Register. - - \return Priority Mask value - */ -__STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - register uint32_t __regPriMask __ASM("primask"); - return(__regPriMask); -} - - -/** \brief Set Priority Mask - - This function assigns the given value to the Priority Mask Register. - - \param [in] priMask Priority Mask - */ -__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - register uint32_t __regPriMask __ASM("primask"); - __regPriMask = (priMask); -} - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Enable FIQ - - This function enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq - - -/** \brief Disable FIQ - - This function disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq - - -/** \brief Get Base Priority - - This function returns the current value of the Base Priority register. - - \return Base Priority register value - */ -__STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - register uint32_t __regBasePri __ASM("basepri"); - return(__regBasePri); -} - - -/** \brief Set Base Priority - - This function assigns the given value to the Base Priority register. - - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) -{ - register uint32_t __regBasePri __ASM("basepri"); - __regBasePri = (basePri & 0xff); -} - - -/** \brief Get Fault Mask - - This function returns the current value of the Fault Mask register. - - \return Fault Mask register value - */ -__STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - return(__regFaultMask); -} - - -/** \brief Set Fault Mask - - This function assigns the given value to the Fault Mask register. - - \param [in] faultMask Fault Mask value to set - */ -__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - __regFaultMask = (faultMask & (uint32_t)1); -} - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) - -/** \brief Get FPSCR - - This function returns the current value of the Floating Point Status/Control register. - - \return Floating Point Status/Control register value - */ -__STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - register uint32_t __regfpscr __ASM("fpscr"); - return(__regfpscr); -#else - return(0); -#endif -} - - -/** \brief Set FPSCR - - This function assigns the given value to the Floating Point Status/Control register. - - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - register uint32_t __regfpscr __ASM("fpscr"); - __regfpscr = (fpscr); -#endif -} - -#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ - - -#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ -/* GNU gcc specific functions */ - -/** \brief Enable IRQ Interrupts - - This function enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** \brief Disable IRQ Interrupts - - This function disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** \brief Get Control Register - - This function returns the content of the Control Register. - - \return Control Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Control Register - - This function writes the given value to the Control Register. - - \param [in] control Control Register value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -/** \brief Get IPSR Register - - This function returns the content of the IPSR Register. - - \return IPSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get APSR Register - - This function returns the content of the APSR Register. - - \return APSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get xPSR Register - - This function returns the content of the xPSR Register. - - \return xPSR Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Get Process Stack Pointer - - This function returns the current value of the Process Stack Pointer (PSP). - - \return PSP Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Process Stack Pointer - - This function assigns the given value to the Process Stack Pointer (PSP). - - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); -} - - -/** \brief Get Main Stack Pointer - - This function returns the current value of the Main Stack Pointer (MSP). - - \return MSP Register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Main Stack Pointer - - This function assigns the given value to the Main Stack Pointer (MSP). - - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); -} - - -/** \brief Get Priority Mask - - This function returns the current state of the priority mask bit from the Priority Mask Register. - - \return Priority Mask value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - /* cppcheck-suppress uninitvar */ - return(result); -} - - -/** \brief Set Priority Mask - - This function assigns the given value to the Priority Mask Register. - - \param [in] priMask Priority Mask - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (__CORTEX_M >= 0x03) - -/** \brief Enable FIQ - - This function enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** \brief Disable FIQ - - This function disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** \brief Get Base Priority - - This function returns the current value of the Base Priority register. - - \return Base Priority register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); - return(result); -} - - -/** \brief Set Base Priority - - This function assigns the given value to the Base Priority register. - - \param [in] basePri Base Priority value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); -} - - -/** \brief Get Fault Mask - - This function returns the current value of the Fault Mask register. - - \return Fault Mask register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -/** \brief Set Fault Mask - - This function assigns the given value to the Fault Mask register. - - \param [in] faultMask Fault Mask value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - -#endif /* (__CORTEX_M >= 0x03) */ - - -#if (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) - -/** \brief Get FPSCR - - This function returns the current value of the Floating Point Status/Control register. - - \return Floating Point Status/Control register value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - uint32_t result; - - /* Empty asm statement works as a scheduling barrier */ - __ASM volatile (""); - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} - - -/** \brief Set FPSCR - - This function assigns the given value to the Floating Point Status/Control register. - - \param [in] fpscr Floating Point Status/Control value to set - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - /* Empty asm statement works as a scheduling barrier */ - __ASM volatile (""); - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} - -#endif /* (__CORTEX_M == 0x04) || (__CORTEX_M == 0x07) */ - - -#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ -/* IAR iccarm specific functions */ -#include - - -#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ -/* TI CCS specific functions */ -#include - - -#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ -/* TASKING carm specific functions */ -/* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - -#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ -/* Cosmic specific functions */ -#include - -#endif - -/*@} end of CMSIS_Core_RegAccFunctions */ - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMFUNC_H */ diff --git a/cpu/cortex-m4_common/include/core_cmInstr.h b/cpu/cortex-m4_common/include/core_cmInstr.h deleted file mode 100644 index d32c3588c9..0000000000 --- a/cpu/cortex-m4_common/include/core_cmInstr.h +++ /dev/null @@ -1,887 +0,0 @@ -/**************************************************************************//** - * @file core_cmInstr.h - * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V4.00 - * @date 28. August 2014 - * - * @note - * - ******************************************************************************/ -/* Copyright (c) 2009 - 2014 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#ifndef __CORE_CMINSTR_H -#define __CORE_CMINSTR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ -/* ARM armcc specific functions */ - -#if (__ARMCC_VERSION < 400677) - #error "Please use ARM Compiler Toolchain V4.0.677 or later!" -#endif - - -/** \brief No Operation - - No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __nop - - -/** \brief Wait For Interrupt - - Wait For Interrupt is a hint instruction that suspends execution - until one of a number of events occurs. - */ -#define __WFI __wfi - - -/** \brief Wait For Event - - Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __wfe - - -/** \brief Send Event - - Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __sev - - -/** \brief Instruction Synchronization Barrier - - Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or - memory, after the instruction has been completed. - */ -#define __ISB() __isb(0xF) - - -/** \brief Data Synchronization Barrier - - This function acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __dsb(0xF) - - -/** \brief Data Memory Barrier - - This function ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __dmb(0xF) - - -/** \brief Reverse byte order (32 bit) - - This function reverses the byte order in integer value. - - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __rev - - -/** \brief Reverse byte order (16 bit) - - This function reverses the byte order in two unsigned short values. - - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) -{ - rev16 r0, r0 - bx lr -} -#endif - -/** \brief Reverse byte order in signed short value - - This function reverses the byte order in a signed short value with sign extension to integer. - - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value) -{ - revsh r0, r0 - bx lr -} -#endif - - -/** \brief Rotate Right in unsigned value (32 bit) - - This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - - \param [in] value Value to rotate - \param [in] value Number of Bits to rotate - \return Rotated value - */ -#define __ROR __ror - - -/** \brief Breakpoint - - This function causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __breakpoint(value) - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Reverse bit order of value - - This function reverses the bit order of the given value. - - \param [in] value Value to reverse - \return Reversed value - */ -#define __RBIT __rbit - - -/** \brief LDR Exclusive (8 bit) - - This function executes a exclusive LDR instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) - - -/** \brief LDR Exclusive (16 bit) - - This function executes a exclusive LDR instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) - - -/** \brief LDR Exclusive (32 bit) - - This function executes a exclusive LDR instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) - - -/** \brief STR Exclusive (8 bit) - - This function executes a exclusive STR instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB(value, ptr) __strex(value, ptr) - - -/** \brief STR Exclusive (16 bit) - - This function executes a exclusive STR instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH(value, ptr) __strex(value, ptr) - - -/** \brief STR Exclusive (32 bit) - - This function executes a exclusive STR instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW(value, ptr) __strex(value, ptr) - - -/** \brief Remove the exclusive lock - - This function removes the exclusive lock which is created by LDREX. - - */ -#define __CLREX __clrex - - -/** \brief Signed Saturate - - This function saturates a signed value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __ssat - - -/** \brief Unsigned Saturate - - This function saturates an unsigned value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __usat - - -/** \brief Count leading zeros - - This function counts the number of leading zeros of a data value. - - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __clz - - -/** \brief Rotate Right with Extend (32 bit) - - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. - - \param [in] value Value to rotate - \return Rotated value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) -{ - rrx r0, r0 - bx lr -} -#endif - - -/** \brief LDRT Unprivileged (8 bit) - - This function executes a Unprivileged LDRT instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) - - -/** \brief LDRT Unprivileged (16 bit) - - This function executes a Unprivileged LDRT instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) - - -/** \brief LDRT Unprivileged (32 bit) - - This function executes a Unprivileged LDRT instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) - - -/** \brief STRT Unprivileged (8 bit) - - This function executes a Unprivileged STRT instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRBT(value, ptr) __strt(value, ptr) - - -/** \brief STRT Unprivileged (16 bit) - - This function executes a Unprivileged STRT instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRHT(value, ptr) __strt(value, ptr) - - -/** \brief STRT Unprivileged (32 bit) - - This function executes a Unprivileged STRT instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRT(value, ptr) __strt(value, ptr) - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ -/* GNU gcc specific functions */ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constrant "l" - * Otherwise, use general registers, specified by constrant "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** \brief No Operation - - No Operation does nothing. This instruction can be used for code alignment purposes. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void) -{ - __ASM volatile ("nop"); -} - - -/** \brief Wait For Interrupt - - Wait For Interrupt is a hint instruction that suspends execution - until one of a number of events occurs. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void) -{ - __ASM volatile ("wfi"); -} - - -/** \brief Wait For Event - - Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void) -{ - __ASM volatile ("wfe"); -} - - -/** \brief Send Event - - Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void) -{ - __ASM volatile ("sev"); -} - - -/** \brief Instruction Synchronization Barrier - - Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or - memory, after the instruction has been completed. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void) -{ - __ASM volatile ("isb"); -} - - -/** \brief Data Synchronization Barrier - - This function acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void) -{ - __ASM volatile ("dsb"); -} - - -/** \brief Data Memory Barrier - - This function ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) -{ - __ASM volatile ("dmb"); -} - - -/** \brief Reverse byte order (32 bit) - - This function reverses the byte order in integer value. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -#endif -} - - -/** \brief Reverse byte order (16 bit) - - This function reverses the byte order in two unsigned short values. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** \brief Reverse byte order in signed short value - - This function reverses the byte order in a signed short value with sign extension to integer. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (short)__builtin_bswap16(value); -#else - uint32_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -#endif -} - - -/** \brief Rotate Right in unsigned value (32 bit) - - This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - - \param [in] value Value to rotate - \param [in] value Number of Bits to rotate - \return Rotated value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - return (op1 >> op2) | (op1 << (32 - op2)); -} - - -/** \brief Breakpoint - - This function causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -#if (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) - -/** \brief Reverse bit order of value - - This function reverses the bit order of the given value. - - \param [in] value Value to reverse - \return Reversed value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - - -/** \brief LDR Exclusive (8 bit) - - This function executes a exclusive LDR instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDR Exclusive (16 bit) - - This function executes a exclusive LDR instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDR Exclusive (32 bit) - - This function executes a exclusive LDR instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** \brief STR Exclusive (8 bit) - - This function executes a exclusive STR instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** \brief STR Exclusive (16 bit) - - This function executes a exclusive STR instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** \brief STR Exclusive (32 bit) - - This function executes a exclusive STR instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** \brief Remove the exclusive lock - - This function removes the exclusive lock which is created by LDREX. - - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - - -/** \brief Signed Saturate - - This function saturates a signed value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** \brief Unsigned Saturate - - This function saturates an unsigned value. - - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** \brief Count leading zeros - - This function counts the number of leading zeros of a data value. - - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief Rotate Right with Extend (32 bit) - - This function moves each bit of a bitstring right by one bit. The carry input is shifted in at the left end of the bitstring. - - \param [in] value Value to rotate - \return Rotated value - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** \brief LDRT Unprivileged (8 bit) - - This function executes a Unprivileged LDRT instruction for 8 bit value. - - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDRT Unprivileged (16 bit) - - This function executes a Unprivileged LDRT instruction for 16 bit values. - - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** \brief LDRT Unprivileged (32 bit) - - This function executes a Unprivileged LDRT instruction for 32 bit values. - - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** \brief STRT Unprivileged (8 bit) - - This function executes a Unprivileged STRT instruction for 8 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); -} - - -/** \brief STRT Unprivileged (16 bit) - - This function executes a Unprivileged STRT instruction for 16 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); -} - - -/** \brief STRT Unprivileged (32 bit) - - This function executes a Unprivileged STRT instruction for 32 bit values. - - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__( ( always_inline ) ) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*addr) : "r" (value) ); -} - -#endif /* (__CORTEX_M >= 0x03) || (__CORTEX_SC >= 300) */ - - -#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ -/* IAR iccarm specific functions */ -#include - - -#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/ -/* TI CCS specific functions */ -#include - - -#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ -/* TASKING carm specific functions */ -/* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - -#elif defined ( __CSMC__ ) /*------------------ COSMIC Compiler -------------------*/ -/* Cosmic specific functions */ -#include - -#endif - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMINSTR_H */ diff --git a/cpu/cortex-m4_common/include/cpu.h b/cpu/cortex-m4_common/include/cpu.h deleted file mode 100644 index 46250c10f7..0000000000 --- a/cpu/cortex-m4_common/include/cpu.h +++ /dev/null @@ -1,64 +0,0 @@ -/* - * 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_cortexm4_common ARM Cortex-M4 common - * @ingroup cpu - * @brief Common implementations and headers for Cortex-M4 family based micro-controllers - * @{ - * - * @file - * @brief Basic definitions for the Cortex-M4 common module - * - * When ever you want to do something hardware related, that is accessing MCUs registers directly, - * just include this file. It will then make sure that the MCU specific headers are included. - * - * @author Stefan Pfeiffer - * @author Hauke Petersen - * @author Joakim Gebart - */ - -#ifndef CORTEXM_COMMON_H_ -#define CORTEXM_COMMON_H_ - -/** - * @brief Cortex-M4 has architecture specific atomic operations in atomic_arch.c. - */ -#define ARCH_HAS_ATOMIC_COMPARE_AND_SWAP 1 - -#include "cpu_conf.h" - -/** - * For downwards compatibility with old RIOT code. - * TODO: remove once core was adjusted - */ -#include "irq.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * @brief Deprecated interrupt control function for backward compatibility - * @{ - */ -#define eINT enableIRQ -#define dINT disableIRQ -/** @} */ - -/** - * @brief Initialization of the CPU - */ -void cpu_init(void); - -#ifdef __cplusplus -} -#endif - -#endif /* CORTEXM_COMMON_H_ */ -/** @} */ diff --git a/cpu/cortex-m4_common/panic.c b/cpu/cortex-m4_common/panic.c deleted file mode 100644 index 61a923eb5e..0000000000 --- a/cpu/cortex-m4_common/panic.c +++ /dev/null @@ -1,34 +0,0 @@ -/* - * Copyright (C) 2015 INRIA - * Copyright (C) 2015 Eistec AB - * - * This file is subject to the terms and conditions of the GNU Lesser General - * Public License v2.1. See the file LICENSE in the top level directory for more - * details. - */ - -/** - * @ingroup cortex-m4_common - * @{ - * - * @file - * @brief Crash handling functions implementation for ARM Cortex-based MCUs - * - * @author Oliver Hahm - * @author Joakim Gebart - */ - -#include "cpu.h" -#include "lpm.h" - -void panic_arch(void) -{ -#if DEVELHELP - /* The bkpt instruction will signal to the debugger to break here. */ - __ASM("bkpt #0"); - /* enter infinite loop, into deepest possible sleep mode */ - while (1) { - lpm_set(LPM_OFF); - } -#endif -} diff --git a/cpu/cortex-m4_common/reboot_arch.c b/cpu/cortex-m4_common/reboot_arch.c deleted file mode 100644 index 174a6a5cce..0000000000 --- a/cpu/cortex-m4_common/reboot_arch.c +++ /dev/null @@ -1,34 +0,0 @@ -/* - * 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_cortexm4_common - * @{ - * - * @file - * @brief Implementation of the kernels reboot interface - * - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "arch/reboot_arch.h" -#include "cpu.h" -#include "hwtimer.h" - -int reboot_arch(int mode) -{ - printf("Going into reboot, mode %i\n", mode); - /* wait 1 ms to make sure the printf is finished */ - hwtimer_wait(HWTIMER_TICKS(1000)); - NVIC_SystemReset(); - return -1; -} diff --git a/cpu/cortex-m4_common/thread_arch.c b/cpu/cortex-m4_common/thread_arch.c deleted file mode 100644 index 7169435847..0000000000 --- a/cpu/cortex-m4_common/thread_arch.c +++ /dev/null @@ -1,256 +0,0 @@ -/* - * 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_cortexm4_common - * @{ - * - * @file - * @brief Implementation of the kernel's architecture dependent thread interface - * - * @author Stefan Pfeiffer - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "arch/thread_arch.h" -#include "sched.h" -#include "thread.h" -#include "irq.h" -#include "cpu.h" -#include "kernel_internal.h" - -/** - * @name noticeable marker marking the beginning of a stack segment - * - * This marker is used e.g. by *thread_arch_start_threading* to identify the stacks start. - */ -#define STACK_MARKER (0x77777777) - -/** - * @name ARM Cortex-M specific exception return value, that triggers the return to the task mode - * stack pointer - */ -#define EXCEPT_RET_TASK_MODE (0xfffffffd) - -/** - * Cortex-M knows stacks and handles register backups, so use different stack frame layout - * - * \todo Cortex-M thread_arch_stack_init: How to handle different Cortex-Ms? Code is so far valid for M3 and M4 without FPU - * - * Layout with storage of floating point registers (applicable for Cortex-M4): - * ------------------------------------------------------------------------------------------------------------------------------------ - * | R0 | R1 | R2 | R3 | LR | PC | xPSR | S0 | S1 | S2 | S3 | S4 | S5 | S6 | S7 | S8 | S9 | S10 | S11 | S12 | S13 | S14 | S15 | FPSCR | - * ------------------------------------------------------------------------------------------------------------------------------------ - * - * Layout without floating point registers: - * -------------------------------------- - * | R0 | R1 | R2 | R3 | LR | PC | xPSR | - * -------------------------------------- - * - */ -char *thread_arch_stack_init(thread_task_func_t task_func, - void *arg, - void *stack_start, - int stack_size) -{ - uint32_t *stk; - stk = (uint32_t *)((uintptr_t)stack_start + stack_size); - - /* adjust to 32 bit boundary by clearing the last two bits in the address */ - stk = (uint32_t *)(((uint32_t)stk) & ~((uint32_t)0x3)); - - /* Stack start marker */ - stk--; - *stk = STACK_MARKER; - - /* Make sure the stack is double word aligned (8 bytes) */ - /* This is required in order to conform with Procedure Call Standard for the - * ARM® Architecture (AAPCS) */ - /* http://infocenter.arm.com/help/topic/com.arm.doc.ihi0042e/IHI0042E_aapcs.pdf */ - if (((uint32_t) stk % 8) != 0) { - /* add a single word padding */ - --stk; - *stk = ~((uint32_t)STACK_MARKER); - } - - /* TODO: fix FPU handling for Cortex-M4 */ - /* - stk--; - *stk = (unsigned int) 0; - */ - - /* S0 - S15 */ - /* - for (int i = 15; i >= 0; i--) { - stk--; - *stk = i; - } - */ - - /* ****************************** */ - /* Automatically popped registers */ - /* ****************************** */ - - /* The following eight stacked registers are popped by the hardware upon - * return from exception. (bx instruction in context_restore) */ - - /* xPSR */ - stk--; - /* Setting bit 9 (0x200) of xPSR will cause the initial stack pointer for - * the process to be aligned on a 32-bit, non-64-bit, boundary. Don't do that. */ - /* Default xPSR, only the Thumb mode-bit is set */ - *stk = 0x01000000; - - /* pc */ - stk--; - /* initial program counter */ - *stk = (uint32_t) task_func; - - /* lr */ - stk--; - /* link register, return address when a thread exits. */ - *stk = (uint32_t) sched_task_exit; - - /* r12 */ - stk--; - *stk = 0; - - /* r1 - r3 */ - for (int i = 3; i >= 1; i--) { - stk--; - *stk = i; - } - - /* r0 */ - stk--; - /* thread function parameter */ - *stk = (uint32_t) arg; - - /* 8 hardware-handled registers in total */ - - /* ************************* */ - /* Manually popped registers */ - /* ************************* */ - - /* The following registers are not handled by hardware in return from - * exception, but manually by context_restore. */ - - /* r11 - r4 */ - for (int i = 11; i >= 4; i--) { - stk--; - *stk = i; - } - - /* exception return code */ - stk--; - *stk = EXCEPT_RET_TASK_MODE; /* return to task-mode process stack pointer */ - - /* 9 manually handled registers in total. */ - - /* The returned stack pointer will be aligned on a 32 bit boundary not on a - * 64 bit boundary because of the odd number of registers above (8+9). - * This is not a problem since the initial stack pointer upon process entry - * _will_ be 64 bit aligned (because of the cleared bit 9 in the stacked - * xPSR and aligned stacking of the hardware-handled registers). */ - - return (char*) stk; -} - -void thread_arch_stack_print(void) -{ - int count = 0; - uint32_t *sp = (uint32_t *)sched_active_thread->sp; - - printf("printing the current stack of thread %" PRIkernel_pid "\n", thread_getpid()); - printf(" address: data:\n"); - - do { - printf(" 0x%08x: 0x%08x\n", (unsigned int)sp, (unsigned int)*sp); - sp++; - count++; - } while (*sp != STACK_MARKER); - - printf("current stack size: %i byte\n", count); -} - -__attribute__((naked)) void NORETURN thread_arch_start_threading(void) -{ - /* enable IRQs to make sure the SVC interrupt is reachable */ - __ASM volatile ("bl irq_arch_enable\n"); - - /* trigger the SVC interrupt which will get and execute the next thread */ - __ASM volatile ("svc #1\n"); - - /* This line is unreachable, infinite loop */ - __ASM volatile ( - "unreachable%=:\n" - "b unreachable%=\n" - :::); -} - -void thread_arch_yield(void) -{ - /* trigger the PENDSV interrupt to run scheduler and schedule new thread if applicable */ - SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; -} - -/** - * @brief The svc is used for running the scheduler and scheduling a new task during start-up or - * after a thread has exited - */ -void isr_svc(void); - -/** - * @brief All task switching activity is carried out in the PendSV interrupt - */ -void isr_pendsv(void); - -__attribute__((naked)) void arch_context_switch(void) -{ - /* {r0-r3,r12,LR,PC,xPSR} are saved automatically on exception entry */ - __ASM volatile ( - /* PendSV handler entry point */ - ".global isr_pendsv \n" - ".thumb_func \n" - "isr_pendsv: \n" - /* Save the context */ - /* save unsaved registers */ - ".thumb_func \n" - "context_save:" - "mrs r0, psp \n" /* get stack pointer from user mode */ - "stmdb r0!,{r4-r11} \n" /* save regs */ - "stmdb r0!,{lr} \n" /* exception return value */ -/* "vstmdb sp!, {s16-s31} \n" */ /* TODO save FPU registers if needed */ - "ldr r1, =sched_active_thread \n" /* load address of current tcb */ - "ldr r1, [r1] \n" /* dereference pdc */ - "str r0, [r1] \n" /* write r0 to pdc->sp means current threads stack pointer */ - /* SVC handler entry point */ - /* PendSV will continue from above and through this part as well */ - ".global isr_svc \n" - ".thumb_func \n" - "isr_svc: \n" - /* perform scheduling */ - "bl sched_run \n" - /* Restore context and return from exception */ - ".thumb_func \n" - "context_restore: \n" - "ldr r0, =sched_active_thread \n" /* load address of current TCB */ - "ldr r0, [r0] \n" /* dereference TCB */ - "ldr r1, [r0] \n" /* load tcb->sp to register 1 */ - "ldmia r1!, {r0} \n" /* restore exception return value from stack */ -/* "pop {s16-s31} \n" */ /* TODO load FPU register if needed depends on r0 exret */ - "ldmia r1!, {r4-r11} \n" /* restore other registers */ - "msr psp, r1 \n" /* restore PSP register (user mode SP)*/ - "bx r0 \n" /* load exception return value to PC causes end of exception*/ - /* {r0-r3,r12,LR,PC,xPSR} are restored automatically on exception return */ - ); -} diff --git a/cpu/cortex-m3_common/Makefile b/cpu/cortexm_common/Makefile similarity index 100% rename from cpu/cortex-m3_common/Makefile rename to cpu/cortexm_common/Makefile diff --git a/cpu/cortexm_common/Makefile.include b/cpu/cortexm_common/Makefile.include new file mode 100644 index 0000000000..3d08ba2017 --- /dev/null +++ b/cpu/cortexm_common/Makefile.include @@ -0,0 +1,2 @@ +# include module specific includes +export INCLUDES += -I$(RIOTCPU)/cortexm_common/include diff --git a/cpu/cortex-m4_common/atomic_arch.c b/cpu/cortexm_common/atomic_arch.c similarity index 87% rename from cpu/cortex-m4_common/atomic_arch.c rename to cpu/cortexm_common/atomic_arch.c index 6827189e3b..640fb794a2 100644 --- a/cpu/cortex-m4_common/atomic_arch.c +++ b/cpu/cortexm_common/atomic_arch.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014-2015 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 @@ -7,7 +7,7 @@ */ /** - * @ingroup cpu_cortexm4_common + * @ingroup cpu_cortexm_common * @{ * * @file @@ -25,6 +25,7 @@ #include "irq.h" #include "cpu.h" +#if ARCH_HAS_ATOMIC_COMPARE_AND_SWAP int atomic_cas(atomic_int_t *var, int old, int now) { int tmp; @@ -44,3 +45,4 @@ int atomic_cas(atomic_int_t *var, int old, int now) return (status == 0); } +#endif diff --git a/cpu/cortex-m0_common/include/core_cm0.h b/cpu/cortexm_common/include/core_cm0.h similarity index 100% rename from cpu/cortex-m0_common/include/core_cm0.h rename to cpu/cortexm_common/include/core_cm0.h diff --git a/cpu/cortex-m0_common/include/core_cm0plus.h b/cpu/cortexm_common/include/core_cm0plus.h similarity index 100% rename from cpu/cortex-m0_common/include/core_cm0plus.h rename to cpu/cortexm_common/include/core_cm0plus.h diff --git a/cpu/cortex-m3_common/include/core_cm3.h b/cpu/cortexm_common/include/core_cm3.h similarity index 100% rename from cpu/cortex-m3_common/include/core_cm3.h rename to cpu/cortexm_common/include/core_cm3.h diff --git a/cpu/cortex-m4_common/include/core_cm4.h b/cpu/cortexm_common/include/core_cm4.h similarity index 100% rename from cpu/cortex-m4_common/include/core_cm4.h rename to cpu/cortexm_common/include/core_cm4.h diff --git a/cpu/cortex-m0_common/include/core_cmFunc.h b/cpu/cortexm_common/include/core_cmFunc.h similarity index 100% rename from cpu/cortex-m0_common/include/core_cmFunc.h rename to cpu/cortexm_common/include/core_cmFunc.h diff --git a/cpu/cortex-m0_common/include/core_cmInstr.h b/cpu/cortexm_common/include/core_cmInstr.h similarity index 100% rename from cpu/cortex-m0_common/include/core_cmInstr.h rename to cpu/cortexm_common/include/core_cmInstr.h diff --git a/cpu/cortex-m4_common/include/core_cmSimd.h b/cpu/cortexm_common/include/core_cmSimd.h similarity index 100% rename from cpu/cortex-m4_common/include/core_cmSimd.h rename to cpu/cortexm_common/include/core_cmSimd.h diff --git a/cpu/cortex-m3_common/include/cpu.h b/cpu/cortexm_common/include/cpu.h similarity index 59% rename from cpu/cortex-m3_common/include/cpu.h rename to cpu/cortexm_common/include/cpu.h index f744c014df..0c6d8bccc9 100644 --- a/cpu/cortex-m3_common/include/cpu.h +++ b/cpu/cortexm_common/include/cpu.h @@ -1,5 +1,5 @@ /* - * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014-2015 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 @@ -7,16 +7,18 @@ */ /** - * @defgroup cpu_cortexm3_common ARM Cortex-M3 common + * @defgroup cpu_cortexm_common ARM Cortex-M common * @ingroup cpu - * @brief Common implementations and headers for Cortex-M3 family based micro-controllers + * @brief Common implementations and headers for Cortex-M family based + * micro-controllers * @{ * * @file - * @brief Basic definitions for the Cortex-M3 common module + * @brief Basic definitions for the Cortex-M common module * - * When ever you want to do something hardware related, that is accessing MCUs registers directly, - * just include this file. It will then make sure that the MCU specific headers are included. + * When ever you want to do something hardware related, that is accessing MCUs + * registers, just include this file. It will then make sure that the MCU + * specific headers are included. * * @author Stefan Pfeiffer * @author Hauke Petersen @@ -26,15 +28,10 @@ #ifndef CORTEXM_COMMON_H_ #define CORTEXM_COMMON_H_ -/** - * @brief Cortex-M3 has architecture specific atomic operations in atomic_arch.c. - */ -#define ARCH_HAS_ATOMIC_COMPARE_AND_SWAP 1 #include "cpu_conf.h" /** - * For downwards compatibility with old RIOT code. * TODO: remove once core was adjusted */ #include "irq.h" @@ -52,7 +49,16 @@ extern "C" { /** @} */ /** - * @brief Initialization of the CPU + * @brief Some members of the Cortex-M family have architecture specific atomic + * operations in atomic_arch.c + */ +#if defined(CPU_ARCH_CORTEX_M3) || defined(CPU_ARCH_CORTEX_M4) || \ + defined(CPU_ARCH_CORTEX_M4F) +#define ARCH_HAS_ATOMIC_COMPARE_AND_SWAP 1 +#endif + +/** + * @brief Initialization of the CPU */ void cpu_init(void); diff --git a/cpu/cortex-m4_common/irq_arch.c b/cpu/cortexm_common/irq_arch.c similarity index 91% rename from cpu/cortex-m4_common/irq_arch.c rename to cpu/cortexm_common/irq_arch.c index 098b598476..28f33c0362 100644 --- a/cpu/cortex-m4_common/irq_arch.c +++ b/cpu/cortexm_common/irq_arch.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014-2015 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 @@ -7,7 +7,7 @@ */ /** - * @ingroup cpu_cortexm4_common + * @ingroup cpu_cortexm_common * @{ * * @file diff --git a/cpu/cortex-m0_common/panic.c b/cpu/cortexm_common/panic.c similarity index 95% rename from cpu/cortex-m0_common/panic.c rename to cpu/cortexm_common/panic.c index ddcbdc635a..ade9a57817 100644 --- a/cpu/cortex-m0_common/panic.c +++ b/cpu/cortexm_common/panic.c @@ -8,7 +8,7 @@ */ /** - * @ingroup cortex-m0_common + * @ingroup cortex-m_common * @{ * * @file diff --git a/cpu/cortex-m0_common/reboot_arch.c b/cpu/cortexm_common/reboot_arch.c similarity index 88% rename from cpu/cortex-m0_common/reboot_arch.c rename to cpu/cortexm_common/reboot_arch.c index 4774572398..16a85754d3 100644 --- a/cpu/cortex-m0_common/reboot_arch.c +++ b/cpu/cortexm_common/reboot_arch.c @@ -1,5 +1,5 @@ /* - * Copyright (C) 2014 Freie Universität Berlin + * Copyright (C) 2014-2015 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 @@ -7,7 +7,7 @@ */ /** - * @ingroup cpu_cortexm0_common + * @ingroup cpu_cortexm_common * @{ * * @file diff --git a/cpu/cortexm_common/thread_arch.c b/cpu/cortexm_common/thread_arch.c new file mode 100644 index 0000000000..e6eed693e0 --- /dev/null +++ b/cpu/cortexm_common/thread_arch.c @@ -0,0 +1,353 @@ +/* + * Copyright (C) 2014-2015 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_cortexm_common + * @{ + * + * @file + * @brief Implementation of the kernel's architecture dependent thread + * interface + * + * Members of the Cortex-M family know stacks and are able to handle register + * backups partly, so we make use of that. + * + * Cortex-M3 and Cortex-M4 use the + * following register layout when saving their context onto the stack: + * + * -------- highest address (bottom of stack) + * | xPSR | + * -------- + * | PC | + * -------- + * | LR | + * -------- + * | R12 | + * -------- + * | R3 | + * -------- + * | R2 | + * -------- + * | R1 | + * -------- + * | R0 | <- the registers from xPSR to R0 are handled by hardware + * -------- + * | R11 | + * -------- + * | R10 | + * -------- + * | R9 | + * -------- + * | R8 | + * -------- + * | R7 | + * -------- + * | R6 | + * -------- + * | R5 | + * -------- + * | R4 | + * -------- + * | RET | <- exception return code + * -------- lowest address (top of stack) + * + * For the Cortex-M0 and Cortex-M0plus we use a slightly different layout by + * switching the blocks R11-R8 and R7-R4. This allows more efficient code when + * saving/restoring the context: + * + * ------------- highest address (bottom of stack) + * | xPSR - R0 | <- same as for Cortex-M3/4 + * ------------- + * | R7 | + * -------- + * | R6 | + * -------- + * | R5 | + * -------- + * | R4 | + * -------- + * | R11 | + * -------- + * | R10 | + * -------- + * | R9 | + * -------- + * | R8 | + * -------- + * | RET | <- exception return code + * -------- lowest address (top of stack) + * + * TODO: Implement handling of FPU registers for Cortex-M4 CPUs + * + * + * @author Stefan Pfeiffer + * @author Hauke Petersen + * @author Joakim Gebart + * + * @} + */ + +#include + +#include "arch/thread_arch.h" +#include "sched.h" +#include "thread.h" +#include "irq.h" +#include "cpu.h" +#include "kernel_internal.h" + +/** + * @brief Noticeable marker marking the beginning of a stack segment + * + * This marker is used e.g. by *thread_arch_start_threading* to identify the + * stacks beginning. + */ +#define STACK_MARKER (0x77777777) + +/** + * @brief Initial program status register value for a newly created thread + * + * In the initial state, only the Thumb mode-bit is set + */ +#define INITIAL_XPSR (0x01000000) + +/** + * @brief ARM Cortex-M specific exception return value, that triggers the + * return to the task mode stack pointer + */ +#define EXCEPT_RET_TASK_MODE (0xfffffffd) + +char *thread_arch_stack_init(thread_task_func_t task_func, + void *arg, + void *stack_start, + int stack_size) +{ + uint32_t *stk; + stk = (uint32_t *)((uintptr_t)stack_start + stack_size); + + /* adjust to 32 bit boundary by clearing the last two bits in the address */ + stk = (uint32_t *)(((uint32_t)stk) & ~((uint32_t)0x3)); + + /* stack start marker */ + stk--; + *stk = STACK_MARKER; + + /* make sure the stack is double word aligned (8 bytes) */ + /* This is required in order to conform with Procedure Call Standard for the + * ARM® Architecture (AAPCS) */ + /* http://infocenter.arm.com/help/topic/com.arm.doc.ihi0042e/IHI0042E_aapcs.pdf */ + if (((uint32_t) stk & 0x7) != 0) { + /* add a single word padding */ + --stk; + *stk = ~((uint32_t)STACK_MARKER); + } + +#ifdef CPU_ARCH_CORTEX_M4F + /* TODO: fix FPU handling for Cortex-M4f */ + /* + stk--; + *stk = (unsigned int) 0; + */ + + /* S0 - S15 */ + /* + for (int i = 15; i >= 0; i--) { + stk--; + *stk = i; + } + */ +#endif + + /* ****************************** */ + /* Automatically popped registers */ + /* ****************************** */ + + /* The following eight stacked registers are popped by the hardware upon + * return from exception. (bx instruction in context_restore) */ + + /* xPSR - initial status register */ + stk--; + *stk = (uint32_t)INITIAL_XPSR; + /* pc - initial program counter value := thread entry function */ + stk--; + *stk = (uint32_t)task_func; + /* lr - contains the return address when the thread exits */ + stk--; + *stk = (uint32_t)sched_task_exit; + /* r12 */ + stk--; + *stk = 0; + /* r3 - r1 */ + for (int i = 3; i >= 1; i--) { + stk--; + *stk = i; + } + /* r0 - contains the thread function parameter */ + stk--; + *stk = (uint32_t)arg; + + /* ************************* */ + /* Manually popped registers */ + /* ************************* */ + + /* The following registers are not handled by hardware in return from + * exception, but manually by context_restore. + * For the Cortex-M0(plus) we write registers R11-R4 in two groups to allow + * for more efficient context save/restore code. + * For the Cortex-M3 and Cortex-M4 we write them continuously onto the stack + * as they can be read/written continuously by stack instructions. */ + +#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) + /* start with r7 - r4 */ + for (int i = 7; i >= 4; i--) { + stk--; + *stk = i; + } + /* and put r11 - r8 on top of them */ + for (int i = 11; i >= 8; i--) { + stk--; + *stk = i; + } +#else + /* r11 - r4 */ + for (int i = 11; i >= 4; i--) { + stk--; + *stk = i; + } +#endif + + /* exception return code - return to task-mode process stack pointer */ + stk--; + *stk = (uint32_t)EXCEPT_RET_TASK_MODE; + + /* The returned stack pointer will be aligned on a 32 bit boundary not on a + * 64 bit boundary because of the odd number of registers above (8+9). + * This is not a problem since the initial stack pointer upon process entry + * _will_ be 64 bit aligned (because of the cleared bit 9 in the stacked + * xPSR and aligned stacking of the hardware-handled registers). */ + + return (char*) stk; +} + +void thread_arch_stack_print(void) +{ + int count = 0; + uint32_t *sp = (uint32_t *)sched_active_thread->sp; + + printf("printing the current stack of thread %" PRIkernel_pid "\n", + thread_getpid()); + printf(" address: data:\n"); + + do { + printf(" 0x%08x: 0x%08x\n", (unsigned int)sp, (unsigned int)*sp); + sp++; + count++; + } while (*sp != STACK_MARKER); + + printf("current stack size: %i byte\n", count); +} + +__attribute__((naked)) void NORETURN thread_arch_start_threading(void) +{ + __ASM volatile ( + "bl irq_arch_enable \n" /* enable IRQs to make the SVC + * interrupt is reachable */ + "svc #1 \n" /* trigger the SVC interrupt */ + "unreachable%=: \n" /* this loop is unreachable */ + "b unreachable%= \n" /* loop indefinitely */ + :::); +} + +void thread_arch_yield(void) +{ + /* trigger the PENDSV interrupt to run scheduler and schedule new thread if + * applicable */ + SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; +} + +__attribute__((naked)) void arch_context_switch(void) +{ + __ASM volatile ( + /* PendSV handler entry point */ + ".global isr_pendsv \n" + ".thumb_func \n" + "isr_pendsv: \n" + /* save context by pushing unsaved registers to the stack */ + /* {r0-r3,r12,LR,PC,xPSR} are saved automatically on exception entry */ + ".thumb_func \n" + "context_save:" + "mrs r0, psp \n" /* get stack pointer from user mode */ +#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) + "mov r12, sp \n" /* remember the exception SP */ + "mov sp, r0 \n" /* set user mode SP as active SP */ + /* we can not push high registers directly, so we move R11-R8 into + * R4-R0, as these are already saved */ + "mov r0, r8 \n" /* move R11-R8 into R3-R0 */ + "mov r1, r9 \n" + "mov r2, r10 \n" + "mov r3, r11 \n" + "push {r0-r7} \n" /* now push them onto the stack */ + "mov r0, lr \n" /* next we save the link register */ + "push {r0} \n" + "mov r0, sp \n" /* switch back to the exception SP */ + "mov sp, r12 \n" +#else + "stmdb r0!,{r4-r11} \n" /* save regs */ + "stmdb r0!,{lr} \n" /* exception return value */ +#ifdef CPU_ARCH_CORTEX_M4F +/* "vstmdb sp!, {s16-s31} \n" */ /* TODO save FPU registers */ +#endif +#endif + "ldr r1, =sched_active_thread \n" /* load address of current tcb */ + "ldr r1, [r1] \n" /* dereference pdc */ + "str r0, [r1] \n" /* write r0 to pdc->sp */ + /* SVC handler entry point */ + /* PendSV will continue from above and through this part as well */ + ".global isr_svc \n" + ".thumb_func \n" + "isr_svc: \n" + /* perform scheduling */ + "bl sched_run \n" + /* restore context and return from exception */ + ".thumb_func \n" + "context_restore: \n" +#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) + "mov lr, sp \n" /* save MSR stack pointer for later */ + "ldr r0, =sched_active_thread \n" /* load address of current TCB */ + "ldr r0, [r0] \n" /* dereference TCB */ + "ldr r0, [r0] \n" /* load tcb-sp to R0 */ + "mov sp, r0 \n" /* make user mode SP active SP */ + "pop {r0} \n" /* restore LR from stack */ + "mov r12, r0 \n" /* remember LR by parking it in R12 */ + "pop {r0-r7} \n" /* get R11-R8 and R7-R4 from stack */ + "mov r8, r0 \n" /* move R11-R8 to correct registers */ + "mov r9, r1 \n" + "mov r10, r2 \n" + "mov r11, r3 \n" + /* restore the application mode stack pointer PSP */ + "mov r0, sp \n" /* restore the user mode SP */ + "msr psp, r0 \n" /* for this write it to the PSP reg */ + "mov sp, lr \n" /* and get the parked MSR SP back */ + /* return from exception mode to application mode */ + "bx r12 \n" /* return from exception mode */ +#else + "ldr r0, =sched_active_thread \n" /* load address of current TCB */ + "ldr r0, [r0] \n" /* dereference TCB */ + "ldr r1, [r0] \n" /* load tcb->sp to register 1 */ + "ldmia r1!, {r0} \n" /* restore exception return value */ +#ifdef CPU_ARCH_CORTEX_M4F +/* "pop {s16-s31} \n" */ /* TODO load FPU registers */ +#endif + "ldmia r1!, {r4-r11} \n" /* restore other registers */ + "msr psp, r1 \n" /* restore user mode SP to PSP reg */ + "bx r0 \n" /* load exception return value to PC, + * causes end of exception*/ +#endif + /* {r0-r3,r12,LR,PC,xPSR} are restored automatically on exception return */ + ); +} From 97b6c561784ec02c9879147285feeb1935d3e6fa Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Thu, 28 May 2015 15:08:21 +0200 Subject: [PATCH 2/8] boards: moved flashing options to openocd Makefile --- boards/Makefile.include.openocd | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/boards/Makefile.include.openocd b/boards/Makefile.include.openocd index 390f3462b0..1f836ea033 100644 --- a/boards/Makefile.include.openocd +++ b/boards/Makefile.include.openocd @@ -2,3 +2,9 @@ export FLASHER = $(RIOTBASE)/dist/tools/openocd/openocd.sh export DEBUGGER = $(RIOTBASE)/dist/tools/openocd/openocd.sh export DEBUGSERVER = $(RIOTBASE)/dist/tools/openocd/openocd.sh export RESET = $(RIOTBASE)/dist/tools/openocd/openocd.sh + +export OFLAGS ?= -O ihex +export FFLAGS ?= flash +export DEBUGGER_FLAGS ?= debug +export DEBUGSERVER_FLAGS ?= debug-server +export RESET_FLAGS ?= reset From 49dcb692d1bc88f565720bff205d567a715de3f0 Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Thu, 28 May 2015 15:09:17 +0200 Subject: [PATCH 3/8] boards: adapted Makefiles to cortexm_common folder - changed naming of cortexm_common in makefiles - included some minor cleanups --- boards/airfy-beacon/Makefile.include | 2 +- boards/arduino-due/Makefile.include | 10 ++++++---- boards/cc2538dk/Makefile.include | 3 +-- boards/f4vi1/Makefile.include | 4 ++-- boards/fox/Makefile.include | 2 +- boards/iot-lab_M3/Makefile.include | 5 +---- boards/mbed_lpc1768/Makefile.include | 4 +++- boards/msbiot/Makefile.include | 2 +- boards/nucleo-f091/Makefile.include | 2 +- boards/nucleo-f334/Makefile.include | 2 +- boards/nucleo-l1/Makefile.include | 2 +- boards/openmote/Makefile.include | 2 +- boards/pca10000/Makefile.include | 2 +- boards/pca10005/Makefile.include | 2 +- boards/saml21-xpro/Makefile.include | 2 +- boards/samr21-xpro/Makefile | 1 - boards/samr21-xpro/Makefile.include | 6 +++--- boards/spark-core/Makefile.include | 2 +- boards/stm32f0discovery/Makefile.include | 2 +- boards/stm32f3discovery/Makefile.include | 2 +- boards/stm32f4discovery/Makefile.include | 2 +- boards/udoo/Makefile.include | 3 ++- boards/yunjia-nrf51822/Makefile.include | 2 +- 23 files changed, 33 insertions(+), 33 deletions(-) diff --git a/boards/airfy-beacon/Makefile.include b/boards/airfy-beacon/Makefile.include index 659c6665db..290d5b4a43 100644 --- a/boards/airfy-beacon/Makefile.include +++ b/boards/airfy-beacon/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/arduino-due/Makefile.include b/boards/arduino-due/Makefile.include index 3b75b2d5d9..4853a41519 100644 --- a/boards/arduino-due/Makefile.include +++ b/boards/arduino-due/Makefile.include @@ -1,15 +1,17 @@ # define the cpu used by the arduino due board export CPU = sam3x8e - -export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/flash.sh -export OFLAGS = -O binary +export CPU_MODEL = sam3x8e # define the default port depending on the host OS PORT_LINUX ?= /dev/ttyACM0 PORT_DARWIN ?= $(shell ls -1 /dev/tty.usbmodem* | head -n 1) +# define board specific flasher options +export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/flash.sh +export OFLAGS = -O binary + # setup serial terminal include $(RIOTBOARD)/Makefile.include.serial # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/cc2538dk/Makefile.include b/boards/cc2538dk/Makefile.include index d4a54e0b10..7ffa8da52e 100644 --- a/boards/cc2538dk/Makefile.include +++ b/boards/cc2538dk/Makefile.include @@ -22,7 +22,6 @@ else ifeq ($(PROGRAMMER),jlink) export FFLAGS = $(BINDIR) $(HEXFILE) endif -export LINKFLAGS += -L$(RIOTCPU)/$(CPU) export OFLAGS = -O binary --gap-fill 0xff export HEXFILE = $(ELFFILE:.elf=.bin) export DEBUGGER_FLAGS = $(BINDIR) $(ELFFILE) @@ -31,4 +30,4 @@ export RESET_FLAGS = $(BINDIR) export OBJDUMPFLAGS += --disassemble --source --disassembler-options=force-thumb # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/f4vi1/Makefile.include b/boards/f4vi1/Makefile.include index 5a38d26a77..ec0c76870b 100644 --- a/boards/f4vi1/Makefile.include +++ b/boards/f4vi1/Makefile.include @@ -14,10 +14,10 @@ export FLASHER = st-flash export DEBUGGER = $(RIOTBOARD)/$(BOARD)/dist/debug.sh export DEBUGSERVER = st-util -# +# define st-flash parameters export OFLAGS = -O binary export FFLAGS = write bin/$(BOARD)/$(APPLICATION).hex 0x8000000 export DEBUGGER_FLAGS = $(RIOTBOARD)/$(BOARD)/dist/gdb.conf $(BINDIR)/$(APPLICATION).elf # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/fox/Makefile.include b/boards/fox/Makefile.include index c972c3d09b..736a5ee29a 100644 --- a/boards/fox/Makefile.include +++ b/boards/fox/Makefile.include @@ -16,4 +16,4 @@ include $(RIOTBOARD)/Makefile.include.openocd include $(RIOTBOARD)/$(BOARD)/Makefile.dep # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/iot-lab_M3/Makefile.include b/boards/iot-lab_M3/Makefile.include index 018f7a9b84..57206e0f1b 100644 --- a/boards/iot-lab_M3/Makefile.include +++ b/boards/iot-lab_M3/Makefile.include @@ -13,11 +13,8 @@ include $(RIOTBOARD)/Makefile.include.serial # this board uses openocd include $(RIOTBOARD)/Makefile.include.openocd -# export board specific includes to the global includes-listing -export INCLUDES += -I$(RIOTBASE)/drivers/at86rf231/include -I$(RIOTBASE)/sys/net/include - # include board dependencies include $(RIOTBOARD)/$(BOARD)/Makefile.dep # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/mbed_lpc1768/Makefile.include b/boards/mbed_lpc1768/Makefile.include index a8d25728a6..d793033390 100644 --- a/boards/mbed_lpc1768/Makefile.include +++ b/boards/mbed_lpc1768/Makefile.include @@ -1,5 +1,7 @@ # define the cpu used by the mbed_lpx1768 board export CPU = lpc1768 +export CPU_MODEL = lpc1768 + export FLASHER = $(RIOTBOARD)/$(BOARD)/dist/flash.sh export DEBUGGER = @@ -18,4 +20,4 @@ PORT_DARWIN ?= $(shell ls -1 /dev/tty.SLAB_USBtoUART* | head -n 1) include $(RIOTBOARD)/Makefile.include.serial # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/msbiot/Makefile.include b/boards/msbiot/Makefile.include index 51e5579efb..30d333740d 100644 --- a/boards/msbiot/Makefile.include +++ b/boards/msbiot/Makefile.include @@ -20,4 +20,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/nucleo-f091/Makefile.include b/boards/nucleo-f091/Makefile.include index b8ca26b9cc..cf2396f504 100644 --- a/boards/nucleo-f091/Makefile.include +++ b/boards/nucleo-f091/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/nucleo-f334/Makefile.include b/boards/nucleo-f334/Makefile.include index 6637da3c5b..9fe952f6b3 100644 --- a/boards/nucleo-f334/Makefile.include +++ b/boards/nucleo-f334/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/nucleo-l1/Makefile.include b/boards/nucleo-l1/Makefile.include index 977038bf43..d734313501 100644 --- a/boards/nucleo-l1/Makefile.include +++ b/boards/nucleo-l1/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/openmote/Makefile.include b/boards/openmote/Makefile.include index de705ca421..7519e44551 100644 --- a/boards/openmote/Makefile.include +++ b/boards/openmote/Makefile.include @@ -25,4 +25,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/pca10000/Makefile.include b/boards/pca10000/Makefile.include index 8036b2fcf5..428f45eb2b 100644 --- a/boards/pca10000/Makefile.include +++ b/boards/pca10000/Makefile.include @@ -22,4 +22,4 @@ export RESET_FLAGS = $(BINDIR) include $(RIOTBOARD)/Makefile.include.serial # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/pca10005/Makefile.include b/boards/pca10005/Makefile.include index 2a9621c983..6d0267045a 100644 --- a/boards/pca10005/Makefile.include +++ b/boards/pca10005/Makefile.include @@ -23,4 +23,4 @@ export RESET_FLAGS = $(BINDIR) include $(RIOTBOARD)/Makefile.include.serial # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/saml21-xpro/Makefile.include b/boards/saml21-xpro/Makefile.include index ae8154e966..6eb631cd17 100644 --- a/boards/saml21-xpro/Makefile.include +++ b/boards/saml21-xpro/Makefile.include @@ -14,4 +14,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/samr21-xpro/Makefile b/boards/samr21-xpro/Makefile index e0fe9b201a..37891de8e6 100644 --- a/boards/samr21-xpro/Makefile +++ b/boards/samr21-xpro/Makefile @@ -1,5 +1,4 @@ # tell the Makefile.base which module to build MODULE = $(BOARD)_base - include $(RIOTBASE)/Makefile.base diff --git a/boards/samr21-xpro/Makefile.include b/boards/samr21-xpro/Makefile.include index abd4714439..9f592f1722 100644 --- a/boards/samr21-xpro/Makefile.include +++ b/boards/samr21-xpro/Makefile.include @@ -2,13 +2,13 @@ export CPU = samd21 export CPU_MODEL = samr21g18a -# +# TODO: remove once the CPU implementation is stable with -Os CFLAGS_OPT = -O0 # set default port depending on operating system PORT_LINUX ?= /dev/ttyACM0 -# +# setup the boards dependencies include $(RIOTBOARD)/$(BOARD)/Makefile.dep # setup serial terminal @@ -18,4 +18,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/spark-core/Makefile.include b/boards/spark-core/Makefile.include index 23b83527f3..c37a22421b 100644 --- a/boards/spark-core/Makefile.include +++ b/boards/spark-core/Makefile.include @@ -26,4 +26,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/stm32f0discovery/Makefile.include b/boards/stm32f0discovery/Makefile.include index 7e3209544c..1916caaabe 100644 --- a/boards/stm32f0discovery/Makefile.include +++ b/boards/stm32f0discovery/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/stm32f3discovery/Makefile.include b/boards/stm32f3discovery/Makefile.include index 323d4a72b8..fef01aa1d4 100644 --- a/boards/stm32f3discovery/Makefile.include +++ b/boards/stm32f3discovery/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/stm32f4discovery/Makefile.include b/boards/stm32f4discovery/Makefile.include index 63b8480a50..fa75792a0d 100644 --- a/boards/stm32f4discovery/Makefile.include +++ b/boards/stm32f4discovery/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/udoo/Makefile.include b/boards/udoo/Makefile.include index 50dce42b98..2f3f84c1f8 100644 --- a/boards/udoo/Makefile.include +++ b/boards/udoo/Makefile.include @@ -1,5 +1,6 @@ # define the cpu used by the udoo board export CPU = sam3x8e +export CPU_MODEL = sam3x8e #define the flash-tool and default port depending on the host operating system OS := $(shell uname) @@ -23,4 +24,4 @@ export FFLAGS = -R -e -w -v -b bin/$(BOARD)/$(APPLICATION).hex include $(RIOTBOARD)/Makefile.include.serial # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common diff --git a/boards/yunjia-nrf51822/Makefile.include b/boards/yunjia-nrf51822/Makefile.include index 04859dfb42..a4a8d7a70e 100644 --- a/boards/yunjia-nrf51822/Makefile.include +++ b/boards/yunjia-nrf51822/Makefile.include @@ -13,4 +13,4 @@ include $(RIOTBOARD)/Makefile.include.serial include $(RIOTBOARD)/Makefile.include.openocd # include cortex defaults -include $(RIOTBOARD)/Makefile.include.cortex_common +include $(RIOTBOARD)/Makefile.include.cortexm_common From 0d5c8546f3e5de71142e10662b29edad1f8d6716 Mon Sep 17 00:00:00 2001 From: haukepetersen Date: Tue, 26 May 2015 20:54:09 +0200 Subject: [PATCH 4/8] cpu: adapted Makefiles to unified cortexm module --- cpu/cc2538/Makefile | 2 +- cpu/cc2538/Makefile.include | 5 ++--- cpu/k60/Makefile | 2 +- cpu/k60/Makefile.include | 10 +++++----- cpu/kw2x/Makefile | 2 +- cpu/kw2x/Makefile.include | 7 ++----- cpu/lpc1768/Makefile | 2 +- cpu/lpc1768/Makefile.include | 4 ++-- cpu/nrf51822/Makefile | 2 +- cpu/nrf51822/Makefile.include | 4 ++-- cpu/sam3x8e/Makefile | 2 +- cpu/sam3x8e/Makefile.include | 4 ++-- cpu/samd21/Makefile | 2 +- cpu/samd21/Makefile.include | 6 +++--- cpu/saml21/Makefile | 2 +- cpu/saml21/Makefile.include | 4 ++-- cpu/stm32f0/Makefile | 2 +- cpu/stm32f0/Makefile.include | 4 ++-- cpu/stm32f1/Makefile | 4 ++-- cpu/stm32f1/Makefile.include | 4 ++-- cpu/stm32f3/Makefile | 2 +- cpu/stm32f3/Makefile.include | 4 ++-- cpu/stm32f4/Makefile | 2 +- cpu/stm32f4/Makefile.include | 4 ++-- cpu/stm32l1/Makefile | 4 ++-- cpu/stm32l1/Makefile.include | 4 ++-- 26 files changed, 45 insertions(+), 49 deletions(-) diff --git a/cpu/cc2538/Makefile b/cpu/cc2538/Makefile index becbb4e92a..67506e130a 100644 --- a/cpu/cc2538/Makefile +++ b/cpu/cc2538/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # Add a list of subdirectories, that should also be built: -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/cc2538/Makefile.include b/cpu/cc2538/Makefile.include index a154f95094..507f47d21b 100644 --- a/cpu/cc2538/Makefile.include +++ b/cpu/cc2538/Makefile.include @@ -1,4 +1,3 @@ -# select CPU -export CORTEX := cortex-m3 +export CPU_ARCH := cortex-m3 -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/k60/Makefile b/cpu/k60/Makefile index ae17a35174..a8496360bf 100644 --- a/cpu/k60/Makefile +++ b/cpu/k60/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_M4_COMMON) devio $(KINETIS_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common devio $(KINETIS_COMMON) include $(RIOTBASE)/Makefile.base diff --git a/cpu/k60/Makefile.include b/cpu/k60/Makefile.include index ceee8cb5dc..6be29670be 100644 --- a/cpu/k60/Makefile.include +++ b/cpu/k60/Makefile.include @@ -1,3 +1,6 @@ +# define the CPU architecture for the k60 +export CPU_ARCH = cortex-m4 + # this CPU implementation is using the explicit core/CPU interface export CFLAGS += -DCOREIF_NG=1 @@ -8,19 +11,16 @@ export USEMODULE += periph export USEMODULE += devio # tell the build system that the CPU depends on the Cortex-M common files -export USEMODULE += cortex-m4_common +export USEMODULE += cortexm_common # tell the build system that the CPU depends on the Kinetis common files export USEMODULE += kinetis_common -# define path to cortex-m common module, which is needed for this CPU -export CORTEX_M4_COMMON = $(RIOTCPU)/cortex-m4_common/ - # define path to kinetis module, which is needed for this CPU export KINETIS_COMMON = $(RIOTCPU)/kinetis_common/ # CPU depends on the cortex-m common module, so include it -include $(CORTEX_M4_COMMON)Makefile.include +include $(RIOTCPU)/cortexm_common/Makefile.include # CPU depends on the kinetis module, so include it include $(KINETIS_COMMON)Makefile.include diff --git a/cpu/kw2x/Makefile b/cpu/kw2x/Makefile index 73e16d02df..12ba41f9cf 100644 --- a/cpu/kw2x/Makefile +++ b/cpu/kw2x/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_M4_COMMON) $(KINETIS_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common $(KINETIS_COMMON) include $(RIOTBASE)/Makefile.base diff --git a/cpu/kw2x/Makefile.include b/cpu/kw2x/Makefile.include index d4b83dfcdc..86beab16de 100644 --- a/cpu/kw2x/Makefile.include +++ b/cpu/kw2x/Makefile.include @@ -5,19 +5,16 @@ export CFLAGS += -DCOREIF_NG=1 export USEMODULE += periph # tell the build system that the CPU depends on the Cortex-M common files -export USEMODULE += cortex-m4_common +export USEMODULE += cortexm_common # tell the build system that the CPU depends on the Kinetis common files export USEMODULE += kinetis_common -# define path to cortex-m common module, which is needed for this CPU -export CORTEX_M4_COMMON = $(RIOTCPU)/cortex-m4_common/ - # define path to kinetis module, which is needed for this CPU export KINETIS_COMMON = $(RIOTCPU)/kinetis_common/ # CPU depends on the cortex-m common module, so include it -include $(CORTEX_M4_COMMON)Makefile.include +include $(RIOTCPU)/cortexm_common/Makefile.include # CPU depends on the kinetis module, so include it include $(KINETIS_COMMON)Makefile.include diff --git a/cpu/lpc1768/Makefile b/cpu/lpc1768/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/lpc1768/Makefile +++ b/cpu/lpc1768/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/lpc1768/Makefile.include b/cpu/lpc1768/Makefile.include index d6e0cfc4d4..f16ada89b8 100644 --- a/cpu/lpc1768/Makefile.include +++ b/cpu/lpc1768/Makefile.include @@ -1,3 +1,3 @@ -export CORTEX = cortex-m3 +export CPU_ARCH = cortex-m3 -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/nrf51822/Makefile b/cpu/nrf51822/Makefile index 4878e72a65..0dcb89e234 100644 --- a/cpu/nrf51822/Makefile +++ b/cpu/nrf51822/Makefile @@ -2,7 +2,7 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common # build one of the radio drivers, if enabled ifneq (,$(filter radio_nrfmin,$(USEMODULE))) diff --git a/cpu/nrf51822/Makefile.include b/cpu/nrf51822/Makefile.include index 19dc639308..04c2fd5dd4 100644 --- a/cpu/nrf51822/Makefile.include +++ b/cpu/nrf51822/Makefile.include @@ -1,3 +1,3 @@ -export CORTEX = cortex-m0 +export CPU_ARCH = cortex-m0 -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/sam3x8e/Makefile b/cpu/sam3x8e/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/sam3x8e/Makefile +++ b/cpu/sam3x8e/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/sam3x8e/Makefile.include b/cpu/sam3x8e/Makefile.include index d6e0cfc4d4..f16ada89b8 100644 --- a/cpu/sam3x8e/Makefile.include +++ b/cpu/sam3x8e/Makefile.include @@ -1,3 +1,3 @@ -export CORTEX = cortex-m3 +export CPU_ARCH = cortex-m3 -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/samd21/Makefile b/cpu/samd21/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/samd21/Makefile +++ b/cpu/samd21/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/samd21/Makefile.include b/cpu/samd21/Makefile.include index 6125983322..ab5f80f11d 100644 --- a/cpu/samd21/Makefile.include +++ b/cpu/samd21/Makefile.include @@ -1,9 +1,9 @@ -export CORTEX = cortex-m0 +export CPU_ARCH = cortex-m0plus # this CPU implementation doesn't use CMSIS initialisation export CFLAGS += -DDONT_USE_CMSIS_INIT -# +# use the hwtimer compatibility layer USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/saml21/Makefile b/cpu/saml21/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/saml21/Makefile +++ b/cpu/saml21/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/saml21/Makefile.include b/cpu/saml21/Makefile.include index da874ab324..389ec9f25b 100644 --- a/cpu/saml21/Makefile.include +++ b/cpu/saml21/Makefile.include @@ -1,4 +1,4 @@ -export CORTEX = cortex-m0 +export CPU_ARCH = cortex-m0plus # this CPU implementation doesn't use CMSIS initialisation export CFLAGS += -DDONT_USE_CMSIS_INIT @@ -6,4 +6,4 @@ export CFLAGS += -DDONT_USE_CMSIS_INIT # use the hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/stm32f0/Makefile b/cpu/stm32f0/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/stm32f0/Makefile +++ b/cpu/stm32f0/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f0/Makefile.include b/cpu/stm32f0/Makefile.include index 86fe9f109f..da01dcdf4f 100644 --- a/cpu/stm32f0/Makefile.include +++ b/cpu/stm32f0/Makefile.include @@ -1,6 +1,6 @@ -export CORTEX = cortex-m0 +export CPU_ARCH = cortex-m0 # use hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/stm32f1/Makefile b/cpu/stm32f1/Makefile index e9a93aba72..7fc216f1ab 100644 --- a/cpu/stm32f1/Makefile +++ b/cpu/stm32f1/Makefile @@ -1,7 +1,7 @@ # define the module that is build -MODULE =cpu +MODULE = cpu # add a list of subdirectories, that should also be build -DIRS += periph $(CORTEX_COMMON) +DIRS += periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f1/Makefile.include b/cpu/stm32f1/Makefile.include index 83df97d3f3..99de28dcc7 100644 --- a/cpu/stm32f1/Makefile.include +++ b/cpu/stm32f1/Makefile.include @@ -1,6 +1,6 @@ -export CORTEX = cortex-m3 +export CPU_ARCH = cortex-m3 # use hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/stm32f3/Makefile b/cpu/stm32f3/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/stm32f3/Makefile +++ b/cpu/stm32f3/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f3/Makefile.include b/cpu/stm32f3/Makefile.include index fb24d08ef1..ed4584a485 100644 --- a/cpu/stm32f3/Makefile.include +++ b/cpu/stm32f3/Makefile.include @@ -1,6 +1,6 @@ -export CORTEX = cortex-m4 +export CPU_ARCH = cortex-m4f # use hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/stm32f4/Makefile b/cpu/stm32f4/Makefile index 55e50d2099..21f0d18719 100644 --- a/cpu/stm32f4/Makefile +++ b/cpu/stm32f4/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(CORTEX_COMMON) +DIRS = periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32f4/Makefile.include b/cpu/stm32f4/Makefile.include index fb24d08ef1..ed4584a485 100644 --- a/cpu/stm32f4/Makefile.include +++ b/cpu/stm32f4/Makefile.include @@ -1,6 +1,6 @@ -export CORTEX = cortex-m4 +export CPU_ARCH = cortex-m4f # use hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/stm32l1/Makefile b/cpu/stm32l1/Makefile index e9a93aba72..7fc216f1ab 100644 --- a/cpu/stm32l1/Makefile +++ b/cpu/stm32l1/Makefile @@ -1,7 +1,7 @@ # define the module that is build -MODULE =cpu +MODULE = cpu # add a list of subdirectories, that should also be build -DIRS += periph $(CORTEX_COMMON) +DIRS += periph $(RIOTCPU)/cortexm_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/stm32l1/Makefile.include b/cpu/stm32l1/Makefile.include index 83df97d3f3..99de28dcc7 100644 --- a/cpu/stm32l1/Makefile.include +++ b/cpu/stm32l1/Makefile.include @@ -1,6 +1,6 @@ -export CORTEX = cortex-m3 +export CPU_ARCH = cortex-m3 # use hwtimer compatibility module USEMODULE += hwtimer_compat -include $(RIOTCPU)/Makefile.include.cortex_common +include $(RIOTCPU)/Makefile.include.cortexm_common From 38f4fc7027fabf135a922c979f5ae4f898cc30ff Mon Sep 17 00:00:00 2001 From: haukepetersen Date: Tue, 26 May 2015 21:03:07 +0200 Subject: [PATCH 5/8] cpu/samd21: moved -O0 from board to cpu --- boards/samr21-xpro/Makefile.include | 3 --- cpu/samd21/Makefile.include | 3 +++ 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/boards/samr21-xpro/Makefile.include b/boards/samr21-xpro/Makefile.include index 9f592f1722..1cd31bd072 100644 --- a/boards/samr21-xpro/Makefile.include +++ b/boards/samr21-xpro/Makefile.include @@ -2,9 +2,6 @@ export CPU = samd21 export CPU_MODEL = samr21g18a -# TODO: remove once the CPU implementation is stable with -Os -CFLAGS_OPT = -O0 - # set default port depending on operating system PORT_LINUX ?= /dev/ttyACM0 diff --git a/cpu/samd21/Makefile.include b/cpu/samd21/Makefile.include index ab5f80f11d..46dcfe3720 100644 --- a/cpu/samd21/Makefile.include +++ b/cpu/samd21/Makefile.include @@ -6,4 +6,7 @@ export CFLAGS += -DDONT_USE_CMSIS_INIT # use the hwtimer compatibility layer USEMODULE += hwtimer_compat +# TODO: remove once the CPU implementation is stable with -Os +CFLAGS_OPT = -O0 + include $(RIOTCPU)/Makefile.include.cortexm_common From 26b9e9acea36e053f977e42e03a6bd752f2f8e3f Mon Sep 17 00:00:00 2001 From: Hauke Petersen Date: Wed, 27 May 2015 16:27:04 +0200 Subject: [PATCH 6/8] doc: adapted doxygen excludes --- doc/doxygen/riot.doxyfile | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/doc/doxygen/riot.doxyfile b/doc/doxygen/riot.doxyfile index 33d635c828..bf0089dfaa 100644 --- a/doc/doxygen/riot.doxyfile +++ b/doc/doxygen/riot.doxyfile @@ -817,9 +817,7 @@ EXCLUDE_PATTERNS = */board/*/tools/* \ */cpu/*/include/pio/* \ */cpu/*/include/atmel/* \ */cpu/lpc*/include/core_cm*.h \ - */cpu/cortex-*_common/include/core_cm*.h \ - */cpu/cortex-*_common/include/core_cmInstr.h \ - */cpu/cortex-*_common/include/core_cmFunc.h \ + */cpu/cortexm_common/include/core_cm*.h \ */cpu/stm32f*/include/stm32f* \ */drivers/nrf24l01p/include/nrf24l01p_settings.h \ */cpu/nrf51822/include/nrf51.h \ From 02fe7c5d76e209cf751047f1238f1cf0ec6d49f0 Mon Sep 17 00:00:00 2001 From: Joakim Gebart Date: Wed, 27 May 2015 22:38:38 +0200 Subject: [PATCH 7/8] boards: Makefile.include.gnu: Use GDBPREFIX for GDB GDB can be built as multitarget which can debug multiple architectures and is often installed without a target prefix. --- boards/Makefile.include.gnu | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/boards/Makefile.include.gnu b/boards/Makefile.include.gnu index f514bf1d70..f571741121 100644 --- a/boards/Makefile.include.gnu +++ b/boards/Makefile.include.gnu @@ -1,3 +1,4 @@ +export GDBPREFIX ?= $(PREFIX) export CC = $(PREFIX)gcc export CXX = $(PREFIX)g++ export AR = $(PREFIX)ar @@ -5,4 +6,4 @@ export AS = $(PREFIX)as export LINK = $(PREFIX)gcc export SIZE = $(PREFIX)size export OBJCOPY = $(PREFIX)objcopy -export DBG = $(PREFIX)gdb +export DBG = $(GDBPREFIX)gdb From 42f48b731f14d31596355189ded1ffa969a9c028 Mon Sep 17 00:00:00 2001 From: Joakim Gebart Date: Wed, 27 May 2015 22:42:38 +0200 Subject: [PATCH 8/8] boards: Let env override PREFIX, set TARGET_TRIPLE --- boards/Makefile.include.cortexm_common | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/boards/Makefile.include.cortexm_common b/boards/Makefile.include.cortexm_common index 3c8b492e7e..9273b7e198 100644 --- a/boards/Makefile.include.cortexm_common +++ b/boards/Makefile.include.cortexm_common @@ -1,5 +1,10 @@ +# Target triple for the build. Use arm-none-eabi if you are unsure. +export TARGET_TRIPLE ?= arm-none-eabi + +# Toolchain prefix, defaults to target triple followed by a dash, you will most likely not need to touch this. +export PREFIX ?= $(if $(TARGET_TRIPLE),$(TARGET_TRIPLE)-) + # we build all cortex boards with the GNU toolchain -export PREFIX = arm-none-eabi- include $(RIOTBOARD)/Makefile.include.gnu # define build specific options