summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-04 22:28:06 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-04 22:28:06 +0000
commitd80abb394a7c0fbcf824f84ed61a061b2af8e86c (patch)
tree685f3af3ca76cc1d06c277ab478ed524db615fbb /nuttx
parent3a43d878137fecaec5b35d9022308833c96517a8 (diff)
downloadpx4-nuttx-d80abb394a7c0fbcf824f84ed61a061b2af8e86c.tar.gz
px4-nuttx-d80abb394a7c0fbcf824f84ed61a061b2af8e86c.tar.bz2
px4-nuttx-d80abb394a7c0fbcf824f84ed61a061b2af8e86c.zip
Add more HC12 common files
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2306 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/common/up_createstack.c4
-rw-r--r--nuttx/arch/arm/src/common/up_usestack.c4
-rwxr-xr-xnuttx/arch/hc/src/common/up_createstack.c130
-rwxr-xr-xnuttx/arch/hc/src/common/up_idle.c85
-rwxr-xr-xnuttx/arch/hc/src/common/up_initialize.c169
-rwxr-xr-xnuttx/arch/hc/src/common/up_internal.h213
-rwxr-xr-xnuttx/arch/hc/src/common/up_interruptcontext.c71
-rwxr-xr-xnuttx/arch/hc/src/common/up_puts.c76
-rwxr-xr-xnuttx/arch/hc/src/common/up_releasestack.c81
-rwxr-xr-xnuttx/arch/hc/src/common/up_usestack.c117
10 files changed, 946 insertions, 4 deletions
diff --git a/nuttx/arch/arm/src/common/up_createstack.c b/nuttx/arch/arm/src/common/up_createstack.c
index 85071269e..c3e213eb4 100644
--- a/nuttx/arch/arm/src/common/up_createstack.c
+++ b/nuttx/arch/arm/src/common/up_createstack.c
@@ -101,7 +101,7 @@ STATUS up_create_stack(_TCB *tcb, size_t stack_size)
size_t top_of_stack;
size_t size_of_stack;
- /* The Arm7Tdmi uses a push-down stack: the stack grows
+ /* The ARM uses a push-down stack: the stack grows
* toward loweraddresses in memory. The stack pointer
* register, points to the lowest, valid work address
* (the "top" of the stack). Items on the stack are
@@ -110,7 +110,7 @@ STATUS up_create_stack(_TCB *tcb, size_t stack_size)
top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
- /* The Arm7Tdmi stack must be aligned at word (4 byte)
+ /* The ARM stack must be aligned at word (4 byte)
* boundaries. If necessary top_of_stack must be rounded
* down to the next boundary
*/
diff --git a/nuttx/arch/arm/src/common/up_usestack.c b/nuttx/arch/arm/src/common/up_usestack.c
index afd29d52d..c67dd6ad0 100644
--- a/nuttx/arch/arm/src/common/up_usestack.c
+++ b/nuttx/arch/arm/src/common/up_usestack.c
@@ -92,7 +92,7 @@ STATUS up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
tcb->stack_alloc_ptr = stack;
- /* The Arm7Tdmi uses a push-down stack: the stack grows
+ /* The ARM uses a push-down stack: the stack grows
* toward loweraddresses in memory. The stack pointer
* register, points to the lowest, valid work address
* (the "top" of the stack). Items on the stack are
@@ -101,7 +101,7 @@ STATUS up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
- /* The Arm7Tdmi stack must be aligned at word (4 byte)
+ /* The ARM stack must be aligned at word (4 byte)
* boundaries. If necessary top_of_stack must be rounded
* down to the next boundary
*/
diff --git a/nuttx/arch/hc/src/common/up_createstack.c b/nuttx/arch/hc/src/common/up_createstack.c
new file mode 100755
index 000000000..1f2cb691c
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_createstack.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ * arch/hc/src/common/up_createstack.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_create_stack
+ *
+ * Description:
+ * Allocate a stack for a new thread and setup up stack-related information
+ * in the TCB.
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware, processor, etc.
+ * This value is retained only for debug purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The initial value of the
+ * stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The requested stack size. At least this much must be
+ * allocated.
+ *
+ ****************************************************************************/
+
+STATUS up_create_stack(_TCB *tcb, size_t stack_size)
+{
+ if (tcb->stack_alloc_ptr && tcb->adj_stack_size != stack_size)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ tcb->stack_alloc_ptr = NULL;
+ }
+
+ if (!tcb->stack_alloc_ptr)
+ {
+ tcb->stack_alloc_ptr = (uint32 *)malloc(stack_size);
+ }
+
+ if (tcb->stack_alloc_ptr)
+ {
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ /* The CPU12 uses a push-down stack: the stack grows
+ * toward lower addresses in memory. Because the CPU12 stack
+ * operates as a decrement then store stack, the value assigned
+ * to the initial stack pointer is one more than the last valid
+ * stack address.
+ */
+
+ top_of_stack = (size_t)tcb->stack_alloc_ptr + stack_size;
+
+ /* The CPU12 stack should be aligned at half-word (2 byte)
+ * boundaries. If necessary top_of_stack must be rounded
+ * down to the next boundary
+ */
+
+ top_of_stack &= ~1;
+ size_of_stack = top_of_stack - (size_t)tcb->stack_alloc_ptr;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+
+ up_ledon(LED_STACKCREATED);
+ return OK;
+ }
+
+ return ERROR;
+}
diff --git a/nuttx/arch/hc/src/common/up_idle.c b/nuttx/arch/hc/src/common/up_idle.c
new file mode 100755
index 000000000..67d1ccae3
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_idle.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/hc/src/common/up_idle.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their is no other
+ * ready-to-run task. This is processor idle time and will continue until
+ * some interrupt occurs to cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g., this is where
+ * power management operations might be performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts,
+ * then process "fake" timer interrupts. Hopefully, something
+ * will wake up.
+ */
+
+ sched_process_timer();
+#endif
+}
+
diff --git a/nuttx/arch/hc/src/common/up_initialize.c b/nuttx/arch/hc/src/common/up_initialize.c
new file mode 100755
index 000000000..725479a07
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_initialize.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ * arch/hc/src/common/up_initialize.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_calibratedelay
+ *
+ * Description:
+ * Delay loops are provided for short timing loops. This function, if
+ * enabled, will just wait for 100 seconds. Using a stopwatch, you can
+ * can then determine if the timing loops are properly calibrated.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_CALIBRATION) && defined(CONFIG_DEBUG)
+static void up_calibratedelay(void)
+{
+ int i;
+ lldbg("Beginning 100s delay\n");
+ for (i = 0; i < 100; i++)
+ {
+ up_mdelay(1000);
+ }
+ lldbg("End 100s delay\n");
+}
+#else
+# define up_calibratedelay()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_initialize
+ *
+ * Description:
+ * up_initialize will be called once during OS initialization after the
+ * basic OS services have been initialized. The architecture specific
+ * details of initializing the OS will be handled here. Such things as
+ * setting up interrupt service routines, starting the clock, and
+ * registering device drivers are some of the things that are different
+ * for each processor and hardware platform.
+ *
+ * up_initialize is called after the OS initialized but before the user
+ * initialization logic has been started and before the libraries have
+ * been initialized. OS services and driver services are available.
+ *
+ ****************************************************************************/
+
+void up_initialize(void)
+{
+ /* Initialize global variables */
+
+ current_regs = NULL;
+
+ /* Calibrate the timing loop */
+
+ up_calibratedelay();
+
+ /* Add any extra memory fragments to the memory manager */
+
+ up_addregion();
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+ /* Initialize the DMA subsystem if the weak function stm32_dmainitialize has been
+ * brought into the build
+ */
+
+#ifdef CONFIG_ARCH_DMA
+#ifdef CONFIG_HAVE_WEAKFUNCTIONS
+ if (up_dmainitialize)
+#endif
+ {
+ up_dmainitialize();
+ }
+#endif
+
+ /* Initialize the system timer interrupt */
+
+#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS)
+ up_timerinit();
+#endif
+
+ /* Register devices */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ devnull_register(); /* Standard /dev/null */
+#endif
+
+ /* Initialize the serial device driver */
+
+#ifdef CONFIG_USE_SERIALDRIVER
+ up_serialinit();
+#elif defined(CONFIG_DEV_LOWCONSOLE)
+ lowconsole_init();
+#endif
+
+ /* Initialize the netwok */
+
+ up_netinitialize();
+
+ /* Initializ USB */
+
+ up_usbinitialize();
+
+ up_ledon(LED_IRQSENABLED);
+}
diff --git a/nuttx/arch/hc/src/common/up_internal.h b/nuttx/arch/hc/src/common/up_internal.h
new file mode 100755
index 000000000..ada4bf8fe
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_internal.h
@@ -0,0 +1,213 @@
+/****************************************************************************
+ * arch/hc/src/common/up_internal.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __UP_INTERNAL_H
+#define __UP_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Bring-up debug configurations. These are here (vs defconfig)
+ * because these should only be controlled during low level
+ * board bring-up and not part of normal platform configuration.
+ */
+
+#undef CONFIG_SUPPRESS_INTERRUPTS /* DEFINED: Do not enable interrupts */
+#undef CONFIG_SUPPRESS_TIMER_INTS /* DEFINED: No timer */
+#undef CONFIG_SUPPRESS_SERIAL_INTS /* DEFINED: Console will poll */
+#undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */
+#undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */
+
+/* Determine which (if any) console driver to use */
+
+#if CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE)
+# undef CONFIG_USE_SERIALDRIVER
+# undef CONFIG_USE_EARLYSERIALINIT
+#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+# define CONFIG_USE_SERIALDRIVER 1
+# define CONFIG_USE_EARLYSERIALINIT 1
+#endif
+
+/* Check if an interrupt stack size is configured */
+
+#ifndef CONFIG_ARCH_INTERRUPTSTACK
+# define CONFIG_ARCH_INTERRUPTSTACK 0
+#endif
+
+/* Macros to handle saving and restore interrupt state. In the current CPU12
+ * model, the state is copied from the stack to the TCB, but only
+ * a referenced is passed to get the state from the TCB.
+ */
+
+#define up_savestate(regs) up_copystate(regs, current_regs)
+#define up_restorestate(regs) (current_regs = regs)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+typedef void (*up_vector_t)(void);
+#endif
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+/* This holds a references to the current interrupt level register storage
+ * structure. If is non-NULL only during interrupt processing.
+ */
+
+extern uint16 *current_regs;
+
+/* This is the beginning of heap as provided from processor-specific logic.
+ * This is the first address in RAM after the loaded program+bss+idle stack.
+ * The end of the heap is CONFIG_DRAM_END
+ */
+
+extern uint16 g_heapbase;
+
+/* Address of the saved user stack pointer */
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 1
+extern uint32 g_userstack;
+#endif
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/* Start-up functions */
+
+extern void up_boot(void);
+
+/* Context switching functions */
+
+extern void up_copystate(uint32 *dest, uint32 *src);
+extern void up_decodeirq(uint32 *regs);
+extern void up_irqinitialize(void);
+extern int up_saveusercontext(uint32 *saveregs);
+extern void up_fullcontextrestore(uint32 *restoreregs) __attribute__ ((noreturn));
+extern void up_switchcontext(uint32 *saveregs, uint32 *restoreregs);
+
+/* Interrupt handling */
+
+extern uint16 *up_doirq(int irq, uint32 *regs);
+extern void up_maskack_irq(int irq);
+
+/* Signal handling */
+
+extern void up_sigdeliver(void);
+
+/* System timer initialization */
+
+extern void up_timerinit(void);
+extern int up_timerisr(int irq, uint32 *regs);
+
+/* Debug output */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+extern void up_earlyserialinit(void);
+extern void up_serialinit(void);
+#else
+# define up_earlyserialinit()
+# define up_serialinit()
+#endif
+
+#ifdef CONFIG_DEV_LOWCONSOLE
+extern void lowconsole_init(void);
+#else
+# define lowconsole_init()
+#endif
+
+extern void up_lowputc(char ch);
+extern void up_puts(const char *str);
+extern void up_lowputs(const char *str);
+
+/* Memory configuration */
+
+#if CONFIG_MM_REGIONS > 1
+void up_addregion(void);
+#else
+# define up_addregion()
+#endif
+
+/* Sub-system/driver initialization */
+
+#ifdef CONFIG_ARCH_DMA
+extern void weak_function up_dmainitialize(void);
+#endif
+
+extern void up_wdtinit(void);
+
+#ifdef CONFIG_NET
+extern void up_netinitialize(void);
+#else
+# define up_netinitialize()
+#endif
+
+#ifdef CONFIG_USBDEV
+extern void up_usbinitialize(void);
+extern void up_usbuninitialize(void);
+#else
+# define up_usbinitialize()
+# define up_usbuninitialize()
+#endif
+
+/* Board-specific functions */
+
+#ifdef CONFIG_ARCH_LEDS
+extern void up_ledinit(void);
+extern void up_ledon(int led);
+extern void up_ledoff(int led);
+#else
+# define up_ledinit()
+# define up_ledon(led)
+# define up_ledoff(led)
+#endif
+
+#endif /* __ASSEMBLY__ */
+
+#endif /* __UP_INTERNAL_H */
diff --git a/nuttx/arch/hc/src/common/up_interruptcontext.c b/nuttx/arch/hc/src/common/up_interruptcontext.c
new file mode 100755
index 000000000..dec88f860
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_interruptcontext.c
@@ -0,0 +1,71 @@
+/****************************************************************************
+ * arch/hc/src/common/up_interruptcontext.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_interrupt_context
+ *
+ * Description: Return TRUE is we are currently executing in the interrupt
+ * handler context.
+ *
+ ****************************************************************************/
+
+boolean up_interrupt_context(void)
+{
+ return current_regs != NULL;
+}
diff --git a/nuttx/arch/hc/src/common/up_puts.c b/nuttx/arch/hc/src/common/up_puts.c
new file mode 100755
index 000000000..470d0ba59
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_puts.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * arch/hc/src/common/up_puts.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_puts
+ *
+ * Description:
+ * This is a low-level helper function used to support debug.
+ *
+ ****************************************************************************/
+
+void up_puts(const char *str)
+{
+ while(*str)
+ {
+ up_putc(*str++);
+ }
+}
diff --git a/nuttx/arch/hc/src/common/up_releasestack.c b/nuttx/arch/hc/src/common/up_releasestack.c
new file mode 100755
index 000000000..0bffef92e
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_releasestack.c
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/hc/src/common/up_releasestack.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include <sched.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_release_stack
+ *
+ * Description:
+ * A task has been stopped. Free all stack related resources retained in
+ * the defunct TCB.
+ *
+ ****************************************************************************/
+
+void up_release_stack(_TCB *dtcb)
+{
+ if (dtcb->stack_alloc_ptr)
+ {
+ sched_free(dtcb->stack_alloc_ptr);
+ dtcb->stack_alloc_ptr = NULL;
+ }
+
+ dtcb->adj_stack_size = 0;
+}
diff --git a/nuttx/arch/hc/src/common/up_usestack.c b/nuttx/arch/hc/src/common/up_usestack.c
new file mode 100755
index 000000000..c5eb6d8e5
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_usestack.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ * arch/hc/src/common/up_usestack.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sched.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_use_stack
+ *
+ * Description:
+ * Setup up stack-related information in the TCB using pre-allocated
+ * stack memory
+ *
+ * The following TCB fields must be initialized:
+ * adj_stack_size: Stack size after adjustment for hardware, processor, etc.
+ * This value is retained only for debug purposes.
+ * stack_alloc_ptr: Pointer to allocated stack
+ * adj_stack_ptr: Adjusted stack_alloc_ptr for HW. The initial value of the
+ * stack pointer.
+ *
+ * Inputs:
+ * tcb: The TCB of new task
+ * stack_size: The allocated stack size.
+ *
+ ****************************************************************************/
+
+STATUS up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
+{
+ size_t top_of_stack;
+ size_t size_of_stack;
+
+ if (tcb->stack_alloc_ptr && tcb->adj_stack_size != stack_size)
+ {
+ sched_free(tcb->stack_alloc_ptr);
+ tcb->stack_alloc_ptr = NULL;
+ }
+
+ /* Save the stack allocation */
+
+ tcb->stack_alloc_ptr = stack;
+
+ /* The CPU12 uses a push-down stack: the stack grows
+ * toward lower addresses in memory. Because the CPU12 stack
+ * operates as a decrement then store stack, the value assigned
+ * to the initial stack pointer is one more than the last valid
+ * stack address.
+ */
+
+ top_of_stack = (size_t)tcb->stack_alloc_ptr + stack_size;
+
+ /* The CPU12 stack should be aligned at half-word (2 byte)
+ * boundaries. If necessary top_of_stack must be rounded
+ * down to the next boundary
+ */
+
+ top_of_stack &= ~1;
+ size_of_stack = top_of_stack - (size_t)tcb->stack_alloc_ptr;
+
+ /* Save the adjusted stack values in the _TCB */
+
+ tcb->adj_stack_ptr = (uint32*)top_of_stack;
+ tcb->adj_stack_size = size_of_stack;
+ return OK;
+} \ No newline at end of file