You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by GitBox <gi...@apache.org> on 2018/01/19 16:43:02 UTC

[GitHub] utzig closed pull request #730: Add Cortex-M3 support

utzig closed pull request #730: Add Cortex-M3 support
URL: https://github.com/apache/mynewt-core/pull/730
 
 
   

This is a PR merged from a forked repository.
As GitHub hides the original diff on merge, it is displayed below for
the sake of provenance:

As this is a foreign pull request (from a fork), the diff is supplied
below (as it won't show otherwise due to GitHub magic):

diff --git a/compiler/arm-none-eabi-m3/compiler.yml b/compiler/arm-none-eabi-m3/compiler.yml
new file mode 100644
index 000000000..6e69c5834
--- /dev/null
+++ b/compiler/arm-none-eabi-m3/compiler.yml
@@ -0,0 +1,37 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance
+# with the License.  You may obtain a copy of the License at
+# 
+#  http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing,
+# software distributed under the License is distributed on an
+# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+# KIND, either express or implied.  See the License for the
+# specific language governing permissions and limitations
+# under the License.
+#
+
+compiler.path.cc: arm-none-eabi-gcc
+compiler.path.cpp: arm-none-eabi-g++
+compiler.path.archive: arm-none-eabi-ar
+compiler.path.as: arm-none-eabi-gcc
+compiler.path.objdump: arm-none-eabi-objdump
+compiler.path.objsize: arm-none-eabi-size
+compiler.path.objcopy: arm-none-eabi-objcopy
+
+compiler.flags.base: -mcpu=cortex-m3 -mthumb-interwork -mthumb -Wall -Werror -fno-exceptions -ffunction-sections -fdata-sections
+compiler.flags.default: [compiler.flags.base, -O1 -ggdb]
+compiler.flags.optimized: [compiler.flags.base, -Os -ggdb]
+compiler.flags.debug: [compiler.flags.base, -Og -ggdb]
+
+compiler.as.flags: [-x, assembler-with-cpp]
+
+compiler.ld.flags: -static -specs=nosys.specs -lgcc -Wl,--gc-sections -nostartfiles
+compiler.ld.resolve_circular_deps: true
+compiler.ld.mapfile: true
diff --git a/compiler/arm-none-eabi-m3/pkg.yml b/compiler/arm-none-eabi-m3/pkg.yml
new file mode 100644
index 000000000..6b3e2b901
--- /dev/null
+++ b/compiler/arm-none-eabi-m3/pkg.yml
@@ -0,0 +1,30 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance
+# with the License.  You may obtain a copy of the License at
+# 
+#  http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing,
+# software distributed under the License is distributed on an
+# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+# KIND, either express or implied.  See the License for the
+# specific language governing permissions and limitations
+# under the License.
+#
+
+pkg.name: compiler/arm-none-eabi-m3
+pkg.type: compiler
+pkg.description: Compiler definition for ARM Cortex-M3 gcc cross compiler.
+pkg.author: "Apache Mynewt <de...@mynewt.apache.org>"
+pkg.homepage: "http://mynewt.apache.org/"
+pkg.keywords:
+    - arm
+    - compiler
+    - cortex
+    - m3
+    - gcc
diff --git a/compiler/arm-none-eabi-m3/syscfg.yml b/compiler/arm-none-eabi-m3/syscfg.yml
new file mode 100644
index 000000000..5f698a8a0
--- /dev/null
+++ b/compiler/arm-none-eabi-m3/syscfg.yml
@@ -0,0 +1,20 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance
+# with the License.  You may obtain a copy of the License at
+#
+#  http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing,
+# software distributed under the License is distributed on an
+# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+# KIND, either express or implied.  See the License for the
+# specific language governing permissions and limitations
+# under the License.
+#
+
+# Package: compiler/arm-none-eabi-m3
diff --git a/kernel/os/include/os/arch/cortex_m3/os/os_arch.h b/kernel/os/include/os/arch/cortex_m3/os/os_arch.h
new file mode 100755
index 000000000..598ac0dc6
--- /dev/null
+++ b/kernel/os/include/os/arch/cortex_m3/os/os_arch.h
@@ -0,0 +1,85 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance
+ * with the License.  You may obtain a copy of the License at
+ *
+ *  http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+ * KIND, either express or implied.  See the License for the
+ * specific language governing permissions and limitations
+ * under the License.
+ */
+
+#ifndef _OS_ARCH_ARM_H
+#define _OS_ARCH_ARM_H
+
+#include <stdint.h>
+#include "mcu/cortex_m3.h"
+#include "os/os_time.h"
+#include "os/os_error.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+struct os_task;
+
+/* Run in priviliged or unprivileged Thread mode */
+#define OS_RUN_PRIV         (0)
+#define OS_RUN_UNPRIV       (1)
+
+/* CPU status register */
+typedef uint32_t os_sr_t;
+/* Stack type, aligned to a 32-bit word. */
+#define OS_STACK_PATTERN    (0xdeadbeef)
+
+typedef uint32_t os_stack_t;
+#define OS_ALIGNMENT        (4)
+#define OS_STACK_ALIGNMENT  (8)
+
+/*
+ * Stack sizes for common OS tasks
+ */
+#define OS_SANITY_STACK_SIZE (64)
+#define OS_IDLE_STACK_SIZE (64)
+
+#define OS_STACK_ALIGN(__nmemb) \
+    (OS_ALIGN((__nmemb), OS_STACK_ALIGNMENT))
+
+/* Enter a critical section, save processor state, and block interrupts */
+#define OS_ENTER_CRITICAL(__os_sr) (__os_sr = os_arch_save_sr())
+/* Exit a critical section, restore processor state and unblock interrupts */
+#define OS_EXIT_CRITICAL(__os_sr) (os_arch_restore_sr(__os_sr))
+#define OS_ASSERT_CRITICAL() (assert(os_arch_in_critical()))
+
+os_stack_t *os_arch_task_stack_init(struct os_task *, os_stack_t *, int);
+void timer_handler(void);
+void os_arch_ctx_sw(struct os_task *);
+os_sr_t os_arch_save_sr(void);
+void os_arch_restore_sr(os_sr_t);
+int os_arch_in_critical(void);
+void os_arch_init(void);
+uint32_t os_arch_start(void);
+os_error_t os_arch_os_init(void);
+os_error_t os_arch_os_start(void);
+void os_set_env(os_stack_t *);
+void os_arch_init_task_stack(os_stack_t *sf);
+void os_default_irq_asm(void);
+
+/* External function prototypes supplied by BSP */
+void os_bsp_systick_init(uint32_t os_tick_per_sec, int prio);
+void os_bsp_idle(os_time_t ticks);
+void os_bsp_ctx_sw(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _OS_ARCH_ARM_H */
diff --git a/kernel/os/src/arch/cortex_m3/m3/HAL_CM3.s b/kernel/os/src/arch/cortex_m3/m3/HAL_CM3.s
new file mode 100755
index 000000000..92b929c82
--- /dev/null
+++ b/kernel/os/src/arch/cortex_m3/m3/HAL_CM3.s
@@ -0,0 +1,224 @@
+/*----------------------------------------------------------------------------
+ * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+ * 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.
+ *---------------------------------------------------------------------------*/
+#include <syscfg/syscfg.h>
+
+        .syntax unified
+
+/*----------------------------------------------------------------------------
+ *      Functions
+ *---------------------------------------------------------------------------*/
+
+        .thumb
+
+        .section ".text"
+        .align  2
+
+/*--------------------------- os_set_env ------------------------------------*/
+#       void os_set_env (void);
+#
+#   Called to switch to privileged or unprivileged thread mode. The variable
+#   'os_flags' contains the CONTROL bit LSB to set the device into the
+#   proper mode. We also use PSP so we set bit 1 (the SPSEL bit) to 1.
+#
+
+        .thumb_func
+        .type   os_set_env, %function
+        .global os_set_env
+os_set_env:
+        .fnstart
+        .cantunwind
+
+        MSR     PSP,R0
+        LDR     R0,=os_flags
+        LDRB    R0,[R0]
+        ADDS    R0, R0, #2
+        MSR     CONTROL,R0
+        ISB
+        BX      LR
+
+        .fnend
+        .size   os_set_env, .-os_set_env
+
+/*--------------------------- os_set_env ------------------------------------*/
+
+
+/*--------------------------- os_arch_init_task_stack------------------------*/
+#       void os_arch_init_task_stack(os_stack_t *sf);
+# NOTE: This function only stores R4 through R11 on stack. The reason we do 
+# this is that the application may have stored some values in some of the
+# registers and we want to preserve those values (position independent code
+# is a good example). The other registers are handled in the C startup code.
+        .thumb_func
+        .type   os_arch_init_task_stack, %function
+        .global os_arch_init_task_stack
+os_arch_init_task_stack:
+        .fnstart
+
+        STMIA   R0,{R4-R11}
+        BX      LR
+
+        .fnend
+        .size   os_arch_init_task_stack, .-os_arch_init_task_stack
+/*--------------------------- os_set_env ------------------------------------*/
+
+
+/*-------------------------- SVC_Handler ------------------------------------*/
+
+#       void SVC_Handler (void);
+
+        .thumb_func
+        .type   SVC_Handler, %function
+        .global SVC_Handler
+SVC_Handler:
+        .fnstart
+        .cantunwind
+
+        MRS     R0,PSP                  /* Read PSP */
+        LDR     R1,[R0,#24]             /* Read Saved PC from Stack */
+        LDRB    R1,[R1,#-2]             /* Load SVC Number */
+        CBNZ    R1,SVC_User
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BLX     R12                     /* Call SVC Function */
+        POP     {R4,LR}                 /* Restore EXC_RETURN */
+
+        MRS     R12,PSP                 /* Read PSP */
+        STM     R12,{R0-R2}             /* Store return values */
+        BX      LR                      /* Return from interrupt */
+
+        /*------------------- User SVC ------------------------------*/
+SVC_User:
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        LDR     R2,=SVC_Count
+        LDR     R2,[R2]
+        CMP     R1,R2
+        BHI     SVC_Done                /* Overflow */
+
+        LDR     R4,=SVC_Table-4
+        LDR     R4,[R4,R1,LSL #2]       /* Load SVC Function Address */
+
+        LDM     R0,{R0-R3,R12}          /* Read R0-R3,R12 from stack */
+        BLX     R4                      /* Call SVC Function */
+
+        MRS     R12,PSP
+        STM     R12,{R0-R3}             /* Function return values */
+SVC_Done:
+        POP     {R4,LR}                 /* Restore EXC_RETURN */
+        BX      LR                      /* Return from interrupt */
+
+        .fnend
+        .size   SVC_Handler, .-SVC_Handler
+
+
+/*-------------------------- PendSV_Handler ---------------------------------*/
+
+#       void PendSV_Handler (void);
+
+        .thumb_func
+        .type   PendSV_Handler, %function
+        .global PendSV_Handler
+PendSV_Handler:
+        .fnstart
+        .cantunwind
+
+        LDR     R3,=g_os_run_list       /* Get highest priority task ready to run */
+        LDR     R2,[R3]                 /* Store in R2 */
+        LDR     R3,=g_current_task      /* Get current task */
+        LDR     R1,[R3]                 /* Current task in R1 */
+        CMP     R1,R2
+        IT      EQ
+        BXEQ    LR                      /* RETI, no task switch */
+
+        MRS     R12,PSP                 /* Read PSP */
+        STMDB   R12!,{R4-R11}           /* Save Old context */
+        STR     R12,[R1,#0]             /* Update stack pointer in current task */
+        STR     R2,[R3]                 /* g_current_task = highest ready */
+
+        LDR     R12,[R2,#0]             /* get stack pointer of task we will start */
+        LDMIA   R12!,{R4-R11}           /* Restore New Context */
+        MSR     PSP,R12                 /* Write PSP */
+        BX      LR                      /* Return to Thread Mode */
+
+        .fnend
+        .size   PendSV_Handler, .-PendSV_Handler
+
+
+/*-------------------------- SysTick_Handler --------------------------------*/
+
+#       void SysTick_Handler (void);
+        .thumb_func
+        .type   SysTick_Handler, %function
+        .global SysTick_Handler
+SysTick_Handler:
+        .fnstart
+        .cantunwind
+
+        PUSH    {R4,LR}                 /* Save EXC_RETURN */
+        BL      timer_handler
+        POP     {R4,LR}                 /* Restore EXC_RETURN */
+        BX      LR
+
+        .fnend
+        .size   SysTick_Handler, .-SysTick_Handler
+
+/*-------------------------- Defalt IRQ --------------------------------*/
+        .thumb_func
+        .type   os_default_irq_asm, %function
+        .global os_default_irq_asm
+os_default_irq_asm:
+        .fnstart
+        .cantunwind
+
+        /*
+         * LR = 0xfffffff9 if we were using MSP as SP
+         * LR = 0xfffffffd if we were using PSP as SP
+         */
+        TST     LR,#4
+        ITE     EQ
+        MRSEQ   R3,MSP
+        MRSNE   R3,PSP
+        PUSH    {R3-R11,LR}
+        MOV     R0, SP
+        BL      os_default_irq
+        POP     {R3-R11,LR}                 /* Restore EXC_RETURN */
+        BX      LR
+
+        .fnend
+        .size   os_default_irq_asm, .-os_default_irq_asm
+
+	/*
+	 * Prevent libgcc unwind stuff from getting pulled in.
+	 */
+        .section ".data"
+	.global __aeabi_unwind_cpp_pr0
+__aeabi_unwind_cpp_pr0:
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff --git a/kernel/os/src/arch/cortex_m3/m3/SVC_Table.s b/kernel/os/src/arch/cortex_m3/m3/SVC_Table.s
new file mode 100755
index 000000000..2b9932128
--- /dev/null
+++ b/kernel/os/src/arch/cortex_m3/m3/SVC_Table.s
@@ -0,0 +1,56 @@
+;/*----------------------------------------------------------------------------
+; *      RL-ARM - RTX
+; *----------------------------------------------------------------------------
+; *      Name:    SVC_TABLE.S
+; *      Purpose: Pre-defined SVC Table for Cortex-M
+; *      Rev.:    V4.70
+; *----------------------------------------------------------------------------
+; *
+; * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH
+; * 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.
+; *---------------------------------------------------------------------------*/
+
+
+        .file   "SVC_Table.S"
+
+
+        .section ".svc_table"
+
+        .global  SVC_Table
+SVC_Table:
+/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
+#       .long   __SVC_1                 /* user SVC function */
+SVC_End:
+
+        .global  SVC_Count
+SVC_Count:
+        .long   (SVC_End-SVC_Table)/4
+
+
+        .end
+
+/*----------------------------------------------------------------------------
+ * end of file
+ *---------------------------------------------------------------------------*/
diff --git a/kernel/os/src/arch/cortex_m3/os_arch_arm.c b/kernel/os/src/arch/cortex_m3/os_arch_arm.c
new file mode 100755
index 000000000..a3b3bddb5
--- /dev/null
+++ b/kernel/os/src/arch/cortex_m3/os_arch_arm.c
@@ -0,0 +1,346 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance
+ * with the License.  You may obtain a copy of the License at
+ *
+ *  http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+ * KIND, either express or implied.  See the License for the
+ * specific language governing permissions and limitations
+ * under the License.
+ */
+#include <syscfg/syscfg.h>
+
+#include "os/os.h"
+#include "os/os_arch.h"
+#include <hal/hal_bsp.h>
+#include <hal/hal_os_tick.h>
+#include <bsp/cmsis_nvic.h>
+
+#include "os_priv.h"
+
+/*
+ * From HAL_CM3.s
+ */
+extern void SVC_Handler(void);
+extern void PendSV_Handler(void);
+extern void SysTick_Handler(void);
+
+/* Initial program status register */
+#define INITIAL_xPSR    0x01000000
+
+/*
+ * Initial LR indicating basic frame.
+ * See ARMv7-M Architecture Ref Manual
+ */
+#define INITIAL_LR      0xfffffffd;
+
+/*
+ * Exception priorities. The higher the number, the lower the priority. A
+ * higher priority exception will interrupt a lower priority exception.
+ */
+#define PEND_SV_PRIO    ((1 << __NVIC_PRIO_BITS) - 1)
+#define OS_TICK_PRIO    (PEND_SV_PRIO - 1)
+
+/* Make the SVC instruction highest priority */
+#define SVC_PRIO        (1)
+
+/* Stack frame structure */
+struct stack_frame {
+    uint32_t    r4;
+    uint32_t    r5;
+    uint32_t    r6;
+    uint32_t    r7;
+    uint32_t    r8;
+    uint32_t    r9;
+    uint32_t    r10;
+    uint32_t    r11;
+    uint32_t    r0;
+    uint32_t    r1;
+    uint32_t    r2;
+    uint32_t    r3;
+    uint32_t    r12;
+    uint32_t    lr;
+    uint32_t    pc;
+    uint32_t    xpsr;
+};
+
+#define SVC_ArgN(n) \
+  register int __r##n __asm("r"#n);
+
+#define SVC_Arg0()  \
+  SVC_ArgN(0)       \
+  SVC_ArgN(1)       \
+  SVC_ArgN(2)       \
+  SVC_ArgN(3)
+
+#if (defined (__CORTEX_M0)) || defined (__CORTEX_M0PLUS)
+#define SVC_Call(f)                                                     \
+  __asm volatile                                                        \
+  (                                                                     \
+    "ldr r7,="#f"\n\t"                                                  \
+    "mov r12,r7\n\t"                                                    \
+    "svc 0"                                                             \
+    :               "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3)  \
+    :                "r" (__r0),  "r" (__r1),  "r" (__r2),  "r" (__r3)  \
+    : "r7", "r12", "lr", "cc"                                           \
+  );
+#else
+#define SVC_Call(f)                                                     \
+  __asm volatile                                                        \
+  (                                                                     \
+    "ldr r12,="#f"\n\t"                                                 \
+    "svc 0"                                                             \
+    :               "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3)  \
+    :                "r" (__r0),  "r" (__r1),  "r" (__r2),  "r" (__r3)  \
+    : "r12", "lr", "cc"                                                 \
+  );
+#endif
+
+/* XXX: determine how we will deal with running un-privileged */
+uint32_t os_flags = OS_RUN_PRIV;
+
+void
+timer_handler(void)
+{
+    os_time_advance(1);
+}
+
+void
+os_arch_ctx_sw(struct os_task *t)
+{
+    os_sched_ctx_sw_hook(t);
+
+    /* Set PendSV interrupt pending bit to force context switch */
+    SCB->ICSR = SCB_ICSR_PENDSVSET_Msk;
+}
+
+os_sr_t
+os_arch_save_sr(void)
+{
+    uint32_t isr_ctx;
+
+    isr_ctx = __get_PRIMASK();
+    __disable_irq();
+    return (isr_ctx & 1);
+}
+
+void
+os_arch_restore_sr(os_sr_t isr_ctx)
+{
+    if (!isr_ctx) {
+        __enable_irq();
+    }
+}
+
+int
+os_arch_in_critical(void)
+{
+    uint32_t isr_ctx;
+
+    isr_ctx = __get_PRIMASK();
+    return (isr_ctx & 1);
+}
+
+os_stack_t *
+os_arch_task_stack_init(struct os_task *t, os_stack_t *stack_top, int size)
+{
+    int i;
+    os_stack_t *s;
+    struct stack_frame *sf;
+
+    /* Get stack frame pointer */
+    s = (os_stack_t *) ((uint8_t *) stack_top - sizeof(*sf));
+
+    /* Zero out R1-R3, R12, LR */
+    for (i = 9; i < 14; ++i) {
+        s[i] = 0;
+    }
+
+    /* Set registers R4 - R11 on stack. */
+    os_arch_init_task_stack(s);
+
+    /* Set remaining portions of stack frame */
+    sf = (struct stack_frame *) s;
+    sf->xpsr = INITIAL_xPSR;
+    sf->pc = (uint32_t)t->t_func;
+    sf->r0 = (uint32_t)t->t_arg;
+
+    return (s);
+}
+
+void
+os_arch_init(void)
+{
+    /*
+     * Trap on divide-by-zero.
+     */
+    SCB->CCR |= SCB_CCR_DIV_0_TRP_Msk;
+    os_init_idle_task();
+}
+
+__attribute__((always_inline))
+static inline void
+svc_os_arch_init(void)
+{
+    SVC_Arg0();
+    SVC_Call(os_arch_init);
+}
+
+os_error_t
+os_arch_os_init(void)
+{
+    os_error_t err;
+    int i;
+
+    /* Cannot be called within an ISR */
+    err = OS_ERR_IN_ISR;
+    if (__get_IPSR() == 0) {
+        err = OS_OK;
+
+        /* Drop priority for all interrupts */
+        for (i = 0; i < sizeof(NVIC->IP); i++) {
+            NVIC->IP[i] = -1;
+        }
+
+        NVIC_SetVector(SVC_IRQn, (uint32_t)SVC_Handler);
+        NVIC_SetVector(PendSV_IRQn, (uint32_t)PendSV_Handler);
+        NVIC_SetVector(SysTick_IRQn, (uint32_t)SysTick_Handler);
+
+        /*
+         * Install default interrupt handler, which'll print out system
+         * state at the time of the interrupt, and few other regs which
+         * should help in trying to figure out what went wrong.
+         */
+        NVIC_SetVector(NonMaskableInt_IRQn, (uint32_t)os_default_irq_asm);
+        NVIC_SetVector(-13, (uint32_t)os_default_irq_asm);
+        NVIC_SetVector(MemoryManagement_IRQn, (uint32_t)os_default_irq_asm);
+        NVIC_SetVector(BusFault_IRQn, (uint32_t)os_default_irq_asm);
+        NVIC_SetVector(UsageFault_IRQn, (uint32_t)os_default_irq_asm);
+        for (i = 0; i < NVIC_NUM_VECTORS - NVIC_USER_IRQ_OFFSET; i++) {
+            NVIC_SetVector(i, (uint32_t)os_default_irq_asm);
+        }
+
+        /* Set the PendSV interrupt exception priority to the lowest priority */
+        NVIC_SetPriority(PendSV_IRQn, PEND_SV_PRIO);
+
+        /* Set the SVC interrupt to priority 0 (highest configurable) */
+        NVIC_SetPriority(SVC_IRQn, SVC_PRIO);
+
+        /* Check if privileged or not */
+        if ((__get_CONTROL() & 1) == 0) {
+            os_arch_init();
+        } else {
+            svc_os_arch_init();
+        }
+    }
+
+    return err;
+}
+
+uint32_t
+os_arch_start(void)
+{
+    struct os_task *t;
+
+    /* Get the highest priority ready to run to set the current task */
+    t = os_sched_next_task();
+    os_sched_set_current_task(t);
+
+    /* Adjust PSP so it looks like this task just took an exception */
+    __set_PSP((uint32_t)t->t_stackptr + offsetof(struct stack_frame, r0));
+
+    /* Intitialize and start system clock timer */
+    os_tick_init(OS_TICKS_PER_SEC, OS_TICK_PRIO);
+
+    /* Mark the OS as started, right before we run our first task */
+    g_os_started = 1;
+
+    /* Perform context switch */
+    os_arch_ctx_sw(t);
+
+    return (uint32_t)(t->t_arg);
+}
+
+__attribute__((always_inline))
+static inline void svc_os_arch_start(void)
+{
+    SVC_Arg0();
+    SVC_Call(os_arch_start);
+}
+
+/**
+ * Start the OS. First check to see if we are running with the correct stack
+ * pointer set (PSP) and privilege mode (PRIV).
+ *
+ *
+ * @return os_error_t
+ */
+os_error_t
+os_arch_os_start(void)
+{
+    os_error_t err;
+
+    /*
+     * Set the os environment. This will set stack pointers and, based
+     * on the contents of os_flags, will determine if the tasks run in
+     * privileged or un-privileged mode.
+     *
+     * We switch to using "empty" part of idle task's stack until
+     * the svc_os_arch_start() executes SVC, and we will never return.
+     */
+    os_set_env(g_idle_task.t_stackptr - 1);
+
+    err = OS_ERR_IN_ISR;
+    if (__get_IPSR() == 0) {
+        /*
+         * The following switch statement is really just a sanity check to
+         * insure that the os initialization routine was called prior to the
+         * os start routine.
+         */
+        err = OS_OK;
+        switch (__get_CONTROL() & 0x03) {
+        /*
+         * These two cases are for completeness. Thread mode should be set
+         * to use PSP already.
+         *
+         * Fall-through intentional!
+         */
+        case 0x00:
+        case 0x01:
+            err = OS_ERR_PRIV;
+            break;
+        case 0x02:
+            /*
+             * We are running in Privileged Thread mode w/SP = PSP but we
+             * are supposed to be un-privileged.
+             */
+            if ((os_flags & 1) == OS_RUN_UNPRIV) {
+                err = OS_ERR_PRIV;
+            }
+            break;
+        case 0x03:
+            /*
+             * We are running in Unprivileged Thread mode w/SP = PSP but we
+             * are supposed to be privileged.
+             */
+            if  ((os_flags & 1) == OS_RUN_PRIV) {
+                err = OS_ERR_PRIV;
+            }
+            break;
+        }
+        if (err == OS_OK) {
+            /* Always start OS through SVC call */
+            svc_os_arch_start();
+        }
+    }
+
+    return err;
+}
diff --git a/kernel/os/src/arch/cortex_m3/os_fault.c b/kernel/os/src/arch/cortex_m3/os_fault.c
new file mode 100644
index 000000000..f1ddc006b
--- /dev/null
+++ b/kernel/os/src/arch/cortex_m3/os_fault.c
@@ -0,0 +1,171 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance
+ * with the License.  You may obtain a copy of the License at
+ *
+ *  http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing,
+ * software distributed under the License is distributed on an
+ * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
+ * KIND, either express or implied.  See the License for the
+ * specific language governing permissions and limitations
+ * under the License.
+ */
+
+#include "syscfg/syscfg.h"
+#include "console/console.h"
+#include "hal/hal_system.h"
+#include "os/os.h"
+
+#if MYNEWT_VAL(OS_COREDUMP)
+#include "coredump/coredump.h"
+#endif
+
+#include <stdint.h>
+#include <unistd.h>
+
+struct exception_frame {
+    uint32_t r0;
+    uint32_t r1;
+    uint32_t r2;
+    uint32_t r3;
+    uint32_t r12;
+    uint32_t lr;
+    uint32_t pc;
+    uint32_t psr;
+};
+
+struct trap_frame {
+    struct exception_frame *ef;
+    uint32_t r4;
+    uint32_t r5;
+    uint32_t r6;
+    uint32_t r7;
+    uint32_t r8;
+    uint32_t r9;
+    uint32_t r10;
+    uint32_t r11;
+    uint32_t lr;    /* this LR holds EXC_RETURN */
+};
+
+struct coredump_regs {
+    uint32_t r0;
+    uint32_t r1;
+    uint32_t r2;
+    uint32_t r3;
+    uint32_t r4;
+    uint32_t r5;
+    uint32_t r6;
+    uint32_t r7;
+    uint32_t r8;
+    uint32_t r9;
+    uint32_t r10;
+    uint32_t r11;
+    uint32_t r12;
+    uint32_t sp;
+    uint32_t lr;
+    uint32_t pc;
+    uint32_t psr;
+};
+
+#if MYNEWT_VAL(OS_COREDUMP)
+static void
+trap_to_coredump(struct trap_frame *tf, struct coredump_regs *regs)
+{
+    regs->r0 = tf->ef->r0;
+    regs->r1 = tf->ef->r1;
+    regs->r2 = tf->ef->r2;
+    regs->r3 = tf->ef->r3;
+    regs->r4 = tf->r4;
+    regs->r5 = tf->r5;
+    regs->r6 = tf->r6;
+    regs->r7 = tf->r7;
+    regs->r8 = tf->r8;
+    regs->r9 = tf->r9;
+    regs->r10 = tf->r10;
+    regs->r11 = tf->r11;
+    regs->r12 = tf->ef->r12;
+    /*
+     * SP just before exception for the coredump.
+     * See ARMv7-M Architecture Ref Manual, sections B1.5.6 - B1.5.8
+     * If floating point registers were pushed to stack, SP is adjusted
+     * by 0x68.
+     * Otherwise, SP is adjusted by 0x20.
+     * If SCB->CCR.STKALIGN is set, or fpu is active, SP is aligned to
+     * 8-byte boundary on exception entry.
+     * If this alignment adjustment happened, xPSR will have bit 9 set.
+     */
+    if ((tf->lr & 0x10) == 0) {
+        /*
+         * Extended frame
+         */
+        regs->sp = ((uint32_t)tf->ef) + 0x68;
+        if (tf->ef->psr & (1 << 9)) {
+            regs->sp += 4;
+        }
+    } else {
+        regs->sp = ((uint32_t)tf->ef) + 0x20;
+        if ((SCB->CCR & SCB_CCR_STKALIGN_Msk) & tf->ef->psr & (1 << 9)) {
+            regs->sp += 4;
+        }
+    }
+    regs->lr = tf->ef->lr;
+    regs->pc = tf->ef->pc;
+    regs->psr = tf->ef->psr;
+}
+#endif
+
+void
+__assert_func(const char *file, int line, const char *func, const char *e)
+{
+    int sr;
+
+    OS_ENTER_CRITICAL(sr);
+    (void)sr;
+    console_blocking_mode();
+    console_printf("Assert @ 0x%x\n",
+                   (unsigned int)__builtin_return_address(0));
+    if (hal_debugger_connected()) {
+       /*
+        * If debugger is attached, breakpoint before the trap.
+        */
+       asm("bkpt");
+    }
+    SCB->ICSR = SCB_ICSR_NMIPENDSET_Msk;
+    asm("isb");
+    hal_system_reset();
+}
+
+void
+os_default_irq(struct trap_frame *tf)
+{
+#if MYNEWT_VAL(OS_COREDUMP)
+    struct coredump_regs regs;
+#endif
+
+    console_blocking_mode();
+    console_printf("Unhandled interrupt (%ld), exception sp 0x%08lx\n",
+      SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk, (uint32_t)tf->ef);
+    console_printf(" r0:0x%08lx  r1:0x%08lx  r2:0x%08lx  r3:0x%08lx\n",
+      tf->ef->r0, tf->ef->r1, tf->ef->r2, tf->ef->r3);
+    console_printf(" r4:0x%08lx  r5:0x%08lx  r6:0x%08lx  r7:0x%08lx\n",
+      tf->r4, tf->r5, tf->r6, tf->r7);
+    console_printf(" r8:0x%08lx  r9:0x%08lx r10:0x%08lx r11:0x%08lx\n",
+      tf->r8, tf->r9, tf->r10, tf->r11);
+    console_printf("r12:0x%08lx  lr:0x%08lx  pc:0x%08lx psr:0x%08lx\n",
+      tf->ef->r12, tf->ef->lr, tf->ef->pc, tf->ef->psr);
+    console_printf("ICSR:0x%08lx HFSR:0x%08lx CFSR:0x%08lx\n",
+      SCB->ICSR, SCB->HFSR, SCB->CFSR);
+    console_printf("BFAR:0x%08lx MMFAR:0x%08lx\n", SCB->BFAR, SCB->MMFAR);
+
+#if MYNEWT_VAL(OS_COREDUMP)
+    trap_to_coredump(tf, &regs);
+    coredump_dump(&regs, sizeof(regs));
+#endif
+    hal_system_reset();
+}


 

----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on GitHub and use the
URL above to go to the specific comment.
 
For queries about this service, please contact Infrastructure at:
users@infra.apache.org


With regards,
Apache Git Services