aboutsummaryrefslogtreecommitdiffstats
path: root/os
diff options
context:
space:
mode:
Diffstat (limited to 'os')
-rw-r--r--os/hal/ports/STM32/RTCv2/rtc_lld.c1
-rw-r--r--os/nil/include/nil.h13
-rw-r--r--os/nil/ports/ARMCMx/compilers/GCC/mk/port_stm32f30x.mk15
-rw-r--r--os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v6m.s3
-rw-r--r--os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v7m.s120
-rw-r--r--os/nil/ports/ARMCMx/nilcore_v6m.c15
-rw-r--r--os/nil/ports/ARMCMx/nilcore_v6m.h22
-rw-r--r--os/nil/ports/ARMCMx/nilcore_v7m.c174
-rw-r--r--os/nil/ports/ARMCMx/nilcore_v7m.h563
-rw-r--r--os/nil/src/nil.c14
-rw-r--r--os/rt/ports/ARMCMx/chcore_timer.h2
-rw-r--r--os/rt/ports/ARMCMx/chcore_v6m.c2
-rw-r--r--os/rt/ports/ARMCMx/chcore_v6m.h10
-rw-r--r--os/rt/ports/ARMCMx/chcore_v7m.c2
-rw-r--r--os/rt/ports/ARMCMx/chcore_v7m.h2
-rw-r--r--os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v6m.s3
-rw-r--r--os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s3
-rw-r--r--os/rt/ports/ARMCMx/compilers/GCC/chtypes.h2
18 files changed, 922 insertions, 44 deletions
diff --git a/os/hal/ports/STM32/RTCv2/rtc_lld.c b/os/hal/ports/STM32/RTCv2/rtc_lld.c
index 17ae46ccf..d30401422 100644
--- a/os/hal/ports/STM32/RTCv2/rtc_lld.c
+++ b/os/hal/ports/STM32/RTCv2/rtc_lld.c
@@ -26,7 +26,6 @@
* @{
*/
-#include "ch.h"
#include "hal.h"
#if HAL_USE_RTC || defined(__DOXYGEN__)
diff --git a/os/nil/include/nil.h b/os/nil/include/nil.h
index ea6839d6b..da79370d7 100644
--- a/os/nil/include/nil.h
+++ b/os/nil/include/nil.h
@@ -550,6 +550,17 @@ typedef struct {
#define chSysUnlockFromISR() port_unlock_from_isr()
/**
+ * @brief Evaluates if a reschedule is required.
+ *
+ * @retval true if there is a thread that must go in running state
+ * immediately.
+ * @retval false if preemption is not required.
+ *
+ * @iclass
+ */
+#define chSchIsRescRequiredI() ((bool)(nil.current != nil.next))
+
+/**
* @brief Delays the invoking thread for the specified number of seconds.
* @note The specified time is rounded up to a value allowed by the real
* system clock.
@@ -716,8 +727,8 @@ extern "C" {
syssts_t chSysGetStatusAndLockX(void);
void chSysRestoreStatusX(syssts_t sts);
thread_reference_t chSchReadyI(thread_reference_t trp, msg_t msg);
- msg_t chSchGoSleepTimeoutS(tstate_t newstate, systime_t timeout);
void chSchRescheduleS(void);
+ msg_t chSchGoSleepTimeoutS(tstate_t newstate, systime_t timeout);
msg_t chThdSuspendTimeoutS(thread_reference_t *trp, systime_t timeout);
void chThdResumeI(thread_reference_t *trp, msg_t msg);
void chThdSleep(systime_t time);
diff --git a/os/nil/ports/ARMCMx/compilers/GCC/mk/port_stm32f30x.mk b/os/nil/ports/ARMCMx/compilers/GCC/mk/port_stm32f30x.mk
new file mode 100644
index 000000000..18df7e0a9
--- /dev/null
+++ b/os/nil/ports/ARMCMx/compilers/GCC/mk/port_stm32f30x.mk
@@ -0,0 +1,15 @@
+# List of the ChibiOS/NIL Cortex-M4 STM32F30x port files.
+PORTSRC = $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/crt0.c \
+ $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/vectors.c \
+ ${CHIBIOS}/os/nil/ports/ARMCMx/nilcore.c \
+ ${CHIBIOS}/os/nil/ports/ARMCMx/nilcore_v7m.c
+
+PORTASM = $(CHIBIOS)/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v7m.s
+
+PORTINC = ${CHIBIOS}/os/ext/CMSIS/include \
+ ${CHIBIOS}/os/ext/CMSIS/ST \
+ ${CHIBIOS}/os/common/ports/ARMCMx/devices/STM32F30x \
+ ${CHIBIOS}/os/nil/ports/ARMCMx \
+ ${CHIBIOS}/os/nil/ports/ARMCMx/compilers/GCC
+
+PORTLD = ${CHIBIOS}/os/common/ports/ARMCMx/compilers/GCC/ld
diff --git a/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v6m.s b/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v6m.s
index 8112d9802..1c1a39067 100644
--- a/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v6m.s
+++ b/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v6m.s
@@ -18,7 +18,7 @@
*/
/**
- * @file ARMCMx/GCC/nilcoreasm_v6m.s
+ * @file nilcoreasm_v6m.s
* @brief ARMv6-M architecture port low level code.
*
* @addtogroup ARMCMx_CORE
@@ -39,7 +39,6 @@
#if !defined(__DOXYGEN__)
-
.set CONTEXT_OFFSET, 0
.set SCB_ICSR, 0xE000ED04
.set ICSR_PENDSVSET, 0x10000000
diff --git a/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v7m.s b/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v7m.s
new file mode 100644
index 000000000..97d15e5d8
--- /dev/null
+++ b/os/nil/ports/ARMCMx/compilers/GCC/nilcoreasm_v7m.s
@@ -0,0 +1,120 @@
+/*
+ ChibiOS/NIL - Copyright (C) 2012,2013 Giovanni Di Sirio.
+
+ This file is part of ChibiOS/NIL.
+
+ ChibiOS/NIL is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 3 of the License, or
+ (at your option) any later version.
+
+ ChibiOS/NIL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/**
+ * @file nilcoreasm_v7m.s
+ * @brief ARMv7-M architecture port low level code.
+ *
+ * @addtogroup ARMCMx_CORE
+ * @{
+ */
+
+#define _FROM_ASM_
+#include "nilconf.h"
+#include "nilcore.h"
+
+#if !defined(FALSE) || defined(__DOXYGEN__)
+#define FALSE 0
+#endif
+
+#if !defined(TRUE) || defined(__DOXYGEN__)
+#define TRUE 1
+#endif
+
+#if !defined(__DOXYGEN__)
+
+ .set CONTEXT_OFFSET, 0
+ .set SCB_ICSR, 0xE000ED04
+ .set ICSR_PENDSVSET, 0x10000000
+
+ .syntax unified
+ .cpu cortex-m4
+#if CORTEX_USE_FPU
+ .fpu fpv4-sp-d16
+#else
+ .fpu softvfp
+#endif
+
+ .thumb
+ .text
+
+/*--------------------------------------------------------------------------*
+ * Performs a context switch between two threads.
+ *--------------------------------------------------------------------------*/
+ .thumb_func
+ .globl _port_switch
+_port_switch:
+ push {r4, r5, r6, r7, r8, r9, r10, r11, lr}
+#if CORTEX_USE_FPU
+ vpush {s16-s31}
+#endif
+ str sp, [r1, #CONTEXT_OFFSET]
+ ldr sp, [r0, #CONTEXT_OFFSET]
+#if CORTEX_USE_FPU
+ vpop {s16-s31}
+#endif
+ pop {r4, r5, r6, r7, r8, r9, r10, r11, pc}
+
+/*--------------------------------------------------------------------------*
+ * Start a thread by invoking its work function.
+ *
+ * Threads execution starts here, the code leaves the system critical zone
+ * and then jumps into the thread function passed in register R4. The
+ * register R5 contains the thread parameter. The function chThdExit() is
+ * called on thread function return.
+ *--------------------------------------------------------------------------*/
+ .thumb_func
+ .globl _port_thread_start
+_port_thread_start:
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ movs r3, #0
+ msr BASEPRI, r3
+#else /* CORTEX_SIMPLIFIED_PRIORITY */
+ cpsie i
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+ mov r0, r5
+ blx r4
+ mov r3, #0
+ bl chSysHalt
+
+/*--------------------------------------------------------------------------*
+ * Post-IRQ switch code.
+ *
+ * Exception handlers return here for context switching.
+ *--------------------------------------------------------------------------*/
+ .thumb_func
+ .globl _port_switch_from_isr
+_port_switch_from_isr:
+ bl chSchRescheduleS
+ .globl _port_exit_from_isr
+_port_exit_from_isr:
+#if CORTEX_SIMPLIFIED_PRIORITY
+ movw r3, #:lower16:SCB_ICSR
+ movt r3, #:upper16:SCB_ICSR
+ mov r2, ICSR_PENDSVSET
+ str r2, [r3, #0]
+ cpsie i
+#else /* !CORTEX_SIMPLIFIED_PRIORITY */
+ svc #0
+#endif /* !CORTEX_SIMPLIFIED_PRIORITY */
+.L1: b .L1
+
+#endif /* !defined(__DOXYGEN__) */
+
+/** @} */
diff --git a/os/nil/ports/ARMCMx/nilcore_v6m.c b/os/nil/ports/ARMCMx/nilcore_v6m.c
index 19f1b9111..158e7d63d 100644
--- a/os/nil/ports/ARMCMx/nilcore_v6m.c
+++ b/os/nil/ports/ARMCMx/nilcore_v6m.c
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/nilcore_v6m.c
+ * @file nilcore_v6m.c
* @brief ARMv6-M architecture port code.
*
* @addtogroup ARMCMx_V6M_CORE
@@ -124,8 +124,17 @@ void _port_irq_epilogue(regarm_t lr) {
/* Setting up a fake XPSR register value.*/
ctxp->xpsr = (regarm_t)0x01000000;
- /* The context switch is handled outside the ISR context..*/
- ctxp->pc = (regarm_t)_port_switch_from_isr;
+ /* The exit sequence is different depending on if a preemption is
+ required or not.*/
+ if (chSchIsRescRequiredI()) {
+ /* Preemption is required we need to enforce a context switch.*/
+ ctxp->pc = (regarm_t)_port_switch_from_isr;
+ }
+ else {
+ /* Preemption not required, we just need to exit the exception
+ atomically.*/
+ ctxp->pc = (regarm_t)_port_exit_from_isr;
+ }
/* Note, returning without unlocking is intentional, this is done in
order to keep the rest of the context switch atomic.*/
diff --git a/os/nil/ports/ARMCMx/nilcore_v6m.h b/os/nil/ports/ARMCMx/nilcore_v6m.h
index 3e3a7f14c..60a2549a2 100644
--- a/os/nil/ports/ARMCMx/nilcore_v6m.h
+++ b/os/nil/ports/ARMCMx/nilcore_v6m.h
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_v6m.h
+ * @file chcore_v6m.h
* @brief ARMv6-M architecture port macros and structures.
*
* @addtogroup ARMCMx_V6M_CORE
@@ -183,16 +183,6 @@ struct port_intctx {
#endif /* !defined(__DOXYGEN__) */
-/**
- * @brief Platform dependent part of the @p thread_t structure.
- * @details In this port the structure just holds a pointer to the
- * @p port_intctx structure representing the stack pointer
- * at context switch time.
- */
-struct context {
- struct port_intctx *r13;
-};
-
/*===========================================================================*/
/* Module macros. */
/*===========================================================================*/
@@ -259,7 +249,7 @@ struct context {
* @param[in] ntp the thread to be switched in
* @param[in] otp the thread to be switched out
*/
-#if !CH_DBG_ENABLE_STACK_CHECK || defined(__DOXYGEN__)
+#if !NIL_CFG_ENABLE_STACK_CHECK || defined(__DOXYGEN__)
#define port_switch(ntp, otp) _port_switch(ntp, otp)
#else
#define port_switch(ntp, otp) { \
@@ -270,10 +260,6 @@ struct context {
}
#endif
-#if NIL_CFG_TIMEDELTA > 0
-#include "nilcore_timer.h"
-#endif
-
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
@@ -290,6 +276,10 @@ extern "C" {
}
#endif
+#if NIL_CFG_TIMEDELTA > 0
+#include "nilcore_timer.h"
+#endif
+
/*===========================================================================*/
/* Module inline functions. */
/*===========================================================================*/
diff --git a/os/nil/ports/ARMCMx/nilcore_v7m.c b/os/nil/ports/ARMCMx/nilcore_v7m.c
new file mode 100644
index 000000000..ac059e38d
--- /dev/null
+++ b/os/nil/ports/ARMCMx/nilcore_v7m.c
@@ -0,0 +1,174 @@
+/*
+ ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
+ 2011,2012,2013 Giovanni Di Sirio.
+
+ This file is part of ChibiOS/RT.
+
+ ChibiOS/RT is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 3 of the License, or
+ (at your option) any later version.
+
+ ChibiOS/RT is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/**
+ * @file nilcore_v7m.c
+ * @brief ARMv7-M architecture port code.
+ *
+ * @addtogroup ARMCMx_V7M_CORE
+ * @{
+ */
+
+#include "nil.h"
+
+/*===========================================================================*/
+/* Module local definitions. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Module exported variables. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Module local types. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Module local variables. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Module local functions. */
+/*===========================================================================*/
+
+/*===========================================================================*/
+/* Module interrupt handlers. */
+/*===========================================================================*/
+
+#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+/**
+ * @brief SVC vector.
+ * @details The SVC vector is used for exception mode re-entering after a
+ * context switch.
+ * @note The PendSV vector is only used in advanced kernel mode.
+ */
+void SVC_Handler(void) {
+
+ /* The port_extctx structure is pointed by the PSP register.*/
+ struct port_extctx *ctxp = (struct port_extctx *)__get_PSP();
+
+ /* Discarding the current exception context and positioning the stack to
+ point to the real one.*/
+ ctxp++;
+
+#if CORTEX_USE_FPU
+ /* Restoring the special register FPCCR.*/
+ FPU->FPCCR = (uint32_t)ctxp->fpccr;
+ FPU->FPCAR = FPU->FPCAR + sizeof (struct port_extctx);
+#endif
+
+ /* Writing back the modified PSP value.*/
+ __set_PSP((uint32_t)ctxp);
+
+ /* Restoring the normal interrupts status.*/
+ port_unlock_from_isr();
+}
+#endif /* !CORTEX_SIMPLIFIED_PRIORITY */
+
+#if CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+/**
+ * @brief PendSV vector.
+ * @details The PendSV vector is used for exception mode re-entering after a
+ * context switch.
+ * @note The PendSV vector is only used in compact kernel mode.
+ */
+void PendSV_Handler(void) {
+
+ /* The port_extctx structure is pointed by the PSP register.*/
+ struct port_extctx *ctxp = (struct port_extctx *)__get_PSP();
+
+ /* Discarding the current exception context and positioning the stack to
+ point to the real one.*/
+ ctxp++;
+
+#if CORTEX_USE_FPU
+ /* Restoring the special register FPCCR.*/
+ FPU->FPCCR = (uint32_t)ctxp->fpccr;
+ FPU->FPCAR = FPU->FPCAR + sizeof (struct port_extctx);
+#endif
+
+ /* Writing back the modified PSP value.*/
+ __set_PSP((uint32_t)ctxp);
+}
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+
+/*===========================================================================*/
+/* Module exported functions. */
+/*===========================================================================*/
+
+/**
+ * @brief Exception exit redirection to _port_switch_from_isr().
+ */
+void _port_irq_epilogue(void) {
+
+ port_lock_from_isr();
+ if ((SCB->ICSR & SCB_ICSR_RETTOBASE_Msk) != 0) {
+
+ /* The port_extctx structure is pointed by the PSP register.*/
+ struct port_extctx *ctxp = (struct port_extctx *)__get_PSP();
+
+ /* Adding an artificial exception return context, there is no need to
+ populate it fully.*/
+ ctxp--;
+
+ /* Writing back the modified PSP value.*/
+ __set_PSP((uint32_t)ctxp);
+
+ /* Setting up a fake XPSR register value.*/
+ ctxp->xpsr = (regarm_t)0x01000000;
+
+ /* The exit sequence is different depending on if a preemption is
+ required or not.*/
+ if (chSchIsRescRequiredI()) {
+ /* Preemption is required we need to enforce a context switch.*/
+ ctxp->pc = (regarm_t)_port_switch_from_isr;
+#if CORTEX_USE_FPU
+ /* Enforcing a lazy FPU state save by accessing the FPCSR register.*/
+ (void) __get_FPSCR();
+#endif
+ }
+ else {
+ /* Preemption not required, we just need to exit the exception
+ atomically.*/
+ ctxp->pc = (regarm_t)_port_exit_from_isr;
+ }
+
+#if CORTEX_USE_FPU
+ {
+ uint32_t fpccr;
+
+ /* Saving the special register SCB_FPCCR into the reserved offset of
+ the Cortex-M4 exception frame.*/
+ (ctxp + 1)->fpccr = (regarm_t)(fpccr = FPU->FPCCR);
+
+ /* Now the FPCCR is modified in order to not restore the FPU status
+ from the artificial return context.*/
+ FPU->FPCCR = fpccr | FPU_FPCCR_LSPACT_Msk;
+ }
+#endif
+
+ /* Note, returning without unlocking is intentional, this is done in
+ order to keep the rest of the context switch atomic.*/
+ return;
+ }
+ port_unlock_from_isr();
+}
+
+/** @} */
diff --git a/os/nil/ports/ARMCMx/nilcore_v7m.h b/os/nil/ports/ARMCMx/nilcore_v7m.h
new file mode 100644
index 000000000..4cbcc6e28
--- /dev/null
+++ b/os/nil/ports/ARMCMx/nilcore_v7m.h
@@ -0,0 +1,563 @@
+/*
+ ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
+ 2011,2012,2013 Giovanni Di Sirio.
+
+ This file is part of ChibiOS/RT.
+
+ ChibiOS/RT is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 3 of the License, or
+ (at your option) any later version.
+
+ ChibiOS/RT is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/**
+ * @file chcore_v7m.h
+ * @brief ARMv7-M architecture port macros and structures.
+ *
+ * @addtogroup ARMCMx_V7M_CORE
+ * @{
+ */
+
+#ifndef _CHCORE_V7M_H_
+#define _CHCORE_V7M_H_
+
+/*===========================================================================*/
+/* Module constants. */
+/*===========================================================================*/
+
+/**
+ * @name Architecture and Compiler
+ * @{
+ */
+#if (CORTEX_MODEL == CORTEX_M3) || defined(__DOXYGEN__)
+/**
+ * @brief Macro defining the specific ARM architecture.
+ */
+#define PORT_ARCHITECTURE_ARM_v7M
+
+/**
+ * @brief Name of the implemented architecture.
+ */
+#define PORT_ARCHITECTURE_NAME "ARMv7-M"
+
+/**
+ * @brief Name of the architecture variant.
+ */
+#define PORT_CORE_VARIANT_NAME "Cortex-M3"
+
+#elif (CORTEX_MODEL == CORTEX_M4)
+#define PORT_ARCHITECTURE_ARM_v7ME
+#define PORT_ARCHITECTURE_NAME "ARMv7-ME"
+#if CORTEX_USE_FPU
+#define PORT_CORE_VARIANT_NAME "Cortex-M4F"
+#else
+#define PORT_CORE_VARIANT_NAME "Cortex-M4"
+#endif
+#endif
+
+/**
+ * @brief Port-specific information string.
+ */
+#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+#define PORT_INFO "Advanced kernel mode"
+#else
+#define PORT_INFO "Compact kernel mode"
+#endif
+/** @} */
+
+/**
+ * @brief This port supports a realtime counter.
+ */
+#define PORT_SUPPORTS_RT FALSE //TRUE
+
+/**
+ * @brief Disabled value for BASEPRI register.
+ */
+#define CORTEX_BASEPRI_DISABLED 0
+
+/*===========================================================================*/
+/* Module pre-compile time settings. */
+/*===========================================================================*/
+
+/**
+ * @brief Stack size for the system idle thread.
+ * @details This size depends on the idle thread implementation, usually
+ * the idle thread should take no more space than those reserved
+ * by @p PORT_INT_REQUIRED_STACK.
+ * @note In this port it is set to 16 because the idle thread does have
+ * a stack frame when compiling without optimizations. You may
+ * reduce this value to zero when compiling with optimizations.
+ */
+#if !defined(PORT_IDLE_THREAD_STACK_SIZE) || defined(__DOXYGEN__)
+#define PORT_IDLE_THREAD_STACK_SIZE 16
+#endif
+
+/**
+ * @brief Per-thread stack overhead for interrupts servicing.
+ * @details This constant is used in the calculation of the correct working
+ * area size.
+ * @note In this port this value is conservatively set to 32 because the
+ * function @p chSchDoReschedule() can have a stack frame, especially
+ * with compiler optimizations disabled. The value can be reduced
+ * when compiler optimizations are enabled.
+ */
+#if !defined(PORT_INT_REQUIRED_STACK) || defined(__DOXYGEN__)
+#define PORT_INT_REQUIRED_STACK 32
+#endif
+
+/**
+ * @brief Enables the use of the WFI instruction in the idle thread loop.
+ */
+#if !defined(CORTEX_ENABLE_WFI_IDLE)
+#define CORTEX_ENABLE_WFI_IDLE FALSE
+#endif
+
+/**
+ * @brief FPU support in context switch.
+ * @details Activating this option activates the FPU support in the kernel.
+ */
+#if !defined(CORTEX_USE_FPU)
+#define CORTEX_USE_FPU CORTEX_HAS_FPU
+#elif CORTEX_USE_FPU && !CORTEX_HAS_FPU
+/* This setting requires an FPU presence check in case it is externally
+ redefined.*/
+#error "the selected core does not have an FPU"
+#endif
+
+/**
+ * @brief Simplified priority handling flag.
+ * @details Activating this option makes the Kernel work in compact mode.
+ * In compact mode interrupts are disabled globally instead of
+ * raising the priority mask to some intermediate level.
+ */
+#if !defined(CORTEX_SIMPLIFIED_PRIORITY)
+#define CORTEX_SIMPLIFIED_PRIORITY FALSE
+#endif
+
+/**
+ * @brief SVCALL handler priority.
+ * @note The default SVCALL handler priority is defaulted to
+ * @p CORTEX_MAXIMUM_PRIORITY+1, this reserves the
+ * @p CORTEX_MAXIMUM_PRIORITY priority level as fast interrupts
+ * priority level.
+ */
+#if !defined(CORTEX_PRIORITY_SVCALL)
+#define CORTEX_PRIORITY_SVCALL (CORTEX_MAXIMUM_PRIORITY + 1)
+#elif !CORTEX_IS_VALID_PRIORITY(CORTEX_PRIORITY_SVCALL)
+/* If it is externally redefined then better perform a validity check on it.*/
+#error "invalid priority level specified for CORTEX_PRIORITY_SVCALL"
+#endif
+
+/**
+ * @brief NVIC VTOR initialization expression.
+ */
+#if !defined(CORTEX_VTOR_INIT) || defined(__DOXYGEN__)
+#define CORTEX_VTOR_INIT 0x00000000
+#endif
+
+/**
+ * @brief NVIC PRIGROUP initialization expression.
+ * @details The default assigns all available priority bits as preemption
+ * priority with no sub-priority.
+ */
+#if !defined(CORTEX_PRIGROUP_INIT) || defined(__DOXYGEN__)
+#define CORTEX_PRIGROUP_INIT (7 - CORTEX_PRIORITY_BITS)
+#endif
+
+/*===========================================================================*/
+/* Derived constants and error checks. */
+/*===========================================================================*/
+
+#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+/**
+ * @brief Maximum usable priority for normal ISRs.
+ */
+#define CORTEX_MAX_KERNEL_PRIORITY (CORTEX_PRIORITY_SVCALL + 1)
+
+/**
+ * @brief BASEPRI level within kernel lock.
+ */
+#define CORTEX_BASEPRI_KERNEL \
+ CORTEX_PRIO_MASK(CORTEX_MAX_KERNEL_PRIORITY)
+#else
+
+#define CORTEX_MAX_KERNEL_PRIORITY 0
+#endif
+
+/**
+ * @brief PendSV priority level.
+ * @note This priority is enforced to be equal to
+ * @p CORTEX_MAX_KERNEL_PRIORITY, this handler always have the
+ * highest priority that cannot preempt the kernel.
+ */
+#define CORTEX_PRIORITY_PENDSV CORTEX_MAX_KERNEL_PRIORITY
+
+/*===========================================================================*/
+/* Module data structures and types. */
+/*===========================================================================*/
+
+/* The following code is not processed when the file is included from an
+ asm module.*/
+#if !defined(_FROM_ASM_)
+
+/**
+ * @brief Generic ARM register.
+ */
+typedef void *regarm_t;
+
+/* The documentation of the following declarations is in chconf.h in order
+ to not have duplicated structure names into the documentation.*/
+#if !defined(__DOXYGEN__)
+
+typedef uint64_t stkalign_t;
+
+struct port_extctx {
+ regarm_t r0;
+ regarm_t r1;
+ regarm_t r2;
+ regarm_t r3;
+ regarm_t r12;
+ regarm_t lr_thd;
+ regarm_t pc;
+ regarm_t xpsr;
+#if CORTEX_USE_FPU
+ regarm_t s0;
+ regarm_t s1;
+ regarm_t s2;
+ regarm_t s3;
+ regarm_t s4;
+ regarm_t s5;
+ regarm_t s6;
+ regarm_t s7;
+ regarm_t s8;
+ regarm_t s9;
+ regarm_t s10;
+ regarm_t s11;
+ regarm_t s12;
+ regarm_t s13;
+ regarm_t s14;
+ regarm_t s15;
+ regarm_t fpscr;
+ regarm_t fpccr;
+#endif /* CORTEX_USE_FPU */
+};
+
+struct port_intctx {
+#if CORTEX_USE_FPU
+ regarm_t s16;
+ regarm_t s17;
+ regarm_t s18;
+ regarm_t s19;
+ regarm_t s20;
+ regarm_t s21;
+ regarm_t s22;
+ regarm_t s23;
+ regarm_t s24;
+ regarm_t s25;
+ regarm_t s26;
+ regarm_t s27;
+ regarm_t s28;
+ regarm_t s29;
+ regarm_t s30;
+ regarm_t s31;
+#endif /* CORTEX_USE_FPU */
+ regarm_t r4;
+ regarm_t r5;
+ regarm_t r6;
+ regarm_t r7;
+ regarm_t r8;
+ regarm_t r9;
+ regarm_t r10;
+ regarm_t r11;
+ regarm_t lr;
+};
+
+#endif /* !defined(__DOXYGEN__) */
+
+/*===========================================================================*/
+/* Module macros. */
+/*===========================================================================*/
+
+/**
+ * @brief Platform dependent part of the @p chThdCreateI() API.
+ * @details This code usually setup the context switching frame represented
+ * by an @p port_intctx structure.
+ */
+#define PORT_SETUP_CONTEXT(tp, workspace, wsize, pf, arg) { \
+ (tp)->ctxp = (struct port_intctx *)((uint8_t *)workspace + \
+ (size_t)wsize - \
+ sizeof(struct port_intctx)); \
+ (tp)->ctxp->r4 = (regarm_t)(pf); \
+ (tp)->ctxp->r5 = (regarm_t)(arg); \
+ (tp)->ctxp->lr = (regarm_t)(_port_thread_start); \
+}
+
+/**
+ * @brief Computes the thread working area global size.
+ * @note There is no need to perform alignments in this macro.
+ */
+#define PORT_WA_SIZE(n) (sizeof(struct port_intctx) + \
+ sizeof(struct port_extctx) + \
+ (n) + (PORT_INT_REQUIRED_STACK))
+
+/**
+ * @brief IRQ prologue code.
+ * @details This macro must be inserted at the start of all IRQ handlers
+ * enabled to invoke system APIs.
+ */
+#define PORT_IRQ_PROLOGUE()
+
+/**
+ * @brief IRQ epilogue code.
+ * @details This macro must be inserted at the end of all IRQ handlers
+ * enabled to invoke system APIs.
+ */
+#define PORT_IRQ_EPILOGUE() _port_irq_epilogue()
+
+/**
+ * @brief IRQ handler function declaration.
+ * @note @p id can be a function name or a vector number depending on the
+ * port implementation.
+ */
+#define PORT_IRQ_HANDLER(id) void id(void)
+
+/**
+ * @brief Fast IRQ handler function declaration.
+ * @note @p id can be a function name or a vector number depending on the
+ * port implementation.
+ */
+#define PORT_FAST_IRQ_HANDLER(id) void id(void)
+
+/**
+ * @brief Performs a context switch between two threads.
+ * @details This is the most critical code in any port, this function
+ * is responsible for the context switch between 2 threads.
+ * @note The implementation of this code affects <b>directly</b> the context
+ * switch performance so optimize here as much as you can.
+ *
+ * @param[in] ntp the thread to be switched in
+ * @param[in] otp the thread to be switched out
+ */
+#if !NIL_CFG_ENABLE_STACK_CHECK || defined(__DOXYGEN__)
+#define port_switch(ntp, otp) _port_switch(ntp, otp)
+#else
+#define port_switch(ntp, otp) { \
+ struct port_intctx *r13 = (struct port_intctx *)__get_PSP(); \
+ if ((stkalign_t *)(r13 - 1) < otp->p_stklimit) \
+ chSysHalt("stack overflow"); \
+ _port_switch(ntp, otp); \
+}
+#endif
+
+/*===========================================================================*/
+/* External declarations. */
+/*===========================================================================*/
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+ void _port_irq_epilogue(void);
+ void _port_switch(thread_t *ntp, thread_t *otp);
+ void _port_thread_start(void);
+ void _port_switch_from_isr(void);
+ void _port_exit_from_isr(void);
+#ifdef __cplusplus
+}
+#endif
+
+#if NIL_CFG_TIMEDELTA > 0
+#include "nilcore_timer.h"
+#endif
+
+/*===========================================================================*/
+/* Module inline functions. */
+/*===========================================================================*/
+
+/**
+ * @brief Port-related initialization code.
+ */
+static inline void port_init(void) {
+
+ /* Initialization of the vector table and priority related settings.*/
+ SCB->VTOR = CORTEX_VTOR_INIT;
+
+ /* Initializing priority grouping.*/
+ NVIC_SetPriorityGrouping(CORTEX_PRIGROUP_INIT);
+
+ /* DWT cycle counter enable.*/
+ CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
+ DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
+
+ /* Initialization of the system vectors used by the port.*/
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ NVIC_SetPriority(SVCall_IRQn, CORTEX_PRIORITY_SVCALL);
+#endif
+ NVIC_SetPriority(PendSV_IRQn, CORTEX_PRIORITY_PENDSV);
+}
+
+/**
+ * @brief Returns a word encoding the current interrupts status.
+ *
+ * @return The interrupts status.
+ */
+static inline syssts_t port_get_irq_status(void) {
+ register uint32_t sts;
+
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ sts = __get_BASEPRI();
+#else /* CORTEX_SIMPLIFIED_PRIORITY */
+ sts = __get_PRIMASK();
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+ return sts;
+}
+
+/**
+ * @brief Checks the interrupt status.
+ *
+ * @param[in] sts the interrupt status word
+ *
+ * @return The interrupt status.
+ * @retvel false the word specified a disabled interrupts status.
+ * @retvel true the word specified an enabled interrupts status.
+ */
+static inline bool port_irq_enabled(syssts_t sts) {
+
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ return sts == CORTEX_BASEPRI_DISABLED;
+#else /* CORTEX_SIMPLIFIED_PRIORITY */
+ return (sts & 1) == 0;
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+}
+
+/**
+ * @brief Determines the current execution context.
+ *
+ * @return The execution context.
+ * @retval false not running in ISR mode.
+ * @retval true running in ISR mode.
+ */
+static inline bool port_is_isr_context(void) {
+
+ return (bool)((__get_IPSR() & 0x1FF) != 0);
+}
+
+/**
+ * @brief Kernel-lock action.
+ * @details In this port this function raises the base priority to kernel
+ * level.
+ */
+static inline void port_lock(void) {
+
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ __set_BASEPRI(CORTEX_BASEPRI_KERNEL);
+#else /* CORTEX_SIMPLIFIED_PRIORITY */
+ __disable_irq();
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+}
+
+/**
+ * @brief Kernel-unlock action.
+ * @details In this port this function lowers the base priority to user
+ * level.
+ */
+static inline void port_unlock(void) {
+
+#if !CORTEX_SIMPLIFIED_PRIORITY
+ __set_BASEPRI(CORTEX_BASEPRI_DISABLED);
+#else /* CORTEX_SIMPLIFIED_PRIORITY */
+ __enable_irq();
+#endif /* CORTEX_SIMPLIFIED_PRIORITY */
+}
+
+/**
+ * @brief Kernel-lock action from an interrupt handler.
+ * @details In this port this function raises the base priority to kernel
+ * level.
+ * @note Same as @p port_lock() in this port.
+ */
+static inline void port_lock_from_isr(void) {
+
+ port_lock();
+}
+
+/**
+ * @brief Kernel-unlock action from an interrupt handler.
+ * @details In this port this function lowers the base priority to user
+ * level.
+ * @note Same as @p port_unlock() in this port.
+ */
+static inline void port_unlock_from_isr(void) {
+
+ port_unlock();
+}
+
+/**
+ * @brief Disables all the interrupt sources.
+ * @note In this port it disables all the interrupt sources by raising
+ * the priority mask to level 0.
+ */
+static inline void port_disable(void) {
+
+ __disable_irq();
+}
+
+/**
+ * @brief Disables the interrupt sources below kernel-level priority.
+ * @note Interrupt sources above kernel level remains enabled.
+ * @note In this port it raises/lowers the base priority to kernel level.
+ */
+static inline void port_suspend(void) {
+
+#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+ __set_BASEPRI(CORTEX_BASEPRI_KERNEL);
+ __enable_irq();
+#else
+ __disable_irq();
+#endif
+}
+
+/**
+ * @brief Enables all the interrupt sources.
+ * @note In this port it lowers the base priority to user level.
+ */
+static inline void port_enable(void) {
+
+#if !CORTEX_SIMPLIFIED_PRIORITY || defined(__DOXYGEN__)
+ __set_BASEPRI(CORTEX_BASEPRI_DISABLED);
+#endif
+ __enable_irq();
+}
+
+/**
+ * @brief Enters an architecture-dependent IRQ-waiting mode.
+ * @details The function is meant to return when an interrupt becomes pending.
+ * The simplest implementation is an empty function or macro but this
+ * would not take advantage of architecture-specific power saving
+ * modes.
+ * @note Implemented as an inlined @p WFI instruction.
+ */
+static inline void port_wait_for_interrupt(void) {
+
+#if CORTEX_ENABLE_WFI_IDLE
+ __WFI;
+#endif
+}
+
+static inline rtcnt_t port_rt_get_counter_value(void) {
+
+ return DWT->CYCCNT;
+}
+
+#endif /* !defined(_FROM_ASM_) */
+
+#endif /* _CHCORE_V7M_H_ */
+
+/** @} */
diff --git a/os/nil/src/nil.c b/os/nil/src/nil.c
index 20b454fa8..692d72a3d 100644
--- a/os/nil/src/nil.c
+++ b/os/nil/src/nil.c
@@ -278,22 +278,22 @@ thread_reference_t chSchReadyI(thread_reference_t tr, msg_t msg) {
}
/**
- * @brief Reschedules.
+ * @brief Reschedules if needed.
*
* @sclass
*/
-void chSchRescheduleS() {
- thread_reference_t otr = nil.current;
- thread_reference_t ntr = nil.next;
+void chSchRescheduleS(void) {
- if (ntr != otr) {
- nil.current = ntr;
+ if (chSchIsRescRequiredI()) {
+ thread_reference_t otr = nil.current;
+
+ nil.current = nil.next;
#if defined(NIL_CFG_IDLE_LEAVE_HOOK)
if (otr == &nil.threads[NIL_CFG_NUM_THREADS]) {
NIL_CFG_IDLE_LEAVE_HOOK();
}
#endif
- port_switch(ntr, otr);
+ port_switch(nil.next, otr);
}
}
diff --git a/os/rt/ports/ARMCMx/chcore_timer.h b/os/rt/ports/ARMCMx/chcore_timer.h
index e0cacabdd..548da4afe 100644
--- a/os/rt/ports/ARMCMx/chcore_timer.h
+++ b/os/rt/ports/ARMCMx/chcore_timer.h
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_timer.h
+ * @file chcore_timer.h
* @brief System timer header file.
*
* @addtogroup ARMCMx_TIMER
diff --git a/os/rt/ports/ARMCMx/chcore_v6m.c b/os/rt/ports/ARMCMx/chcore_v6m.c
index 03688709a..9548c2a8e 100644
--- a/os/rt/ports/ARMCMx/chcore_v6m.c
+++ b/os/rt/ports/ARMCMx/chcore_v6m.c
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_v6m.c
+ * @file chcore_v6m.c
* @brief ARMv6-M architecture port code.
*
* @addtogroup ARMCMx_V6M_CORE
diff --git a/os/rt/ports/ARMCMx/chcore_v6m.h b/os/rt/ports/ARMCMx/chcore_v6m.h
index 759041b8a..62dde2b30 100644
--- a/os/rt/ports/ARMCMx/chcore_v6m.h
+++ b/os/rt/ports/ARMCMx/chcore_v6m.h
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_v6m.h
+ * @file chcore_v6m.h
* @brief ARMv6-M architecture port macros and structures.
*
* @addtogroup ARMCMx_V6M_CORE
@@ -270,10 +270,6 @@ struct context {
}
#endif
-#if CH_CFG_TIMEDELTA > 0
-#include "chcore_timer.h"
-#endif
-
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
@@ -290,6 +286,10 @@ extern "C" {
}
#endif
+#if CH_CFG_TIMEDELTA > 0
+#include "chcore_timer.h"
+#endif
+
/*===========================================================================*/
/* Module inline functions. */
/*===========================================================================*/
diff --git a/os/rt/ports/ARMCMx/chcore_v7m.c b/os/rt/ports/ARMCMx/chcore_v7m.c
index ff9219ac6..29add3fb1 100644
--- a/os/rt/ports/ARMCMx/chcore_v7m.c
+++ b/os/rt/ports/ARMCMx/chcore_v7m.c
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_v7m.c
+ * @file chcore_v7m.c
* @brief ARMv7-M architecture port code.
*
* @addtogroup ARMCMx_V7M_CORE
diff --git a/os/rt/ports/ARMCMx/chcore_v7m.h b/os/rt/ports/ARMCMx/chcore_v7m.h
index 57b5fc40f..fb5bd4476 100644
--- a/os/rt/ports/ARMCMx/chcore_v7m.h
+++ b/os/rt/ports/ARMCMx/chcore_v7m.h
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/chcore_v7m.h
+ * @file chcore_v7m.h
* @brief ARMv7-M architecture port macros and structures.
*
* @addtogroup ARMCMx_V7M_CORE
diff --git a/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v6m.s b/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v6m.s
index d8f5601db..25f05fdc1 100644
--- a/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v6m.s
+++ b/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v6m.s
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/GCC/chcoreasm_v6m.s
+ * @file chcoreasm_v6m.s
* @brief ARMv6-M architecture port low level code.
*
* @addtogroup ARMCMx_CORE
@@ -40,7 +40,6 @@
#if !defined(__DOXYGEN__)
-
.set CONTEXT_OFFSET, 12
.set SCB_ICSR, 0xE000ED04
.set ICSR_PENDSVSET, 0x10000000
diff --git a/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s b/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s
index 8e3a913e7..3bcc00c92 100644
--- a/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s
+++ b/os/rt/ports/ARMCMx/compilers/GCC/chcoreasm_v7m.s
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/GCC/chcoreasm_v7m.s
+ * @file chcoreasm_v7m.s
* @brief ARMv7-M architecture port low level code.
*
* @addtogroup ARMCMx_CORE
@@ -40,7 +40,6 @@
#if !defined(__DOXYGEN__)
-
.set CONTEXT_OFFSET, 12
.set SCB_ICSR, 0xE000ED04
.set ICSR_PENDSVSET, 0x10000000
diff --git a/os/rt/ports/ARMCMx/compilers/GCC/chtypes.h b/os/rt/ports/ARMCMx/compilers/GCC/chtypes.h
index bc33d2e10..e16e4379e 100644
--- a/os/rt/ports/ARMCMx/compilers/GCC/chtypes.h
+++ b/os/rt/ports/ARMCMx/compilers/GCC/chtypes.h
@@ -19,7 +19,7 @@
*/
/**
- * @file ARMCMx/GCC/chtypes.h
+ * @file ARMCMx/compilers/GCC/chtypes.h
* @brief ARM Cortex-Mx port system types.
*
* @addtogroup ARMCMx_CORE