aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch/rgmp
diff options
context:
space:
mode:
authorpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2011-12-19 19:24:09 +0000
committerpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2011-12-19 19:24:09 +0000
commitadd995c32e86f9de8fa8fc05172435332c25a895 (patch)
tree0191fde92a5c4dcd55a24b2aa760fa4c88713242 /nuttx/arch/rgmp
downloadpx4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.tar.gz
px4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.tar.bz2
px4-firmware-add995c32e86f9de8fa8fc05172435332c25a895.zip
Completes coding of the PWM module
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4200 7fd9a85b-ad96-42d3-883c-3090e2eb8679
Diffstat (limited to 'nuttx/arch/rgmp')
-rw-r--r--nuttx/arch/rgmp/include/arch.h64
-rw-r--r--nuttx/arch/rgmp/include/arm/arch/subarch/arch.h58
-rw-r--r--nuttx/arch/rgmp/include/irq.h76
-rw-r--r--nuttx/arch/rgmp/include/limits.h81
-rw-r--r--nuttx/arch/rgmp/include/math.h65
-rw-r--r--nuttx/arch/rgmp/include/stdbool.h89
-rw-r--r--nuttx/arch/rgmp/include/stdint.h277
-rw-r--r--nuttx/arch/rgmp/include/types.h96
-rw-r--r--nuttx/arch/rgmp/include/x86/arch/com.h58
-rw-r--r--nuttx/arch/rgmp/include/x86/arch/subarch/arch.h60
-rw-r--r--nuttx/arch/rgmp/src/Makefile104
-rw-r--r--nuttx/arch/rgmp/src/arm/Make.defs42
-rw-r--r--nuttx/arch/rgmp/src/arm/arch_nuttx.c91
-rw-r--r--nuttx/arch/rgmp/src/arm/sigentry.S49
-rw-r--r--nuttx/arch/rgmp/src/bridge.c104
-rw-r--r--nuttx/arch/rgmp/src/nuttx.c504
-rw-r--r--nuttx/arch/rgmp/src/rgmp.c168
-rw-r--r--nuttx/arch/rgmp/src/x86/Make.defs42
-rw-r--r--nuttx/arch/rgmp/src/x86/arch_nuttx.c106
-rw-r--r--nuttx/arch/rgmp/src/x86/com.c631
-rw-r--r--nuttx/arch/rgmp/src/x86/sigentry.S55
21 files changed, 2820 insertions, 0 deletions
diff --git a/nuttx/arch/rgmp/include/arch.h b/nuttx/arch/rgmp/include/arch.h
new file mode 100644
index 000000000..c93397baa
--- /dev/null
+++ b/nuttx/arch/rgmp/include/arch.h
@@ -0,0 +1,64 @@
+/****************************************************************************
+ * arch/rgmp/include/arch.h
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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 __RGMP_ARCH_ARCH_H
+#define __RGMP_ARCH_ARCH_H
+
+#include <arch/subarch/arch.h>
+
+#ifndef __ASSEMBLY__
+
+#include <nuttx/sched.h>
+
+
+struct up_wait {
+ struct up_wait *next;
+ _TCB *task;
+};
+
+extern _TCB *current_task;
+
+void up_sigentry(void);
+
+int up_register_bridge(char *name, int size);
+int up_unregister_bridge(char *name);
+
+#endif /* !__ASSEMBLY__ */
+
+#endif
diff --git a/nuttx/arch/rgmp/include/arm/arch/subarch/arch.h b/nuttx/arch/rgmp/include/arm/arch/subarch/arch.h
new file mode 100644
index 000000000..8b92c6bfe
--- /dev/null
+++ b/nuttx/arch/rgmp/include/arm/arch/subarch/arch.h
@@ -0,0 +1,58 @@
+/****************************************************************************
+ * arch/rgmp/include/arm/arch/subarch/arch.h
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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 __RGMP_ARCH_SUBARCH_ARCH_H
+#define __RGMP_ARCH_SUBARCH_ARCH_H
+
+#ifndef __ASSEMBLY__
+
+
+static inline void up_mdelay(uint32_t msec)
+{
+
+}
+
+static inline void up_udelay(uint32_t usec)
+{
+
+}
+
+#endif /* !__ASSEMBLY__ */
+
+#endif
diff --git a/nuttx/arch/rgmp/include/irq.h b/nuttx/arch/rgmp/include/irq.h
new file mode 100644
index 000000000..00c977560
--- /dev/null
+++ b/nuttx/arch/rgmp/include/irq.h
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * arch/rgmp/include/irq.h
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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 __ARCH_RGMP_INCLUDE_IRQ_H
+#define __ARCH_RGMP_INCLUDE_IRQ_H
+
+#define NR_IRQS 0
+
+#ifndef __ASSEMBLY__
+
+#include <rgmp/spinlock.h>
+#include <arch/types.h>
+#include <rgmp/trap.h>
+
+struct xcptcontext {
+ struct Trapframe *tf;
+ // for signal using
+ unsigned int save_eip;
+ unsigned int save_eflags;
+ void *sigdeliver;
+};
+
+void push_xcptcontext(struct xcptcontext *xcp);
+void pop_xcptcontext(struct xcptcontext *xcp);
+
+extern int nest_irq;
+
+static inline irqstate_t irqsave(void)
+{
+ return pushcli();
+}
+
+static inline void irqrestore(irqstate_t flags)
+{
+ popcli(flags);
+}
+
+#endif /* !__ASSEMBLY__ */
+
+#endif
diff --git a/nuttx/arch/rgmp/include/limits.h b/nuttx/arch/rgmp/include/limits.h
new file mode 100644
index 000000000..855836660
--- /dev/null
+++ b/nuttx/arch/rgmp/include/limits.h
@@ -0,0 +1,81 @@
+/************************************************************
+ * arch/rgmp/include/limits.h
+ *
+ * Copyright (C) 2011 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 Gregory Nutt 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 __ARCH_RGMP_INCLUDE_LIMITS_H
+#define __ARCH_RGMP_INCLUDE_LIMITS_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN 0x80
+#define SCHAR_MAX 0x7f
+#define UCHAR_MAX 0xff
+
+/* These could be different on machines where char is unsigned */
+
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+
+#define SHRT_MIN 0x8000
+#define SHRT_MAX 0x7fff
+#define USHRT_MAX 0xffff
+
+#define INT_MIN 0x80000000
+#define INT_MAX 0x7fffffff
+#define UINT_MAX 0xffffffff
+
+/* These change on 32-bit and 64-bit platforms */
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#define LLONG_MAX 0x8000000000000000
+#define LLONG_MIN 0x7fffffffffffffff
+#define ULLONG_MAX 0xffffffffffffffff
+
+/* A pointer is 4 bytes */
+
+#define PTR_MIN 0x80000000
+#define PTR_MAX 0x7fffffff
+#define UPTR_MAX 0xffffffff
+
+#endif /* __ARCH_RGMP_INCLUDE_LIMITS_H */
diff --git a/nuttx/arch/rgmp/include/math.h b/nuttx/arch/rgmp/include/math.h
new file mode 100644
index 000000000..55f24aaa4
--- /dev/null
+++ b/nuttx/arch/rgmp/include/math.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ * arch/rgmp/include/math.h
+ *
+ * Copyright (C) 2011 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 __ARCH_RGMP_INCLUDE_MATH_H
+#define __ARCH_RGMP_INCLUDE_MATH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#include <rgmp/math.h>
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_RGMP_INCLUDE_MATH_H */
diff --git a/nuttx/arch/rgmp/include/stdbool.h b/nuttx/arch/rgmp/include/stdbool.h
new file mode 100644
index 000000000..4af9ec9e3
--- /dev/null
+++ b/nuttx/arch/rgmp/include/stdbool.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * arch/rgmp/include/stdbool.h
+ *
+ * Copyright (C) 2009, 2011 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 __ARCH_RGMP_INCLUDE_STDBOOL_H
+#define __ARCH_RGMP_INCLUDE_STDBOOL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* bool, true, and false must be provided as macros so that they can be
+ * redefined by the application if necessary.
+ *
+ * NOTE: Under C99 'bool' is required to be defined to be the intrinsic type
+ * _Bool. However, in this NuttX context, we need backward compatibility
+ * to pre-C99 standards where _Bool is not an intrinsic type. Hence, we
+ * use _Bool8 as the underlying type.
+ */
+
+#ifndef CONFIG_ARCH_RGMP
+#define bool _Bool8
+#endif
+#define true 1
+#define false 0
+
+#define __bool_true_false_are_defined 1
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* A byte is the smallest address memory element (at least in architectures
+ * that do not support bit banding). The requirement is only that type _Bool
+ * be large enough to hold the values 0 and 1. We select uint8_t to minimize
+ * the RAM footprint of the executable.
+ *
+ * NOTE: We can't actually define the type _Bool here. Under C99 _Bool is
+ * an intrinsic type and cannot be the target of a typedef. However, in this
+ * NuttX context, we also need backward compatibility to pre-C99 standards
+ * where _Bool is not an intrinsic type. We work around this by using _Bool8
+ * as the underlying type.
+ */
+
+#ifndef CONFIG_ARCH_RGMP
+typedef uint8_t _Bool8;
+#endif
+
+#endif /* __ARCH_RGMP_INCLUDE_STDBOOL_H */
diff --git a/nuttx/arch/rgmp/include/stdint.h b/nuttx/arch/rgmp/include/stdint.h
new file mode 100644
index 000000000..7b244dd9f
--- /dev/null
+++ b/nuttx/arch/rgmp/include/stdint.h
@@ -0,0 +1,277 @@
+/****************************************************************************
+ * arch/rgmp/include/stdint.h
+ *
+ * Copyright (C) 2009, 2011 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 __ARCH_RGMP_INCLUDE_STDINTL_H
+#define __ARCH_RGMP_INCLUDE_STDINTL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+#include <arch/types.h>
+#include <limits.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Limits of exact-width integer types */
+
+#define INT8_MIN 0x80
+#define INT8_MAX 0x7f
+#define UINT8_MAX 0xff
+
+#define INT16_MIN 0x8000
+#define INT16_MAX 0x7fff
+#define UINT16_MAX 0xffff
+
+#ifdef __INT64_DEFINED
+# define INT24_MIN 0x800000
+# define INT24_MAX 0x7fffff
+# define UINT24_MAX 0xffffff
+#endif
+
+#define INT32_MIN 0x80000000
+#define INT32_MAX 0x7fffffff
+#define UINT32_MAX 0xffffffff
+
+#ifdef __INT64_DEFINED
+# define INT64_MIN 0x8000000000000000
+# define INT64_MAX 0x7fffffffffffffff
+# define UINT64_MAX 0xffffffffffffffff
+#endif
+
+/* Limits of minimum-width integer types */
+
+#define INT8_LEASTN_MIN 0x80
+#define INT8_LEASTN_MAX 0x7f
+#define UINT8_LEASTN_MAX 0xff
+
+#define INT16_LEASTN_MIN 0x8000
+#define INT16_LEASTN_MAX 0x7fff
+#define UINT16_LEASTN_MAX 0xffff
+
+#ifdef __INT64_DEFINED
+# define INT24_LEASTN_MIN 0x800000
+# define INT24_LEASTN_MAX 0x7fffff
+# define UINT24_LEASTN_MAX 0xffffff
+#endif
+
+#define INT32_LEASTN_MIN 0x80000000
+#define INT32_LEASTN_MAX 0x7fffffff
+#define UINT32_LEASTN_MAX 0xffffffff
+
+#ifdef __INT64_DEFINED
+# define INT64_LEASTN_MIN 0x8000000000000000
+# define INT64_LEASTN_MAX 0x7fffffffffffffff
+# define UINT64_LEASTN_MAX 0xffffffffffffffff
+#endif
+
+/* Limits of fastest minimum-width integer types */
+
+#define INT8_FASTN_MIN 0x80
+#define INT8_FASTN_MAX 0x7f
+#define UINT8_FASTN_MAX 0xff
+
+#define INT16_FASTN_MIN 0x8000
+#define INT16_FASTN_MAX 0x7fff
+#define UINT16_FASTN_MAX 0xffff
+
+#ifdef __INT64_DEFINED
+# define INT24_FASTN_MIN 0x800000
+# define INT24_FASTN_MAX 0x7fffff
+# define UINT24_FASTN_MAX 0xffffff
+#endif
+
+#define INT32_FASTN_MIN 0x80000000
+#define INT32_FASTN_MAX 0x7fffffff
+#define UINT32_FASTN_MAX 0xffffffff
+
+#ifdef __INT64_DEFINED
+# define INT64_FASTN_MIN 0x8000000000000000
+# define INT64_FASTN_MAX 0x7fffffffffffffff
+# define UINT64_FASTN_MAX 0xffffffffffffffff
+#endif
+
+/* Limits of integer types capable of holding object pointers */
+
+#define INTPTR_MIN PTR_MIN
+#define INTPTR_MAX PTR_MIN
+#define UINTPTR_MAX UPTR_MAX
+
+/* Limits of greatest-width integer types */
+
+#ifdef __INT64_DEFINED
+# define INTMAX_MIN INT64_MIN
+# define INTMAX_MAX INT64_MAX
+
+# define UINTMAX_MIN UINT64_MIN
+# define UINTMAX_MAX UINT64_MAX
+#else
+# define INTMAX_MIN INT32_MIN
+# define INTMAX_MAX INT32_MAX
+
+# define UINTMAX_MIN UINT32_MIN
+# define UINTMAX_MAX UINT32_MAX
+#endif
+
+/* Macros for minimum-width integer constant expressions */
+
+#if 0 /* REVISIT: Depends on architecture specific implementation */
+#define INT8_C(x) x
+#define INT16_C(x) x
+#define INT32_C(x) x ## L
+#define INT64_C(x) x ## LL
+
+#define UINT8_C(x) x
+#define UINT16_C(x) x
+#define UINT32_C(x) x ## UL
+#define UINT64_C(x) x ## ULL
+#endif
+
+/* Macros for greatest-width integer constant expressions
+
+#ifdef CONFIG_HAVE_LONG_LONG
+# define INTMAX_C(x) x ## LL
+# define UINTMAX_C(x) x ## ULL
+#else
+# define INTMAX_C(x) x ## L
+# define UINTMAX_C(x) x ## UL
+#endif
+
+/* Limits of Other Integer Types */
+
+#if 0
+# define PTRDIFF_MIN
+# define PTRDIFF_MAX
+#endif
+
+#ifdef CONFIG_SMALL_MEMORY
+# define SIZE_MAX 0xffff
+#else
+# define SIZE_MAX 0xffffffff
+#endif
+
+#if 0
+# define WCHAR_MIN
+# define WCHAR_MAX
+
+# define WINT_MIN
+# define WINT_MAX
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Exact-width integer types. NOTE that these types are defined in
+ * architecture-specific logic with leading underscore character. This file
+ * typedef's these to the final name without the underscore character. This
+ * roundabout way of doings things allows the stdint.h to be removed from the
+ * include/ directory in the event that the user prefers to use the definitions
+ * provided by their toolchain header files.
+ */
+
+#include <rgmp/types.h>
+
+/* Minimum-width integer types */
+
+typedef _int8_t int_least8_t;
+typedef _uint8_t uint_least8_t;
+
+typedef _int16_t int_least16_t;
+typedef _uint16_t uint_least16_t;
+
+#ifdef __INT24_DEFINED
+typedef _int24_t int_least24_t;
+typedef _uint24_t uint_least24_t;
+#else
+typedef _int32_t int_least24_t;
+typedef _uint32_t uint_least24_t;
+#endif
+
+typedef _int32_t int_least32_t;
+typedef _uint32_t uint_least32_t;
+
+#ifdef __INT64_DEFINED
+typedef _int64_t int_least64_t;
+typedef _uint64_t uint_least64_t;
+#endif
+
+/* Fastest minimum-width integer types */
+
+typedef _int8_t int_fast8_t;
+typedef _uint8_t uint_fast8_t;
+
+typedef int int_fast16_t;
+typedef unsigned int uint_fast16_t;
+
+#ifdef __INT24_DEFINED
+typedef _int24_t int_fast24_t;
+typedef _uint24_t uint_fast24_t;
+#else
+typedef _int32_t int_fast24_t;
+typedef _uint32_t uint_fast24_t;
+#endif
+
+typedef _int32_t int_fast32_t;
+typedef _uint32_t uint_fast32_t;
+
+#ifdef __INT64_DEFINED
+typedef _int64_t int_fast64_t;
+typedef _uint64_t uint_fast64_t;
+#endif
+
+/* Integer types capable of holding object pointers */
+
+#ifndef CONFIG_ARCH_RGMP
+typedef _intptr_t intptr_t;
+typedef _uintptr_t uintptr_t;
+#endif
+
+/* Greatest-width integer types */
+
+#ifdef __INT64_DEFINED
+typedef _int64_t intmax_t;
+typedef _uint64_t uintmax_t;
+#else
+typedef _int32_t intmax_t;
+typedef _uint32_t uintmax_t;
+#endif
+
+#endif /* __ARCH_RGMP_INCLUDE_STDINTL_H */
diff --git a/nuttx/arch/rgmp/include/types.h b/nuttx/arch/rgmp/include/types.h
new file mode 100644
index 000000000..48e141db3
--- /dev/null
+++ b/nuttx/arch/rgmp/include/types.h
@@ -0,0 +1,96 @@
+/************************************************************************
+ * arch/rgmp/include/types.h
+ *
+ * Copyright (C) 2011 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 Gregory Nutt 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.
+ *
+ ************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through sys/types.h
+ */
+
+#ifndef __ARCH_RGMP_INCLUDE_TYPES_H
+#define __ARCH_RGMP_INCLUDE_TYPES_H
+
+/************************************************************************
+ * Included Files
+ ************************************************************************/
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Type Declarations
+ ************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard integer types. NOTE that these type
+ * names have a leading underscore character. This file will be included
+ * (indirectly) by include/stdint.h and typedef'ed to the final name without
+ * the underscore character. This roundabout way of doings things allows
+ * the stdint.h to be removed from the include/ directory in the event that
+ * the user prefers to use the definitions provided by their toolchain header
+ * files
+ */
+
+typedef char _int8_t;
+typedef unsigned char _uint8_t;
+
+typedef short _int16_t;
+typedef unsigned short _uint16_t;
+
+typedef int _int32_t;
+typedef unsigned int _uint32_t;
+
+typedef long long _int64_t;
+typedef unsigned long long _uint64_t;
+#define __INT64_DEFINED
+
+/* A pointer is 4 bytes */
+
+typedef unsigned int _intptr_t;
+typedef unsigned int _uintptr_t;
+
+/* This is the size of the interrupt state save returned by
+ * irqsave()
+ */
+
+typedef unsigned int irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/************************************************************************
+ * Global Function Prototypes
+ ************************************************************************/
+
+#endif /* __ARCH_RGMP_INCLUDE_TYPES_H */
diff --git a/nuttx/arch/rgmp/include/x86/arch/com.h b/nuttx/arch/rgmp/include/x86/arch/com.h
new file mode 100644
index 000000000..89df901bb
--- /dev/null
+++ b/nuttx/arch/rgmp/include/x86/arch/com.h
@@ -0,0 +1,58 @@
+/****************************************************************************
+ * arch/rgmp/include/com.h
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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 __ARCH_RGMP_INCLUDE_COM_H
+#define __ARCH_RGMP_INCLUDE_COM_H
+
+#define COM_SET_BAUD 1
+#define COM_SET_PARITY 2
+#define COM_NO_PARITY 0
+#define COM_ODD_PARITY 1
+#define COM_EVEN_PARITY 3
+#define COM_SET_STOPBITS 3
+#define COM_ONE_STOPBITS 0
+#define COM_TWO_STOPBITS 1
+#define COM_SET_BITS 4
+#define COM_8_BITS 3
+#define COM_7_BITS 2
+#define COM_6_BITS 1
+#define COM_5_BITS 0
+
+
+#endif
diff --git a/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h b/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h
new file mode 100644
index 000000000..2f401c03b
--- /dev/null
+++ b/nuttx/arch/rgmp/include/x86/arch/subarch/arch.h
@@ -0,0 +1,60 @@
+/****************************************************************************
+ * arch/rgmp/include/x86/arch/subarch/arch.h
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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 __RGMP_ARCH_SUBARCH_ARCH_H
+#define __RGMP_ARCH_SUBARCH_ARCH_H
+
+#ifndef __ASSEMBLY__
+
+#include <rgmp/arch/hpet.h>
+
+
+static inline void up_mdelay(uint32_t msec)
+{
+ hpet_ndelay(msec*1000000);
+}
+
+static inline void up_udelay(uint32_t usec)
+{
+ hpet_udelay(usec*1000);
+}
+
+#endif /* !__ASSEMBLY__ */
+
+#endif
diff --git a/nuttx/arch/rgmp/src/Makefile b/nuttx/arch/rgmp/src/Makefile
new file mode 100644
index 000000000..f973a28fa
--- /dev/null
+++ b/nuttx/arch/rgmp/src/Makefile
@@ -0,0 +1,104 @@
+############################################################################
+# arch/rgmp/src/Makefile
+#
+# Copyright (C) 2011 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+include $(CONFIG_RGMP_SUBARCH)/Make.defs
+
+RGMP_ARCH_ASRCS := $(addprefix $(CONFIG_RGMP_SUBARCH)/,$(RGMP_ARCH_ASRCS))
+RGMP_ARCH_CSRCS := $(addprefix $(CONFIG_RGMP_SUBARCH)/,$(RGMP_ARCH_CSRCS))
+
+CFLAGS += -I$(TOPDIR)/sched -I$(TOPDIR)/fs
+
+ASRCS = $(RGMP_ARCH_ASRCS)
+CSRCS = nuttx.c rgmp.c bridge.c $(RGMP_ARCH_CSRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+LDFLAGS += -T$(RGMPLKSCPT)
+LDPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
+LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
+LDPATHS += -L$(RGMPLIBDIR)
+LDLIBS += -lrgmp -lm -ltest $(shell gcc -print-libgcc-file-name)
+
+all: libarch$(LIBEXT)
+.PHONY: clean distclean depend
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+# The architecture-specific library
+libarch$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+# Generate the final NuttX binary by linking the host-specific objects with the NuttX
+# specific objects (with munged names)
+
+nuttx$(EXEEXT):
+ @echo "LD: nuttx$(EXEEXT)"
+ @$(LD) $(LDFLAGS) $(LDPATHS) --start-group $(LDLIBS) --end-group -o $(TOPDIR)/$@
+ @$(OBJDUMP) -S $(TOPDIR)/$@ > $(TOPDIR)/nuttx.asm
+ @$(NM) -n $(TOPDIR)/$@ > $(TOPDIR)/nuttx.sym
+ @$(OBJCOPY) -S -O binary $(TOPDIR)/$@ nuttx.img
+ @cp nuttx.img $(TOPDIR)/kernel.img
+
+# This is part of the top-level export target
+
+export_head:
+
+# Dependencies
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm $(TOPDIR)/kernel.img nuttx.img
+ @rm -f libarch$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/arch/rgmp/src/arm/Make.defs b/nuttx/arch/rgmp/src/arm/Make.defs
new file mode 100644
index 000000000..8185980c6
--- /dev/null
+++ b/nuttx/arch/rgmp/src/arm/Make.defs
@@ -0,0 +1,42 @@
+############################################################################
+# rgmp/arm/Make.defs
+#
+# Copyright (C) 2011 Yu Qiang. All rights reserved.
+# Author: Yu Qiang <yuq825@gmail.com>
+#
+# This file is a part of NuttX:
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+#
+#
+# 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 Gregory Nutt 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.
+#
+############################################################################
+
+RGMP_ARCH_ASRCS = sigentry.S
+RGMP_ARCH_CSRCS = arch_nuttx.c
diff --git a/nuttx/arch/rgmp/src/arm/arch_nuttx.c b/nuttx/arch/rgmp/src/arm/arch_nuttx.c
new file mode 100644
index 000000000..cb946bfd1
--- /dev/null
+++ b/nuttx/arch/rgmp/src/arm/arch_nuttx.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * arch/rgmp/src/arm/arch_nuttx.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <rgmp/mmu.h>
+#include <rgmp/string.h>
+
+#include <arch/arch.h>
+#include <nuttx/sched.h>
+#include <os_internal.h>
+
+
+void nuttx_arch_init(void)
+{
+
+}
+
+void nuttx_arch_exit(void)
+{
+
+}
+
+void up_initial_state(_TCB *tcb)
+{
+ struct Trapframe *tf;
+
+ if (tcb->pid != 0) {
+ tf = (struct Trapframe *)tcb->adj_stack_ptr-1;
+ memset(tf, 0, sizeof(struct Trapframe));
+ tf->tf_cpsr = SVC_MOD;
+ tf->tf_pc = (uint32_t)tcb->start;
+ tcb->xcp.tf = tf;
+ }
+}
+
+void push_xcptcontext(struct xcptcontext *xcp)
+{
+ xcp->save_eip = xcp->tf->tf_pc;
+ xcp->save_eflags = xcp->tf->tf_cpsr;
+
+ // set interrupts disabled
+ xcp->tf->tf_pc = (uint32_t)up_sigentry;
+ xcp->tf->tf_cpsr |= CPSR_IF;
+}
+
+void pop_xcptcontext(struct xcptcontext *xcp)
+{
+ xcp->tf->tf_pc = xcp->save_eip;
+ xcp->tf->tf_cpsr = xcp->save_eflags;
+}
+
+void raise(void)
+{
+
+}
+
diff --git a/nuttx/arch/rgmp/src/arm/sigentry.S b/nuttx/arch/rgmp/src/arm/sigentry.S
new file mode 100644
index 000000000..1e413450b
--- /dev/null
+++ b/nuttx/arch/rgmp/src/arm/sigentry.S
@@ -0,0 +1,49 @@
+/****************************************************************************
+ * arch/rgmp/src/arm/sigentry.S
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+ .globl up_sigentry
+up_sigentry:
+ sub sp, sp, #68 @ 68 is the size of Trapframe
+ mov r0, sp
+ bl up_sigdeliver
+ add sp, sp, #4 @ skip current_task
+ pop {r0-r12, lr}
+ rfefd sp!
+
+ \ No newline at end of file
diff --git a/nuttx/arch/rgmp/src/bridge.c b/nuttx/arch/rgmp/src/bridge.c
new file mode 100644
index 000000000..7dcaf90f1
--- /dev/null
+++ b/nuttx/arch/rgmp/src/bridge.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * arch/rgmp/src/bridge.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <sys/types.h>
+#include <stdbool.h>
+#include <nuttx/fs.h>
+#include <nuttx/kmalloc.h>
+#include <fs_internal.h>
+#include <queue.h>
+#include <arch/irq.h>
+#include <rgmp/bridge.h>
+#include <rgmp/string.h>
+#include <rgmp/stdio.h>
+
+
+static ssize_t up_bridge_read(struct file *filp, char *buffer, size_t len)
+{
+ struct rgmp_bridge *b;
+
+ b = filp->f_inode->i_private;
+ return rgmp_bridge_read(b, buffer, len);
+}
+
+static ssize_t up_bridge_write(struct file *filp, const char *buffer, size_t len)
+{
+ struct rgmp_bridge *b;
+
+ b = filp->f_inode->i_private;
+ return rgmp_bridge_write(b, (char *)buffer, len);
+}
+
+static int up_bridge_open(struct file *filp)
+{
+ return 0;
+}
+
+static int up_bridge_close(struct file *filp)
+{
+ return 0;
+}
+
+static const struct file_operations up_bridge_fops =
+{
+ .read = up_bridge_read,
+ .write = up_bridge_write,
+ .open = up_bridge_open,
+ .close = up_bridge_close,
+};
+
+void up_register_bridges(void)
+{
+ int err;
+ char path[30] = {'/', 'd', 'e', 'v', '/'};
+ struct rgmp_bridge *b;
+
+ for (b=bridge_list.next; b!=NULL; b=b->next) {
+ // make rgmp_bridge0 to be the console
+ if (strcmp(b->vdev->name, "rgmp_bridge0") == 0)
+ strlcpy(path+5, "console", 25);
+ else
+ strlcpy(path+5, b->vdev->name, 25);
+ err = register_driver(path, &up_bridge_fops, 0666, b);
+ if (err == ERROR)
+ cprintf("NuttX: register bridge %s fail\n", b->vdev->name);
+ }
+}
+
+
diff --git a/nuttx/arch/rgmp/src/nuttx.c b/nuttx/arch/rgmp/src/nuttx.c
new file mode 100644
index 000000000..14b3e6d1d
--- /dev/null
+++ b/nuttx/arch/rgmp/src/nuttx.c
@@ -0,0 +1,504 @@
+/****************************************************************************
+ * arch/rgmp/src/nuttx.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <rgmp/boot.h>
+#include <rgmp/pmap.h>
+#include <rgmp/assert.h>
+#include <rgmp/spinlock.h>
+#include <rgmp/string.h>
+
+#include <rgmp/arch/arch.h>
+#include <rgmp/arch/console.h>
+
+#include <nuttx/sched.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <arch/irq.h>
+#include <arch/arch.h>
+#include <os_internal.h>
+
+_TCB *current_task = NULL;
+
+
+/**
+ * This function is called in non-interrupt context
+ * to switch tasks.
+ * Assumption: global interrupt is disabled.
+ */
+static inline void up_switchcontext(_TCB *ctcb, _TCB *ntcb)
+{
+ // do nothing if two tasks are the same
+ if (ctcb == ntcb)
+ return;
+
+ // this function can not be called in interrupt
+ if (up_interrupt_context()) {
+ panic("%s: try to switch context in interrupt\n", __func__);
+ }
+
+ // start switch
+ current_task = ntcb;
+ rgmp_context_switch(ctcb?&ctcb->xcp.tf:NULL, ntcb->xcp.tf);
+}
+
+void up_initialize(void)
+{
+ extern pidhash_t g_pidhash[];
+ extern void up_register_bridges(void);
+ extern void vnet_initialize(void);
+ extern void nuttx_arch_init(void);
+
+ // intialize the current_task to g_idletcb
+ current_task = g_pidhash[PIDHASH(0)].tcb;
+
+ // setup console
+ up_register_bridges();
+
+#ifdef CONFIG_NET_VNET
+ // setup vnet device
+ vnet_initialize();
+#endif
+
+ nuttx_arch_init();
+
+ // enable interrupt
+ local_irq_enable();
+}
+
+void up_idle(void)
+{
+ arch_hlt();
+}
+
+void up_allocate_heap(void **heap_start, size_t *heap_size)
+{
+ *heap_start = boot_freemem;
+ *heap_size = KERNBASE + boot_param.mem_size - (uint32_t)boot_freemem;
+}
+
+int up_create_stack(_TCB *tcb, size_t stack_size)
+{
+ int ret = ERROR;
+ size_t *adj_stack_ptr;
+
+ /* Move up to next even word boundary if necessary */
+
+ size_t adj_stack_size = (stack_size + 3) & ~3;
+ size_t adj_stack_words = adj_stack_size >> 2;
+
+ /* Allocate the memory for the stack */
+
+ uint32_t *stack_alloc_ptr = (uint32_t*)kmalloc(adj_stack_size);
+ if (stack_alloc_ptr) {
+ /* This is the address of the last word in the allocation */
+
+ adj_stack_ptr = &stack_alloc_ptr[adj_stack_words - 1];
+
+ /* Save the values in the TCB */
+
+ tcb->adj_stack_size = adj_stack_size;
+ tcb->stack_alloc_ptr = stack_alloc_ptr;
+ tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7);
+ ret = OK;
+ }
+ return ret;
+}
+
+int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
+{
+ /* Move up to next even word boundary if necessary */
+
+ size_t adj_stack_size = stack_size & ~3;
+ size_t adj_stack_words = adj_stack_size >> 2;
+
+ /* This is the address of the last word in the allocation */
+
+ size_t *adj_stack_ptr = &((size_t*)stack)[adj_stack_words - 1];
+
+ /* Save the values in the TCB */
+
+ tcb->adj_stack_size = adj_stack_size;
+ tcb->stack_alloc_ptr = stack;
+ tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7);
+ return OK;
+}
+
+void up_release_stack(_TCB *dtcb)
+{
+ if (dtcb->stack_alloc_ptr) {
+ free(dtcb->stack_alloc_ptr);
+ }
+
+ dtcb->stack_alloc_ptr = NULL;
+ dtcb->adj_stack_size = 0;
+ dtcb->adj_stack_ptr = NULL;
+}
+
+/****************************************************************************
+ * Name: up_block_task
+ *
+ * Description:
+ * The currently executing task at the head of
+ * the ready to run list must be stopped. Save its context
+ * and move it to the inactive list specified by task_state.
+ *
+ * This function is called only from the NuttX scheduling
+ * logic. Interrupts will always be disabled when this
+ * function is called.
+ *
+ * Inputs:
+ * tcb: Refers to a task in the ready-to-run list (normally
+ * the task at the head of the list). It most be
+ * stopped, its context saved and moved into one of the
+ * waiting task lists. It it was the task at the head
+ * of the ready-to-run list, then a context to the new
+ * ready to run task must be performed.
+ * task_state: Specifies which waiting task list should be
+ * hold the blocked task TCB.
+ *
+ ****************************************************************************/
+void up_block_task(_TCB *tcb, tstate_t task_state)
+{
+ /* Verify that the context switch can be performed */
+ if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) ||
+ (tcb->task_state > LAST_READY_TO_RUN_STATE)) {
+ warn("%s: task sched error\n", __func__);
+ return;
+ }
+ else {
+ _TCB *rtcb = current_task;
+ bool switch_needed;
+
+ /* Remove the tcb task from the ready-to-run list. If we
+ * are blocking the task at the head of the task list (the
+ * most likely case), then a context switch to the next
+ * ready-to-run task is needed. In this case, it should
+ * also be true that rtcb == tcb.
+ */
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Add the task to the specified blocked task list */
+ sched_addblocked(tcb, (tstate_t)task_state);
+
+ /* Now, perform the context switch if one is needed */
+ if (switch_needed) {
+ _TCB *nexttcb;
+ // this part should not be executed in interrupt context
+ if (up_interrupt_context()) {
+ panic("%s: %d\n", __func__, __LINE__);
+ }
+ // If there are any pending tasks, then add them to the g_readytorun
+ // task list now. It should be the up_realease_pending() called from
+ // sched_unlock() to do this for disable preemption. But it block
+ // itself, so it's OK.
+ if (g_pendingtasks.head) {
+ warn("Disable preemption failed for task block itself\n");
+ sched_mergepending();
+ }
+ nexttcb = (_TCB*)g_readytorun.head;
+ // context switch
+ up_switchcontext(rtcb, nexttcb);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: up_unblock_task
+ *
+ * Description:
+ * A task is currently in an inactive task list
+ * but has been prepped to execute. Move the TCB to the
+ * ready-to-run list, restore its context, and start execution.
+ *
+ * Inputs:
+ * tcb: Refers to the tcb to be unblocked. This tcb is
+ * in one of the waiting tasks lists. It must be moved to
+ * the ready-to-run list and, if it is the highest priority
+ * ready to run taks, executed.
+ *
+ ****************************************************************************/
+void up_unblock_task(_TCB *tcb)
+{
+ /* Verify that the context switch can be performed */
+ if ((tcb->task_state < FIRST_BLOCKED_STATE) ||
+ (tcb->task_state > LAST_BLOCKED_STATE)) {
+ warn("%s: task sched error\n", __func__);
+ return;
+ }
+ else {
+ _TCB *rtcb = current_task;
+
+ /* Remove the task from the blocked task list */
+ sched_removeblocked(tcb);
+
+ /* Reset its timeslice. This is only meaningful for round
+ * robin tasks but it doesn't here to do it for everything
+ */
+#if CONFIG_RR_INTERVAL > 0
+ tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK;
+#endif
+
+ // Add the task in the correct location in the prioritized
+ // g_readytorun task list.
+ if (sched_addreadytorun(tcb) && !up_interrupt_context()) {
+ /* The currently active task has changed! */
+ _TCB *nexttcb = (_TCB*)g_readytorun.head;
+ // context switch
+ up_switchcontext(rtcb, nexttcb);
+ }
+ }
+}
+
+/**
+ * This function is called from sched_unlock() which will check not
+ * in interrupt context and disable interrupt.
+ */
+void up_release_pending(void)
+{
+ _TCB *rtcb = current_task;
+
+ /* Merge the g_pendingtasks list into the g_readytorun task list */
+
+ if (sched_mergepending()) {
+ /* The currently active task has changed! */
+ _TCB *nexttcb = (_TCB*)g_readytorun.head;
+
+ // context switch
+ up_switchcontext(rtcb, nexttcb);
+ }
+}
+
+void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
+{
+ /* Verify that the caller is sane */
+
+ if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > UINT8_MIN
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ ) {
+ warn("%s: task sched error\n", __func__);
+ return;
+ }
+ else {
+ _TCB *rtcb = current_task;
+ bool switch_needed;
+
+ /* Remove the tcb task from the ready-to-run list.
+ * sched_removereadytorun will return true if we just
+ * remove the head of the ready to run list.
+ */
+ switch_needed = sched_removereadytorun(tcb);
+
+ /* Setup up the new task priority */
+ tcb->sched_priority = (uint8_t)priority;
+
+ /* Return the task to the specified blocked task list.
+ * sched_addreadytorun will return true if the task was
+ * added to the new list. We will need to perform a context
+ * switch only if the EXCLUSIVE or of the two calls is non-zero
+ * (i.e., one and only one the calls changes the head of the
+ * ready-to-run list).
+ */
+ switch_needed ^= sched_addreadytorun(tcb);
+
+ /* Now, perform the context switch if one is needed */
+ if (switch_needed && !up_interrupt_context()) {
+ _TCB *nexttcb;
+ // If there are any pending tasks, then add them to the g_readytorun
+ // task list now. It should be the up_realease_pending() called from
+ // sched_unlock() to do this for disable preemption. But it block
+ // itself, so it's OK.
+ if (g_pendingtasks.head) {
+ warn("Disable preemption failed for reprioritize task\n");
+ sched_mergepending();
+ }
+
+ nexttcb = (_TCB*)g_readytorun.head;
+ // context switch
+ up_switchcontext(rtcb, nexttcb);
+ }
+ }
+}
+
+void _exit(int status)
+{
+ _TCB* tcb;
+
+ /* Destroy the task at the head of the ready to run list. */
+
+ (void)task_deletecurrent();
+
+ /* Now, perform the context switch to the new ready-to-run task at the
+ * head of the list.
+ */
+
+ tcb = (_TCB*)g_readytorun.head;
+
+ /* Then switch contexts */
+
+ up_switchcontext(NULL, tcb);
+}
+
+void up_assert(const uint8_t *filename, int line)
+{
+ fprintf(stderr, "Assertion failed at file:%s line: %d\n", filename, line);
+
+ // in interrupt context or idle task means kernel error
+ // which will stop the OS
+ // if in user space just terminate the task
+ if (up_interrupt_context() || current_task->pid == 0) {
+ panic("%s: %d\n", __func__, __LINE__);
+ }
+ else {
+ exit(EXIT_FAILURE);
+ }
+}
+
+void up_assert_code(const uint8_t *filename, int line, int code)
+{
+ fprintf(stderr, "Assertion failed at file:%s line: %d error code: %d\n",
+ filename, line, code);
+
+ // in interrupt context or idle task means kernel error
+ // which will stop the OS
+ // if in user space just terminate the task
+ if (up_interrupt_context() || current_task->pid == 0) {
+ panic("%s: %d\n", __func__, __LINE__);
+ }
+ else {
+ exit(EXIT_FAILURE);
+ }
+}
+
+
+#ifndef CONFIG_DISABLE_SIGNALS
+
+void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
+{
+ /* Refuse to handle nested signal actions */
+ if (!tcb->xcp.sigdeliver) {
+ int flags;
+
+ /* Make sure that interrupts are disabled */
+ flags = pushcli();
+
+ // First, handle some special cases when the signal is
+ // being delivered to the currently executing task.
+ if (tcb == current_task) {
+ // CASE 1: We are not in an interrupt handler and
+ // a task is signalling itself for some reason.
+ if (!up_interrupt_context()) {
+ // In this case just deliver the signal now.
+ sigdeliver(tcb);
+ }
+ // CASE 2: We are in an interrupt handler AND the
+ // interrupted task is the same as the one that
+ // must receive the signal.
+ else {
+ tcb->xcp.sigdeliver = sigdeliver;
+ }
+ }
+
+ // Otherwise, we are (1) signaling a task is not running
+ // from an interrupt handler or (2) we are not in an
+ // interrupt handler and the running task is signalling
+ // some non-running task.
+ else {
+ tcb->xcp.sigdeliver = sigdeliver;
+ push_xcptcontext(&tcb->xcp);
+ }
+
+ popcli(flags);
+ }
+}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
+
+
+bool up_interrupt_context(void)
+{
+ if (nest_irq)
+ return true;
+ return false;
+}
+
+#ifndef CONFIG_ARCH_NOINTC
+void up_disable_irq(int irq)
+{
+
+}
+
+void up_enable_irq(int irq)
+{
+
+}
+#endif
+
+#ifdef CONFIG_ARCH_IRQPRIO
+int up_prioritize_irq(int irq, int priority)
+{
+
+}
+#endif
+
+void up_sigdeliver(struct Trapframe *tf)
+{
+ sig_deliver_t sigdeliver;
+
+ pop_xcptcontext(&current_task->xcp);
+ sigdeliver = current_task->xcp.sigdeliver;
+ current_task->xcp.sigdeliver = NULL;
+ local_irq_enable();
+ sigdeliver(current_task);
+ local_irq_disable();
+}
+
+
+
+
+
+
+
diff --git a/nuttx/arch/rgmp/src/rgmp.c b/nuttx/arch/rgmp/src/rgmp.c
new file mode 100644
index 000000000..40fad1f87
--- /dev/null
+++ b/nuttx/arch/rgmp/src/rgmp.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * arch/rgmp/src/rgmp.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <rgmp/trap.h>
+#include <rgmp/mmu.h>
+#include <rgmp/arch/arch.h>
+
+#include <nuttx/config.h>
+#include <nuttx/init.h>
+#include <nuttx/arch.h>
+#include <nuttx/sched.h>
+#include <nuttx/kmalloc.h>
+#include <semaphore.h>
+#include <queue.h>
+#include <stdlib.h>
+#include <arch/arch.h>
+#include <os_internal.h>
+
+int nest_irq = 0;
+
+// the default time is 10ms
+#ifdef CONFIG_MSEC_PER_TICK
+unsigned int rtos_tick_time = CONFIG_MSEC_PER_TICK;
+#else
+unsigned int rtos_tick_time = 10;
+#endif
+
+void rtos_entry(void)
+{
+ os_start();
+}
+
+void *rtos_get_page(void)
+{
+ return memalign(PTMEMSIZE, PTMEMSIZE);
+}
+
+void rtos_free_page(void *page)
+{
+ free(page);
+}
+
+/**
+ * The interrupt can be nested. The pair of rtos_enter_interrupt()
+ * and rtos_exit_interrupt() make sure the context switch is
+ * performed only in the last IRQ exit.
+ */
+void rtos_enter_interrupt(struct Trapframe *tf)
+{
+ nest_irq++;
+}
+
+void rtos_exit_interrupt(struct Trapframe *tf)
+{
+ local_irq_disable();
+ nest_irq--;
+ if (!nest_irq) {
+ _TCB *rtcb = current_task;
+ _TCB *ntcb;
+
+ if (rtcb->xcp.sigdeliver) {
+ rtcb->xcp.tf = tf;
+ push_xcptcontext(&rtcb->xcp);
+ }
+ ntcb = (_TCB*)g_readytorun.head;
+ // switch needed
+ if (rtcb != ntcb) {
+ rtcb->xcp.tf = tf;
+ current_task = ntcb;
+ rgmp_pop_tf(ntcb->xcp.tf);
+ }
+ }
+}
+
+void rtos_timer_isr(struct Trapframe *tf)
+{
+ sched_process_timer();
+}
+
+/**
+ * RTOS mutex operation
+ */
+const int rtos_mutex_size = sizeof(sem_t);
+void rtos_mutex_init(void *lock)
+{
+ sem_init(lock, 0, 1);
+}
+
+int rtos_mutex_lock(void *lock)
+{
+ return sem_wait(lock);
+}
+
+int rtos_mutex_unlock(void *lock)
+{
+ return sem_post(lock);
+}
+
+/**
+ * RTOS semaphore operation
+ */
+const int rtos_semaphore_size = sizeof(sem_t);
+
+void rtos_sem_init(void *sem, int val)
+{
+ sem_init(sem, 0, val);
+}
+
+int rtos_sem_up(void *sem)
+{
+ return sem_post(sem);
+}
+
+int rtos_sem_down(void *sem)
+{
+ return sem_wait(sem);
+}
+
+void rtos_stop_running(void)
+{
+ extern void nuttx_arch_exit(void);
+
+ local_irq_disable();
+
+ nuttx_arch_exit();
+
+ while(1) {
+ arch_hlt();
+ }
+}
+
+
diff --git a/nuttx/arch/rgmp/src/x86/Make.defs b/nuttx/arch/rgmp/src/x86/Make.defs
new file mode 100644
index 000000000..5fb40006e
--- /dev/null
+++ b/nuttx/arch/rgmp/src/x86/Make.defs
@@ -0,0 +1,42 @@
+############################################################################
+# rgmp/x86/Make.defs
+#
+# Copyright (C) 2011 Yu Qiang. All rights reserved.
+# Author: Yu Qiang <yuq825@gmail.com>
+#
+# This file is a part of NuttX:
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+#
+#
+# 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 Gregory Nutt 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.
+#
+############################################################################
+
+RGMP_ARCH_ASRCS = sigentry.S
+RGMP_ARCH_CSRCS = com.c arch_nuttx.c
diff --git a/nuttx/arch/rgmp/src/x86/arch_nuttx.c b/nuttx/arch/rgmp/src/x86/arch_nuttx.c
new file mode 100644
index 000000000..c7b7577f3
--- /dev/null
+++ b/nuttx/arch/rgmp/src/x86/arch_nuttx.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * arch/rgmp/src/x86/arch_nuttx.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <rgmp/pmap.h>
+#include <rgmp/string.h>
+#include <rgmp/arch/fpu.h>
+
+#include <arch/arch.h>
+#include <nuttx/sched.h>
+#include <os_internal.h>
+
+
+void nuttx_arch_init(void)
+{
+ extern void e1000_mod_init(void);
+ extern void up_serialinit(void);
+
+ // setup COM device
+ up_serialinit();
+
+#ifdef CONFIG_NET_E1000
+ // setup e1000
+ e1000_mod_init();
+#endif
+
+}
+
+void nuttx_arch_exit(void)
+{
+ extern void e1000_mod_exit(void);
+
+#ifdef CONFIG_NET_E1000
+ e1000_mod_exit();
+#endif
+
+}
+
+void up_initial_state(_TCB *tcb)
+{
+ struct Trapframe *tf;
+
+ if (tcb->pid != 0) {
+ tf = (struct Trapframe *)tcb->adj_stack_ptr-1;
+ memset(tf, 0, sizeof(struct Trapframe));
+ tf->tf_fpu = rgmp_fpu_init_regs;
+ tf->tf_eflags = 0x00000202;
+ tf->tf_cs = GD_KT;
+ tf->tf_ds = GD_KD;
+ tf->tf_es = GD_KD;
+ tf->tf_eip = (uint32_t)tcb->start;
+ tcb->xcp.tf = tf;
+ }
+}
+
+void push_xcptcontext(struct xcptcontext *xcp)
+{
+ xcp->save_eip = xcp->tf->tf_eip;
+ xcp->save_eflags = xcp->tf->tf_eflags;
+
+ // set up signal entry with interrupts disabled
+ xcp->tf->tf_eip = (uint32_t)up_sigentry;
+ xcp->tf->tf_eflags = 0;
+}
+
+void pop_xcptcontext(struct xcptcontext *xcp)
+{
+ xcp->tf->tf_eip = xcp->save_eip;
+ xcp->tf->tf_eflags = xcp->save_eflags;
+}
+
diff --git a/nuttx/arch/rgmp/src/x86/com.c b/nuttx/arch/rgmp/src/x86/com.c
new file mode 100644
index 000000000..36ca15238
--- /dev/null
+++ b/nuttx/arch/rgmp/src/x86/com.c
@@ -0,0 +1,631 @@
+/****************************************************************************
+ * arch/rgmp/src/x86/com.c
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Authors: Yu Qiang <yuq825@gmail.com>
+ * 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 <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/serial.h>
+#include <nuttx/kmalloc.h>
+
+#include <arch/com.h>
+
+#include <rgmp/trap.h>
+#include <rgmp/arch/console.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define COM1 0x3F8
+#define COM2 0x2f8
+#define COM3 0x3e8
+#define COM4 0x2e8
+
+#define COM_RX 0 // In: Receive buffer (DLAB=0)
+#define COM_DLL 0 // Out: Divisor Latch Low (DLAB=1)
+#define COM_TX 0 // Out: Transmit buffer (DLAB=0)
+#define COM_DLM 1 // Out: Divisor Latch High (DLAB=1)
+#define COM_IER 1 // Out: Interrupt Enable Register
+#define COM_IER_TEI 0x02 // Enable transmit buffer empty interrupt
+#define COM_IER_RDI 0x01 // Enable receiver data interrupt
+#define COM_IIR 2 // In: Interrupt ID Register
+#define COM_FCR 2 // Out: FIFO Control Register
+#define COM_LCR 3 // Out: Line Control Register
+#define COM_LCR_DLAB 0x80 // Divisor latch access bit
+#define COM_LCR_WLEN8 0x03 // Wordlength: 8 bits
+#define COM_MCR 4 // Out: Modem Control Register
+#define COM_MCR_RTS 0x02 // RTS complement
+#define COM_MCR_DTR 0x01 // DTR complement
+#define COM_MCR_OUT2 0x08 // Out2 complement
+#define COM_LSR 5 // In: Line Status Register
+#define COM_LSR_DATA 0x01 // Data available
+#define COM_LSR_ETR 0x20 // buffer has space
+#define COM_LSR_EDR 0x40 // buffer empty
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#ifndef CONFIG_COM_RXBUFSIZE
+#define CONFIG_COM_RXBUFSIZE 64
+#endif
+
+#ifndef CONFIG_COM_TXBUFSIZE
+#define CONFIG_COM_TXBUFSIZE 64
+#endif
+
+struct up_dev_s
+{
+ unsigned int base; /* Base address of COM registers */
+ unsigned int baud; /* Configured baud */
+ int irq; /* IRQ associated with this COM */
+ struct irq_action action;
+ union {
+ uint8_t val;
+ struct {
+ unsigned bits : 2; /* 3=8 bits, 2=7 bits, 1=6 bits, 0=5 bits */
+ unsigned stopbits : 1; /* 0=1 stop bit, 1=2 stop bits */
+ unsigned parity : 3; /* xx0=none, 001=odd, 011=even */
+ unsigned ebreak : 1;
+ unsigned dlab : 1;
+ } sep;
+ } lcr;
+ char rxbuff[CONFIG_COM_RXBUFSIZE]; /* receive buffer */
+ char txbuff[CONFIG_COM_TXBUFSIZE]; /* transmit buffer */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int up_setup(struct uart_dev_s *dev);
+static void up_shutdown(struct uart_dev_s *dev);
+static int up_attach(struct uart_dev_s *dev);
+static void up_detach(struct uart_dev_s *dev);
+static irqreturn_t up_com_int_handler(struct Trapframe *tf, void *dev_id);
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int up_receive(struct uart_dev_s *dev, unsigned int *status);
+static void up_rxint(struct uart_dev_s *dev, bool enable);
+static bool up_rxavailable(struct uart_dev_s *dev);
+static void up_send(struct uart_dev_s *dev, int ch);
+static void up_txint(struct uart_dev_s *dev, bool enable);
+static bool up_txready(struct uart_dev_s *dev);
+static bool up_txempty(struct uart_dev_s *dev);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+static struct uart_ops_s g_com_ops =
+{
+ .setup = up_setup,
+ .shutdown = up_shutdown,
+ .attach = up_attach,
+ .detach = up_detach,
+ .ioctl = up_ioctl,
+ .receive = up_receive,
+ .rxint = up_rxint,
+ .rxavailable = up_rxavailable,
+ .send = up_send,
+ .txint = up_txint,
+ .txready = up_txready,
+ .txempty = up_txempty,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_alloc_com
+ ****************************************************************************/
+
+static uart_dev_t *up_alloc_com(unsigned int base, int irq)
+{
+ uart_dev_t *dev;
+ struct up_dev_s *priv;
+
+ priv = kzalloc(sizeof(struct up_dev_s));
+ if (priv == NULL)
+ goto err0;
+
+ dev = kzalloc(sizeof(uart_dev_t));
+ if (dev == NULL)
+ goto err1;
+
+ priv->base = base;
+ priv->irq = irq;
+ priv->baud = 115200;
+ priv->lcr.val = 0;
+ priv->lcr.sep.parity = 0;
+ priv->lcr.sep.bits = 3;
+ priv->lcr.sep.stopbits = 0;
+ priv->action.handler = up_com_int_handler;
+ priv->action.dev_id = dev;
+
+ dev->recv.size = CONFIG_COM_RXBUFSIZE;
+ dev->recv.buffer = priv->rxbuff;
+ dev->xmit.size = CONFIG_COM_TXBUFSIZE;
+ dev->xmit.buffer = priv->txbuff;
+ dev->ops = &g_com_ops;
+ dev->priv = priv;
+
+ return dev;
+
+ err1:
+ kfree(priv);
+ err0:
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: up_alloc_com
+ ****************************************************************************/
+
+static inline void up_free_com(uart_dev_t *com)
+{
+ kfree(com->priv);
+ kfree(com);
+}
+
+/****************************************************************************
+ * Name: up_setup
+ *
+ * Description:
+ * Configure the UART baud, bits, parity, fifos, etc. This
+ * method is called the first time that the serial port is
+ * opened.
+ *
+ ****************************************************************************/
+
+static int up_setup(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = dev->priv;
+ uint16_t base = priv->base;
+ union {
+ uint16_t val;
+ struct {
+ uint8_t low;
+ uint8_t high;
+ } sep;
+ } data;
+
+ // clear and disable FIFO
+ outb(base+COM_FCR, 1);
+ outb(base+COM_FCR, 3);
+ outb(base+COM_FCR, 0);
+
+ // Clear any preexisting overrun indications and interrupts
+ // Serial port doesn't exist if COM_LSR returns 0xFF
+ inb(base+COM_LSR);
+ inb(base+COM_IIR);
+ inb(base+COM_RX);
+ if (inb(base+COM_LSR) == 0xff) {
+ dbg("COM %d does not exist\n", base);
+ return -1;
+ }
+
+ // Set speed; requires DLAB latch
+ outb(base+COM_LCR, COM_LCR_DLAB);
+ data.val = 115200 / priv->baud;
+ outb(base+COM_DLL, data.sep.low);
+ outb(base+COM_DLM, data.sep.high);
+
+ // set data bits, stop bit, parity; turn off DLAB latch
+ outb(base+COM_LCR, priv->lcr.val);
+
+ // OUT2 must be set to enable interrupt
+ outb(base+COM_MCR, COM_MCR_OUT2);
+
+ // setup FIFO
+ outb(base+COM_FCR, 1);
+
+ // disable COM interrupts
+ outb(base+COM_IER, 0);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_shutdown
+ *
+ * Description:
+ * Disable the UART. This method is called when the serial port is closed
+ *
+ ****************************************************************************/
+
+static void up_shutdown(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = dev->priv;
+ uint16_t base = priv->base;
+
+ // disable COM interrupts
+ outb(base+COM_IER, 0);
+}
+
+/****************************************************************************
+ * Name: up_attach
+ *
+ * Description:
+ * Configure the UART to operation in interrupt driven mode. This method is
+ * called when the serial port is opened. Normally, this is just after the
+ * the setup() method is called, however, the serial console may operate in
+ * a non-interrupt driven mode during the boot phase.
+ *
+ * RX and TX interrupts are not enabled when by the attach method (unless the
+ * hardware supports multiple levels of interrupt enabling). The RX and TX
+ * interrupts are not enabled until the txint() and rxint() methods are called.
+ *
+ ****************************************************************************/
+
+static int up_attach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = dev->priv;
+ int err;
+
+ err = rgmp_request_irq(priv->irq, &priv->action, 0);
+
+ return err;
+}
+
+/****************************************************************************
+ * Name: up_detach
+ *
+ * Description:
+ * Detach UART interrupts. This method is called when the serial port is
+ * closed normally just before the shutdown method is called. The exception is
+ * the serial console which is never shutdown.
+ *
+ ****************************************************************************/
+
+static void up_detach(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = dev->priv;
+
+ rgmp_free_irq(priv->irq, &priv->action);
+}
+
+/****************************************************************************
+ * Name: up_com_int_handler
+ *
+ * Description:
+ * This is the UART interrupt handler. It will be invoked
+ * when an interrupt received on the 'irq' It should call
+ * uart_transmitchars or uart_receivechar to perform the
+ * appropriate data transfers. The interrupt handling logic\
+ * must be able to map the 'irq' number into the approprite
+ * uart_dev_s structure in order to call these functions.
+ *
+ ****************************************************************************/
+
+static irqreturn_t up_com_int_handler(struct Trapframe *tf, void *dev_id)
+{
+ struct uart_dev_s *dev = dev_id;
+ struct up_dev_s *priv = dev->priv;
+ uint16_t base = priv->base;
+ //uint8_t cause = inb(base+COM_IIR);
+ uint8_t state = inb(base+COM_LSR);
+
+ if (state & COM_LSR_DATA)
+ uart_recvchars(dev);
+
+ if (state & COM_LSR_ETR)
+ uart_xmitchars(dev);
+
+ return IRQ_HANDLED;
+}
+
+/****************************************************************************
+ * Name: up_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ struct inode *inode = filep->f_inode;
+ struct uart_dev_s *dev = inode->i_private;
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
+ switch (cmd) {
+ case COM_SET_BAUD:
+ priv->baud = arg;
+ break;
+ case COM_SET_PARITY:
+ priv->lcr.sep.parity = arg;
+ break;
+ case COM_SET_STOPBITS:
+ priv->lcr.sep.stopbits = arg;
+ break;
+ case COM_SET_BITS:
+ priv->lcr.sep.bits = arg;
+ break;
+ default:
+ return ERROR;
+ }
+
+ if (up_setup(dev) != OK)
+ return ERROR;
+
+ up_rxint(dev, 1);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_receive
+ *
+ * Description:
+ * Called (usually) from the interrupt level to receive one character from
+ * the UART. Error bits associated with the receipt are provided in the
+ * the return 'status'.
+ *
+ ****************************************************************************/
+
+static int up_receive(struct uart_dev_s *dev, unsigned int *status)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+
+ return inb(base+COM_RX);
+}
+
+/****************************************************************************
+ * Name: up_rxint
+ *
+ * Description:
+ * Call to enable or disable RX interrupts
+ *
+ ****************************************************************************/
+
+static void up_rxint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+ uint8_t ier;
+
+ ier = inb(base+COM_IER);
+ if (enable)
+ ier |= COM_IER_RDI;
+ else
+ ier &= ~COM_IER_RDI;
+ outb(base+COM_IER, ier);
+}
+
+/****************************************************************************
+ * Name: up_rxavailable
+ *
+ * Description:
+ * Return true if the receive fifo is not empty
+ *
+ ****************************************************************************/
+
+static bool up_rxavailable(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+
+ return inb(base+COM_LSR) & COM_LSR_DATA;
+}
+
+/****************************************************************************
+ * Name: up_send
+ *
+ * Description:
+ * This method will send one byte on the UART
+ *
+ ****************************************************************************/
+
+static void up_send(struct uart_dev_s *dev, int ch)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+
+ outb(base+COM_TX, ch);
+}
+
+/****************************************************************************
+ * Name: up_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void up_txint(struct uart_dev_s *dev, bool enable)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+ irqstate_t flags;
+ uint8_t ier;
+
+ flags = irqsave();
+ ier = inb(base+COM_IER);
+ if (enable) {
+ ier |= COM_IER_TEI;
+ outb(base+COM_IER, ier);
+
+ /* Fake a TX interrupt here by just calling uart_xmitchars() with
+ * interrupts disabled (note this may recurse).
+ */
+
+ uart_xmitchars(dev);
+ }
+ else {
+ ier &= ~COM_IER_TEI;
+ outb(base+COM_IER, ier);
+ }
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: up_txready
+ *
+ * Description:
+ * Return true if the tranmsit fifo is not full
+ *
+ ****************************************************************************/
+
+static bool up_txready(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+
+ return inb(base+COM_LSR) & COM_LSR_ETR;
+}
+
+/****************************************************************************
+ * Name: up_txempty
+ *
+ * Description:
+ * Return true if the transmit fifo is empty
+ *
+ ****************************************************************************/
+
+static bool up_txempty(struct uart_dev_s *dev)
+{
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ uint16_t base = priv->base;
+
+ return inb(base+COM_LSR) & COM_LSR_EDR;
+}
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_serialinit
+ *
+ * Description:
+ * Performs the low level UART initialization early in
+ * debug so that the serial console will be available
+ * during bootup. This must be called before up_serialinit.
+ *
+ ****************************************************************************/
+
+void up_earlyserialinit(void)
+{
+
+}
+
+/****************************************************************************
+ * Name: up_serialinit
+ *
+ * Description:
+ * Register serial console and serial ports. This assumes
+ * that up_earlyserialinit was called previously.
+ *
+ ****************************************************************************/
+
+void up_serialinit(void)
+{
+ uart_dev_t *dev;
+ int err;
+
+#ifdef CONFIG_COM1
+ dev = up_alloc_com(COM1, 4);
+ if (dev == NULL)
+ dbg("alloc com1 fail\n");
+ else {
+ err = uart_register("/dev/ttyS0", dev);
+ if (err)
+ dbg("register com1 fail\n");
+ }
+#endif
+#ifdef CONFIG_COM2
+ dev = up_alloc_com(COM2, 3);
+ if (dev == NULL)
+ dbg("alloc com2 fail\n");
+ else {
+ err = uart_register("/dev/ttyS1", dev);
+ if (err)
+ dbg("register com2 fail\n");
+ }
+#endif
+#ifdef CONFIG_COM3
+ dev = up_alloc_com(COM3, 4);
+ if (dev == NULL)
+ dbg("alloc com3 fail\n");
+ else {
+ err = uart_register("/dev/ttyS2", dev);
+ if (err)
+ dbg("register com3 fail\n");
+ }
+#endif
+#ifdef CONFIG_COM4
+ dev = up_alloc_com(COM4, 3);
+ if (dev == NULL)
+ dbg("alloc com4 fail\n");
+ else {
+ err = uart_register("/dev/ttyS3", dev);
+ if (err)
+ dbg("register com4 fail\n");
+ }
+#endif
+}
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug
+ * writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+ cons_putc(ch);
+ return ch;
+}
+
diff --git a/nuttx/arch/rgmp/src/x86/sigentry.S b/nuttx/arch/rgmp/src/x86/sigentry.S
new file mode 100644
index 000000000..98891c026
--- /dev/null
+++ b/nuttx/arch/rgmp/src/x86/sigentry.S
@@ -0,0 +1,55 @@
+/****************************************************************************
+ * arch/rgmp/src/x86/sigentry.S
+ *
+ * Copyright (C) 2011 Yu Qiang. All rights reserved.
+ * Author: Yu Qiang <yuq825@gmail.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+ .globl up_sigentry
+up_sigentry:
+ subl $172, %esp # 172 is the size of TrapFrame
+ pushl %esp
+ movl %esp, %eax
+ call up_sigdeliver
+ addl $8, %esp # skip parameter and current_task
+ frstor 0(%esp)
+ addl $108, %esp
+ popal
+ popl %es
+ popl %ds
+ addl $0x8, %esp # trapno and errcode
+ iret
+
+ \ No newline at end of file