From c07e3aeb901dac03d1faff65b4c6eda1de25141c Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 4 Aug 2011 12:29:19 +0000 Subject: Add Yu Qiang's patch for RGMP support on the ARM git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3843 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/nxlines/nxlines_bkgd.c | 19 +- nuttx/ChangeLog | 5 + nuttx/arch/rgmp/include/arch.h | 16 +- nuttx/arch/rgmp/include/arm/arch/subarch/arch.h | 58 +++ nuttx/arch/rgmp/include/com.h | 59 --- nuttx/arch/rgmp/include/irq.h | 8 +- nuttx/arch/rgmp/include/stdint.h | 22 - nuttx/arch/rgmp/include/x86/arch/com.h | 58 +++ nuttx/arch/rgmp/include/x86/arch/subarch/arch.h | 60 +++ nuttx/arch/rgmp/src/Makefile | 7 +- nuttx/arch/rgmp/src/arm/Make.defs | 42 ++ nuttx/arch/rgmp/src/arm/arch_nuttx.c | 91 ++++ nuttx/arch/rgmp/src/arm/sigentry.S | 49 ++ nuttx/arch/rgmp/src/com.c | 631 ------------------------ nuttx/arch/rgmp/src/nuttx.c | 66 +-- nuttx/arch/rgmp/src/rgmp.c | 28 +- nuttx/arch/rgmp/src/sigentry.S | 55 --- nuttx/arch/rgmp/src/x86/Make.defs | 42 ++ nuttx/arch/rgmp/src/x86/arch_nuttx.c | 106 ++++ nuttx/arch/rgmp/src/x86/com.c | 631 ++++++++++++++++++++++++ nuttx/arch/rgmp/src/x86/sigentry.S | 55 +++ nuttx/configs/rgmp/README.txt | 22 +- nuttx/configs/rgmp/arm/default/Make.defs | 117 +++++ nuttx/configs/rgmp/arm/default/appconfig | 39 ++ nuttx/configs/rgmp/arm/default/defconfig | 403 +++++++++++++++ nuttx/configs/rgmp/arm/default/setenv.sh | 47 ++ nuttx/configs/rgmp/arm/nsh/Make.defs | 117 +++++ nuttx/configs/rgmp/arm/nsh/appconfig | 54 ++ nuttx/configs/rgmp/arm/nsh/defconfig | 433 ++++++++++++++++ nuttx/configs/rgmp/arm/nsh/setenv.sh | 47 ++ nuttx/configs/rgmp/default/Make.defs | 119 ----- nuttx/configs/rgmp/default/appconfig | 39 -- nuttx/configs/rgmp/default/defconfig | 412 ---------------- nuttx/configs/rgmp/default/setenv.sh | 47 -- nuttx/configs/rgmp/include/stdarg.h | 21 +- nuttx/configs/rgmp/nsh/Make.defs | 119 ----- nuttx/configs/rgmp/nsh/appconfig | 54 -- nuttx/configs/rgmp/nsh/defconfig | 442 ----------------- nuttx/configs/rgmp/nsh/setenv.sh | 47 -- nuttx/configs/rgmp/x86/default/Make.defs | 116 +++++ nuttx/configs/rgmp/x86/default/appconfig | 39 ++ nuttx/configs/rgmp/x86/default/defconfig | 417 ++++++++++++++++ nuttx/configs/rgmp/x86/default/setenv.sh | 47 ++ nuttx/configs/rgmp/x86/nsh/Make.defs | 116 +++++ nuttx/configs/rgmp/x86/nsh/appconfig | 54 ++ nuttx/configs/rgmp/x86/nsh/defconfig | 447 +++++++++++++++++ nuttx/configs/rgmp/x86/nsh/setenv.sh | 47 ++ nuttx/drivers/net/e1000.c | 4 +- nuttx/drivers/net/e1000.h | 2 +- 49 files changed, 3818 insertions(+), 2158 deletions(-) create mode 100644 nuttx/arch/rgmp/include/arm/arch/subarch/arch.h delete mode 100644 nuttx/arch/rgmp/include/com.h create mode 100644 nuttx/arch/rgmp/include/x86/arch/com.h create mode 100644 nuttx/arch/rgmp/include/x86/arch/subarch/arch.h create mode 100644 nuttx/arch/rgmp/src/arm/Make.defs create mode 100644 nuttx/arch/rgmp/src/arm/arch_nuttx.c create mode 100644 nuttx/arch/rgmp/src/arm/sigentry.S delete mode 100644 nuttx/arch/rgmp/src/com.c delete mode 100644 nuttx/arch/rgmp/src/sigentry.S create mode 100644 nuttx/arch/rgmp/src/x86/Make.defs create mode 100644 nuttx/arch/rgmp/src/x86/arch_nuttx.c create mode 100644 nuttx/arch/rgmp/src/x86/com.c create mode 100644 nuttx/arch/rgmp/src/x86/sigentry.S create mode 100644 nuttx/configs/rgmp/arm/default/Make.defs create mode 100644 nuttx/configs/rgmp/arm/default/appconfig create mode 100644 nuttx/configs/rgmp/arm/default/defconfig create mode 100644 nuttx/configs/rgmp/arm/default/setenv.sh create mode 100644 nuttx/configs/rgmp/arm/nsh/Make.defs create mode 100644 nuttx/configs/rgmp/arm/nsh/appconfig create mode 100644 nuttx/configs/rgmp/arm/nsh/defconfig create mode 100644 nuttx/configs/rgmp/arm/nsh/setenv.sh delete mode 100644 nuttx/configs/rgmp/default/Make.defs delete mode 100644 nuttx/configs/rgmp/default/appconfig delete mode 100644 nuttx/configs/rgmp/default/defconfig delete mode 100755 nuttx/configs/rgmp/default/setenv.sh delete mode 100644 nuttx/configs/rgmp/nsh/Make.defs delete mode 100644 nuttx/configs/rgmp/nsh/appconfig delete mode 100644 nuttx/configs/rgmp/nsh/defconfig delete mode 100755 nuttx/configs/rgmp/nsh/setenv.sh create mode 100644 nuttx/configs/rgmp/x86/default/Make.defs create mode 100644 nuttx/configs/rgmp/x86/default/appconfig create mode 100644 nuttx/configs/rgmp/x86/default/defconfig create mode 100644 nuttx/configs/rgmp/x86/default/setenv.sh create mode 100644 nuttx/configs/rgmp/x86/nsh/Make.defs create mode 100644 nuttx/configs/rgmp/x86/nsh/appconfig create mode 100644 nuttx/configs/rgmp/x86/nsh/defconfig create mode 100644 nuttx/configs/rgmp/x86/nsh/setenv.sh diff --git a/apps/examples/nxlines/nxlines_bkgd.c b/apps/examples/nxlines/nxlines_bkgd.c index 164521156..80808b1da 100644 --- a/apps/examples/nxlines/nxlines_bkgd.c +++ b/apps/examples/nxlines/nxlines_bkgd.c @@ -257,12 +257,25 @@ void nxlines_test(NXWINDOW hwnd) message("nxlines_test: nx_drawline failed clearing: %d\n", ret); } - /* Set up for the next time throught the loop then sleep for a bit. */ + /* Set up for the next time through the loop then sleep for a bit. */ - angle += b16PI / 16; /* 32 angular positions in full circle */ - if (angle > (31 * (2 * b16PI) / 32)) /* Wrap back to zero.. allowing for slop */ + angle += b16PI / 16; /* 32 angular positions in full circle */ + + /* Check if we have gone all the way around */ + + if (angle > (31 * (2 * b16PI) / 32)) { +#ifdef CONFIG_EXAMPLES_NXLINES_BUILTIN + /* If this example was built as an NSH add-on, then exit after we + * have gone all the way around once. + */ + + return; +#else + /* Wrap back to zero and continue with the test */ + angle = 0; +#endif } memcpy(&previous, &vector, sizeof(struct nxgl_vector_s)); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 73a100a34..16813774d 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -1977,3 +1977,8 @@ examples/nxlines. * arch/graphics: Used apps/examples/nxlines to (finally) verify the NX trapezoid drawing functions and (wide) line drawing functions. + * arch/rgmp and configs/rgmp. Yu Qiang has ported RGMP to the OMAP4430 (arm) + pandaboard and release the new RGMP 0.3 version. The main changes are: (1) + Separate configs/rgmp/x86 and configs/rgmp/arm configuration directory, and + (2) Extract architecture dependent code in arch/rgmp/include and + arch/rgmp/src into corresponding x86/ and arm/ directories. diff --git a/nuttx/arch/rgmp/include/arch.h b/nuttx/arch/rgmp/include/arch.h index 789c1d471..c93397baa 100644 --- a/nuttx/arch/rgmp/include/arch.h +++ b/nuttx/arch/rgmp/include/arch.h @@ -40,10 +40,12 @@ #ifndef __RGMP_ARCH_ARCH_H #define __RGMP_ARCH_ARCH_H +#include + #ifndef __ASSEMBLY__ #include -#include + struct up_wait { struct up_wait *next; @@ -57,16 +59,6 @@ void up_sigentry(void); int up_register_bridge(char *name, int size); int up_unregister_bridge(char *name); -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 +#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 + * + * 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/com.h b/nuttx/arch/rgmp/include/com.h deleted file mode 100644 index 918e3bd3f..000000000 --- a/nuttx/arch/rgmp/include/com.h +++ /dev/null @@ -1,59 +0,0 @@ -/**************************************************************************** - * arch/rgmp/include/com.h - * - * Copyright (C) 2011 Yu Qiang. All rights reserved. - * Author: Yu Qiang - * - * 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 - -void up_serialinit(void); - -#endif diff --git a/nuttx/arch/rgmp/include/irq.h b/nuttx/arch/rgmp/include/irq.h index 7f8a06dbb..00c977560 100644 --- a/nuttx/arch/rgmp/include/irq.h +++ b/nuttx/arch/rgmp/include/irq.h @@ -44,9 +44,9 @@ #ifndef __ASSEMBLY__ -#include #include #include +#include struct xcptcontext { struct Trapframe *tf; @@ -56,6 +56,9 @@ struct xcptcontext { void *sigdeliver; }; +void push_xcptcontext(struct xcptcontext *xcp); +void pop_xcptcontext(struct xcptcontext *xcp); + extern int nest_irq; static inline irqstate_t irqsave(void) @@ -68,5 +71,6 @@ static inline void irqrestore(irqstate_t flags) popcli(flags); } -#endif +#endif /* !__ASSEMBLY__ */ + #endif diff --git a/nuttx/arch/rgmp/include/stdint.h b/nuttx/arch/rgmp/include/stdint.h index 59dff2c8d..7b244dd9f 100644 --- a/nuttx/arch/rgmp/include/stdint.h +++ b/nuttx/arch/rgmp/include/stdint.h @@ -207,29 +207,7 @@ * provided by their toolchain header files. */ -#ifdef CONFIG_ARCH_RGMP #include -#else -typedef _int8_t int8_t; -typedef _uint8_t uint8_t; - -typedef _int16_t int16_t; -typedef _uint16_t uint16_t; - -#ifdef __INT24_DEFINED -typedef _int24_t int24_t; -typedef _uint24_t uint24_t; -#endif - -typedef _int32_t int32_t; -typedef _uint32_t uint32_t; - -#ifdef __INT64_DEFINED -typedef _int64_t int64_t; -typedef _uint64_t uint64_t; -#endif - -#endif /* CONFIG_ARCH_RGMP */ /* Minimum-width integer types */ 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 + * + * 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 + * + * 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 + + +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 index ae2c68876..f973a28fa 100644 --- a/nuttx/arch/rgmp/src/Makefile +++ b/nuttx/arch/rgmp/src/Makefile @@ -34,13 +34,16 @@ ############################################################################ -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 = sigentry.S +ASRCS = $(RGMP_ARCH_ASRCS) +CSRCS = nuttx.c rgmp.c bridge.c $(RGMP_ARCH_CSRCS) AOBJS = $(ASRCS:.S=$(OBJEXT)) -CSRCS = nuttx.c rgmp.c bridge.c com.c COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) 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 +# +# 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 + * + * 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 +#include + +#include +#include +#include + + +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 + * + * 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/com.c b/nuttx/arch/rgmp/src/com.c deleted file mode 100644 index e1b8febb2..000000000 --- a/nuttx/arch/rgmp/src/com.c +++ /dev/null @@ -1,631 +0,0 @@ -/**************************************************************************** - * arch/rgmp/src/com.c - * - * Copyright (C) 2011 Yu Qiang. All rights reserved. - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Authors: Yu Qiang - * Gregory Nutt - * - * 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 - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include -#include - -/**************************************************************************** - * 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/nuttx.c b/nuttx/arch/rgmp/src/nuttx.c index b81fc98dd..14b3e6d1d 100644 --- a/nuttx/arch/rgmp/src/nuttx.c +++ b/nuttx/arch/rgmp/src/nuttx.c @@ -1,5 +1,5 @@ /**************************************************************************** - * arch/rgmp/src/bridge.c + * arch/rgmp/src/nuttx.c * * Copyright (C) 2011 Yu Qiang. All rights reserved. * Author: Yu Qiang @@ -39,12 +39,13 @@ #include #include -#include #include #include -#include #include -#include + +#include +#include + #include #include #include @@ -52,11 +53,11 @@ #include #include #include -#include #include _TCB *current_task = NULL; + /** * This function is called in non-interrupt context * to switch tasks. @@ -75,9 +76,7 @@ static inline void up_switchcontext(_TCB *ctcb, _TCB *ntcb) // start switch current_task = ntcb; - asm volatile ("int $0x40" - ::"a"(ctcb?&ctcb->xcp.tf:NULL), - "b"(ntcb->xcp.tf)); + rgmp_context_switch(ctcb?&ctcb->xcp.tf:NULL, ntcb->xcp.tf); } void up_initialize(void) @@ -85,7 +84,7 @@ void up_initialize(void) extern pidhash_t g_pidhash[]; extern void up_register_bridges(void); extern void vnet_initialize(void); - extern void e1000_mod_init(void); + extern void nuttx_arch_init(void); // intialize the current_task to g_idletcb current_task = g_pidhash[PIDHASH(0)].tcb; @@ -98,38 +97,15 @@ void up_initialize(void) vnet_initialize(); #endif - // setup COM device - up_serialinit(); - -#ifdef CONFIG_NET_E1000 - // setup e1000 - e1000_mod_init(); -#endif + nuttx_arch_init(); // enable interrupt - sti(); + local_irq_enable(); } void up_idle(void) { - asm volatile("hlt"); -} - -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; - } + arch_hlt(); } void up_allocate_heap(void **heap_start, size_t *heap_size) @@ -160,7 +136,7 @@ int up_create_stack(_TCB *tcb, size_t stack_size) tcb->adj_stack_size = adj_stack_size; tcb->stack_alloc_ptr = stack_alloc_ptr; - tcb->adj_stack_ptr = adj_stack_ptr; + tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7); ret = OK; } return ret; @@ -181,7 +157,7 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size) tcb->adj_stack_size = adj_stack_size; tcb->stack_alloc_ptr = stack; - tcb->adj_stack_ptr = adj_stack_ptr; + tcb->adj_stack_ptr = (void *)((unsigned int)adj_stack_ptr & ~7); return OK; } @@ -472,12 +448,7 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) // some non-running task. else { tcb->xcp.sigdeliver = sigdeliver; - tcb->xcp.save_eip = tcb->xcp.tf->tf_eip; - tcb->xcp.save_eflags = tcb->xcp.tf->tf_eflags; - - // Then set up to the trampoline with interrupts disabled - tcb->xcp.tf->tf_eip = (uint32_t)up_sigentry; - tcb->xcp.tf->tf_eflags = 0; + push_xcptcontext(&tcb->xcp); } popcli(flags); @@ -516,14 +487,13 @@ int up_prioritize_irq(int irq, int priority) void up_sigdeliver(struct Trapframe *tf) { sig_deliver_t sigdeliver; - - tf->tf_eip = current_task->xcp.save_eip; - tf->tf_eflags = current_task->xcp.save_eflags; + + pop_xcptcontext(¤t_task->xcp); sigdeliver = current_task->xcp.sigdeliver; current_task->xcp.sigdeliver = NULL; - sti(); + local_irq_enable(); sigdeliver(current_task); - cli(); + local_irq_disable(); } diff --git a/nuttx/arch/rgmp/src/rgmp.c b/nuttx/arch/rgmp/src/rgmp.c index 6cc7aceb4..40fad1f87 100644 --- a/nuttx/arch/rgmp/src/rgmp.c +++ b/nuttx/arch/rgmp/src/rgmp.c @@ -37,8 +37,10 @@ * ****************************************************************************/ -#include #include +#include +#include + #include #include #include @@ -66,7 +68,7 @@ void rtos_entry(void) void *rtos_get_page(void) { - return memalign(4096, 4096); + return memalign(PTMEMSIZE, PTMEMSIZE); } void rtos_free_page(void *page) @@ -86,19 +88,15 @@ void rtos_enter_interrupt(struct Trapframe *tf) void rtos_exit_interrupt(struct Trapframe *tf) { - cli(); + local_irq_disable(); nest_irq--; if (!nest_irq) { _TCB *rtcb = current_task; _TCB *ntcb; if (rtcb->xcp.sigdeliver) { - rtcb->xcp.save_eip = tf->tf_eip; - rtcb->xcp.save_eflags = tf->tf_eflags; - - // Then set up to the trampoline with interrupts disabled - tf->tf_eip = (uint32_t)up_sigentry; - tf->tf_eflags = 0; + rtcb->xcp.tf = tf; + push_xcptcontext(&rtcb->xcp); } ntcb = (_TCB*)g_readytorun.head; // switch needed @@ -156,16 +154,14 @@ int rtos_sem_down(void *sem) void rtos_stop_running(void) { - extern void e1000_mod_exit(void); + extern void nuttx_arch_exit(void); - cli(); - -#ifdef CONFIG_NET_E1000 - e1000_mod_exit(); -#endif + local_irq_disable(); + + nuttx_arch_exit(); while(1) { - asm volatile("hlt"); + arch_hlt(); } } diff --git a/nuttx/arch/rgmp/src/sigentry.S b/nuttx/arch/rgmp/src/sigentry.S deleted file mode 100644 index b2f9d6283..000000000 --- a/nuttx/arch/rgmp/src/sigentry.S +++ /dev/null @@ -1,55 +0,0 @@ -/**************************************************************************** - * arch/rgmp/src/sigentry.S - * - * Copyright (C) 2011 Yu Qiang. All rights reserved. - * Author: Yu Qiang - * - * 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 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 +# +# 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 + * + * 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 +#include +#include + +#include +#include +#include + + +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 + * Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include + +/**************************************************************************** + * 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 + * + * 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 diff --git a/nuttx/configs/rgmp/README.txt b/nuttx/configs/rgmp/README.txt index 2db1d6b13..3e4603e7e 100755 --- a/nuttx/configs/rgmp/README.txt +++ b/nuttx/configs/rgmp/README.txt @@ -16,12 +16,16 @@ http://rgmp.sourceforge.net/wiki/index.php/Documentation Ubuntu Build Instructions -------------------------- Build requirements: -Hardware: x86 PC -Software: Ubuntu 10.04, 10.10 or 11.04 + * x86 PC: + Ubuntu 10.04, 10.10 or 11.04 + * OMAP4430 pandaboard: + Ubuntu 11.04 Run requirements: -Hardware: multi-processor x86 PC -Software: Ubuntu 10.04, 10.10 or 11.04 + * multi-processor x86 PC: + Ubuntu 10.04, 10.10 or 11.04 + * OMAP4430 pandaboard: + Ubuntu 11.04 1. Download RGMP from the following URL: @@ -45,12 +49,12 @@ Software: Ubuntu 10.04, 10.10 or 11.04 $ sudo /usr/rgmp/setup $ exit -4. Configure NuttX. For example, for the RGMP NSH configuration, do the +4. Configure NuttX. For example, for the RGMP x86 NSH configuration, do the following: $ cd $ cd tools - $ ./configure.sh rgmp/nsh + $ ./configure.sh rgmp/x86/nsh $ cd .. 5. Build NuttX. Get the binary image at /kernel.img. @@ -68,8 +72,10 @@ Software: Ubuntu 10.04, 10.10 or 11.04 Other Linux OS Build Instruction -------------------------------------- Requirements: -Hardware: multi-processor x86 PC -Software: running Linux kernel 2.6.32, 2.6.35 or 2.6.38 + * multi-processor x86 PC + running Linux kernel 2.6.32, 2.6.35 or 2.6.38 + * OMAP4430 pandaboard + running Linux kernel 2.6.38 1. Get your running Linux kernel header under /usr/src/linux-headers-$(uname -r) directory. diff --git a/nuttx/configs/rgmp/arm/default/Make.defs b/nuttx/configs/rgmp/arm/default/Make.defs new file mode 100644 index 000000000..19d643cc3 --- /dev/null +++ b/nuttx/configs/rgmp/arm/default/Make.defs @@ -0,0 +1,117 @@ +############################################################################ +# configs/rgmp/default/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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}/.config + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector -fno-omit-frame-pointer \ + -marm -march=armv7-a +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/arm +ARCHSCRIPT = + +CROSSDEV = +CC = $(CROSSDEV)gcc +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/arm/default/appconfig b/nuttx/configs/rgmp/arm/default/appconfig new file mode 100644 index 000000000..e1397db20 --- /dev/null +++ b/nuttx/configs/rgmp/arm/default/appconfig @@ -0,0 +1,39 @@ +############################################################################ +# configs/sim/default/appconfig +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/rgmp + diff --git a/nuttx/configs/rgmp/arm/default/defconfig b/nuttx/configs/rgmp/arm/default/defconfig new file mode 100644 index 000000000..5723276e3 --- /dev/null +++ b/nuttx/configs/rgmp/arm/default/defconfig @@ -0,0 +1,403 @@ +############################################################################ +# configs/rgmp/default/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=rgmp +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD=rgmp +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=n +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_RECEIVE_WINDOW=128 +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Settings for examples/uip +CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|10<<8|2) +CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|10<<8|1) +CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_UIP_DHCPC=n + +# +# Settings for examples/nettest +CONFIG_EXAMPLE_NETTEST_SERVER=n +CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLE_NETTEST_NOMAC=n +CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) + +# +# Settings for examples/nsh +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_STACKSIZE=4096 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) +CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=arm + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + + diff --git a/nuttx/configs/rgmp/arm/default/setenv.sh b/nuttx/configs/rgmp/arm/default/setenv.sh new file mode 100644 index 000000000..a6a533e47 --- /dev/null +++ b/nuttx/configs/rgmp/arm/default/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/default/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/arm/nsh/Make.defs b/nuttx/configs/rgmp/arm/nsh/Make.defs new file mode 100644 index 000000000..3bb764a1c --- /dev/null +++ b/nuttx/configs/rgmp/arm/nsh/Make.defs @@ -0,0 +1,117 @@ +############################################################################ +# configs/rgmp/nsh/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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}/.config + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector -fno-omit-frame-pointer \ + -marm -march=armv7-a +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/arm +ARCHSCRIPT = + +CROSSDEV = +CC = $(CROSSDEV)gcc +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/arm/nsh/appconfig b/nuttx/configs/rgmp/arm/nsh/appconfig new file mode 100644 index 000000000..092554129 --- /dev/null +++ b/nuttx/configs/rgmp/arm/nsh/appconfig @@ -0,0 +1,54 @@ +############################################################################ +# configs/rgmp/nsh/appconfig +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nsh + +# The NSH Library + +CONFIGURED_APPS += nshlib + +# Networking support + +ifeq ($(CONFIG_NET),y) +CONFIGURED_APPS += netutils/uiplib +CONFIGURED_APPS += netutils/dhcpc +CONFIGURED_APPS += netutils/resolv +CONFIGURED_APPS += netutils/tftpc +CONFIGURED_APPS += netutils/webclient +endif + + diff --git a/nuttx/configs/rgmp/arm/nsh/defconfig b/nuttx/configs/rgmp/arm/nsh/defconfig new file mode 100644 index 000000000..25c3ed3b4 --- /dev/null +++ b/nuttx/configs/rgmp/arm/nsh/defconfig @@ -0,0 +1,433 @@ +############################################################################ +# configs/rgmp/nsh/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=rgmp +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD=rgmp +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +CONFIG_NET_RECEIVE_WINDOW=128 +CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Settings for examples/uip +CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_UIP_DHCPC=n + +# +# Settings for examples/nettest +CONFIG_EXAMPLE_NETTEST_SERVER=n +CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLE_NETTEST_NOMAC=n +CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_STACKSIZE - Stack size to use for new threads. +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +# +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_STACKSIZE=4096 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(192<<24|168<<16|10<<8|2) +CONFIG_NSH_DRIPADDR=(192<<24|168<<16|10<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=arm + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + + diff --git a/nuttx/configs/rgmp/arm/nsh/setenv.sh b/nuttx/configs/rgmp/arm/nsh/setenv.sh new file mode 100644 index 000000000..6caf8de84 --- /dev/null +++ b/nuttx/configs/rgmp/arm/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/nsh/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/default/Make.defs b/nuttx/configs/rgmp/default/Make.defs deleted file mode 100644 index 1e104d76d..000000000 --- a/nuttx/configs/rgmp/default/Make.defs +++ /dev/null @@ -1,119 +0,0 @@ -############################################################################ -# configs/rgmp/default/Make.defs -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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}/.config - -RGMPLIBDIR := $(RGMP_INST_DIR)/lib -RGMPINCDIR := $(RGMP_INST_DIR)/include -RGMPLKSCPT := $(RGMP_INST_DIR)/etc/x86.ld - -HOSTOS = ${shell uname -o} - -ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -O2 -gstabs -else - ARCHOPTIMIZATION = -O2 -endif - -ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector -ARCHPICFLAGS = -fpic -ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHDEFINES = -ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ - -I$(TOPDIR)/configs/rgmp/include -ARCHSCRIPT = - -CROSSDEV = -CC = $(CROSSDEV)gcc -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump - -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ - -OBJEXT = .o -LIBEXT = .a - -ifeq ($(HOSTOS),Cygwin) - EXEEXT = .exe -else - EXEEXT = -endif - -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") - LDFLAGS += -g -endif -LDFLAGS += -nostdlib -EXTRA_LIBS = - -define PREPROCESS - @echo "CPP: $1->$2" - @$(CPP) $(CPPFLAGS) $1 -o $2 -endef - -define COMPILE - @echo "CC: $1" - @$(CC) -c $(CFLAGS) $1 -o $2 -endef - -define ASSEMBLE - @echo "AS: $1" - @$(CC) -c $(AFLAGS) $1 -o $2 -endef - -define ARCHIVE - echo "AR: $2"; \ - $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } -endef - -define CLEAN - @rm -f *.o *.a -endef - -MKDEP = $(TOPDIR)/tools/mkdeps.sh - -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe -HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/default/appconfig b/nuttx/configs/rgmp/default/appconfig deleted file mode 100644 index e1397db20..000000000 --- a/nuttx/configs/rgmp/default/appconfig +++ /dev/null @@ -1,39 +0,0 @@ -############################################################################ -# configs/sim/default/appconfig -# -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt -# -# 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/rgmp - diff --git a/nuttx/configs/rgmp/default/defconfig b/nuttx/configs/rgmp/default/defconfig deleted file mode 100644 index 198a0ddcb..000000000 --- a/nuttx/configs/rgmp/default/defconfig +++ /dev/null @@ -1,412 +0,0 @@ -############################################################################ -# configs/rgmp/default/defconfig -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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. -# -############################################################################ -# -# Architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_name - for use in C code. This identifies the particular -# processor architecture (CONFIG_ARCH_SIM). -# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# -CONFIG_ARCH=rgmp -CONFIG_ARCH_RGMP=y -CONFIG_ARCH_BOARD=rgmp -CONFIG_ARCH_BOARD_RGMP=y - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# CONFIG_DEBUG_SYMBOLS - build without optimization and with -# debug symbols (needed for use with a debugger). -# CONFIG_MM_REGIONS - If the architecture includes multiple -# regions of memory to allocate from, this specifies the -# number of memory regions that the memory manager must -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_JULIAN_TIME - Enables Julian time conversions -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket -# desciptors by task_create() when a new task is started. If -# set, all sockets will appear to be closed in the new task. -# -#CONFIG_APPS_DIR= -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y -CONFIG_MSEC_PER_TICK=1 -CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n -CONFIG_TASK_NAME_SIZE=32 -CONFIG_START_YEAR=2007 -CONFIG_START_MONTH=2 -CONFIG_START_DAY=27 -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n -CONFIG_SDCLONE_DISABLE=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve sysem performance -# -CONFIG_ARCH_MEMCPY=y -CONFIG_ARCH_MEMCMP=y -CONFIG_ARCH_MEMMOVE=y -CONFIG_ARCH_MEMSET=y -CONFIG_ARCH_STRCMP=y -CONFIG_ARCH_STRCPY=y -CONFIG_ARCH_STRNCPY=y -CONFIG_ARCH_STRLEN=y -CONFIG_ARCH_STRNLEN=y -CONFIG_ARCH_BZERO=n -CONFIG_ARCH_MATH_H=y -CONFIG_ARCH_STDINT_H=y -CONFIG_ARCH_STDBOOL_H=y - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# CONFIG_NAME_MAX - The maximum size of a file name. -# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate -# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_NUNGET_CHARS - Number of characters that can be -# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=64 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=4 -CONFIG_NFILE_DESCRIPTORS=32 -CONFIG_NFILE_STREAMS=16 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=64 -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=32 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=4 -CONFIG_PREALLOC_WDOGS=32 -CONFIG_PREALLOC_TIMERS=8 -CONFIG_STDIO_LINEBUFFER=y - -# -# FAT filesystem configuration -# CONFIG_FS_FAT - Enable FAT filesystem support -# CONFIG_FAT_SECTORSIZE - Max supported sector size -# CONFIG_FS_ROMFS - Enable ROMFS filesystem support -CONFIG_FS_FAT=n -CONFIG_FS_ROMFS=n - -# -# TCP/IP and UDP support via uIP -# CONFIG_NET - Enable or disable all network features -# CONFIG_NET_IPv6 - Build in support for IPv6 -# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. -# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options -# CONFIG_NET_BUFSIZE - uIP buffer size -# CONFIG_NET_TCP - TCP support on or off -# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) -# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers -# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) -# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until -# accept() is called. The size of the backlog is selected when listen() is called. -# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) -# CONFIG_NET_UDP - UDP support on or off -# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off -# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections -# CONFIG_NET_ICMP - ICMP ping response support on or off -# CONFIG_NET_ICMP_PING - ICMP ping request support on or off -# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address -# CONFIG_NET_STATISTICS - uIP statistics on or off -# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window -# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table -# CONFIG_NET_BROADCAST - Broadcast support -# CONFIG_NET_LLH_LEN - The link level header length -# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates -CONFIG_NET=y -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=5 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=1514 -CONFIG_NET_TCP=y -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=y -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=y -CONFIG_NET_ICMP_PING=y -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW=128 -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n -#CONFIG_NET_LLH_LEN=14 -#CONFIG_NET_FWCACHE_SIZE=2 - -# -# UIP Network Utilities -# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP -# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 - -# -# Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|10<<8|2) -CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|10<<8|1) -CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_UIP_DHCPC=n - -# -# Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) -CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) -CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) - -# -# Settings for examples/nsh -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_CMD_SIZE=40 -CONFIG_NSH_STACKSIZE=4096 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) -CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) -CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2 after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=4096 -CONFIG_USERMAIN_STACKSIZE=4096 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=8192 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= - - -########################################## -# RGMP specific configuration -########################################## - -# -# VNET -# -CONFIG_NET_VNET=y -CONFIG_VNET_NINTERFACES=1 - -# -# Serial port -# -CONFIG_COM1=y -CONFIG_COM2=y -CONFIG_COM3=n -CONFIG_COM4=n - -# -# E1000 -# -CONFIG_NET_E1000=n -CONFIG_E1000_N_TX_DESC=128 -CONFIG_E1000_N_RX_DESC=128 -CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/default/setenv.sh b/nuttx/configs/rgmp/default/setenv.sh deleted file mode 100755 index a6a533e47..000000000 --- a/nuttx/configs/rgmp/default/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# config/rgmp/default/setenv.sh -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi - -#export NUTTX_BIN= -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/include/stdarg.h b/nuttx/configs/rgmp/include/stdarg.h index 8f879a819..b748243d1 100755 --- a/nuttx/configs/rgmp/include/stdarg.h +++ b/nuttx/configs/rgmp/include/stdarg.h @@ -1,23 +1,8 @@ -#ifndef _RGMP_STDARG_H -#define _RGMP_STDARG_H +#ifndef _CONFIG_RGMP_STDARG_H +#define _CONFIG_RGMP_STDARG_H -typedef char *va_list; -#define __va_size(type) \ - (((sizeof(type) + sizeof(long) - 1) / sizeof(long)) * sizeof(long)) +#include -#ifndef va_start -#define va_start(ap, last) \ - ((ap) = (va_list)&(last) + __va_size(last)) -#endif - -#ifndef va_arg -#define va_arg(ap, type) \ - (*(type *)((ap) += __va_size(type), (ap) - __va_size(type))) -#endif - -#ifndef va_end -#define va_end(ap) ((void)0) -#endif #endif diff --git a/nuttx/configs/rgmp/nsh/Make.defs b/nuttx/configs/rgmp/nsh/Make.defs deleted file mode 100644 index 41073c249..000000000 --- a/nuttx/configs/rgmp/nsh/Make.defs +++ /dev/null @@ -1,119 +0,0 @@ -############################################################################ -# configs/rgmp/nsh/Make.defs -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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}/.config - -RGMPLIBDIR := $(RGMP_INST_DIR)/lib -RGMPINCDIR := $(RGMP_INST_DIR)/include -RGMPLKSCPT := $(RGMP_INST_DIR)/etc/x86.ld - -HOSTOS = ${shell uname -o} - -ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -O2 -gstabs -else - ARCHOPTIMIZATION = -O2 -endif - -ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector -ARCHPICFLAGS = -fpic -ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -ARCHDEFINES = -ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ - -I$(TOPDIR)/configs/rgmp/include -ARCHSCRIPT = - -CROSSDEV = -CC = $(CROSSDEV)gcc -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump - -CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe -CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ - -OBJEXT = .o -LIBEXT = .a - -ifeq ($(HOSTOS),Cygwin) - EXEEXT = .exe -else - EXEEXT = -endif - -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") - LDFLAGS += -g -endif -LDFLAGS += -nostdlib -EXTRA_LIBS = - -define PREPROCESS - @echo "CPP: $1->$2" - @$(CPP) $(CPPFLAGS) $1 -o $2 -endef - -define COMPILE - @echo "CC: $1" - @$(CC) -c $(CFLAGS) $1 -o $2 -endef - -define ASSEMBLE - @echo "AS: $1" - @$(CC) -c $(AFLAGS) $1 -o $2 -endef - -define ARCHIVE - echo "AR: $2"; \ - $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } -endef - -define CLEAN - @rm -f *.o *.a -endef - -MKDEP = $(TOPDIR)/tools/mkdeps.sh - -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe -HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/nsh/appconfig b/nuttx/configs/rgmp/nsh/appconfig deleted file mode 100644 index 092554129..000000000 --- a/nuttx/configs/rgmp/nsh/appconfig +++ /dev/null @@ -1,54 +0,0 @@ -############################################################################ -# configs/rgmp/nsh/appconfig -# -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt -# -# 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nsh - -# The NSH Library - -CONFIGURED_APPS += nshlib - -# Networking support - -ifeq ($(CONFIG_NET),y) -CONFIGURED_APPS += netutils/uiplib -CONFIGURED_APPS += netutils/dhcpc -CONFIGURED_APPS += netutils/resolv -CONFIGURED_APPS += netutils/tftpc -CONFIGURED_APPS += netutils/webclient -endif - - diff --git a/nuttx/configs/rgmp/nsh/defconfig b/nuttx/configs/rgmp/nsh/defconfig deleted file mode 100644 index 081204024..000000000 --- a/nuttx/configs/rgmp/nsh/defconfig +++ /dev/null @@ -1,442 +0,0 @@ -############################################################################ -# configs/rgmp/nsh/defconfig -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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. -# -############################################################################ -# -# Architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_name - for use in C code. This identifies the particular -# processor architecture (CONFIG_ARCH_SIM). -# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# -CONFIG_ARCH=rgmp -CONFIG_ARCH_RGMP=y -CONFIG_ARCH_BOARD=rgmp -CONFIG_ARCH_BOARD_RGMP=y - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# CONFIG_DEBUG_SYMBOLS - build without optimization and with -# debug symbols (needed for use with a debugger). -# CONFIG_MM_REGIONS - If the architecture includes multiple -# regions of memory to allocate from, this specifies the -# number of memory regions that the memory manager must -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_JULIAN_TIME - Enables Julian time conversions -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket -# desciptors by task_create() when a new task is started. If -# set, all sockets will appear to be closed in the new task. -# -#CONFIG_APPS_DIR= -CONFIG_DEBUG=y -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=y -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y -CONFIG_MSEC_PER_TICK=1 -CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n -CONFIG_TASK_NAME_SIZE=32 -CONFIG_START_YEAR=2007 -CONFIG_START_MONTH=2 -CONFIG_START_DAY=27 -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n -CONFIG_SDCLONE_DISABLE=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve sysem performance -# -CONFIG_ARCH_MEMCPY=y -CONFIG_ARCH_MEMCMP=y -CONFIG_ARCH_MEMMOVE=y -CONFIG_ARCH_MEMSET=y -CONFIG_ARCH_STRCMP=y -CONFIG_ARCH_STRCPY=y -CONFIG_ARCH_STRNCPY=y -CONFIG_ARCH_STRLEN=y -CONFIG_ARCH_STRNLEN=y -CONFIG_ARCH_BZERO=n -CONFIG_ARCH_MATH_H=y -CONFIG_ARCH_STDINT_H=y -CONFIG_ARCH_STDBOOL_H=y - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# CONFIG_NAME_MAX - The maximum size of a file name. -# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate -# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_NUNGET_CHARS - Number of characters that can be -# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=64 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=4 -CONFIG_NFILE_DESCRIPTORS=32 -CONFIG_NFILE_STREAMS=16 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=64 -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=32 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=4 -CONFIG_PREALLOC_WDOGS=32 -CONFIG_PREALLOC_TIMERS=8 -CONFIG_STDIO_LINEBUFFER=y - -# -# FAT filesystem configuration -# CONFIG_FS_FAT - Enable FAT filesystem support -# CONFIG_FAT_SECTORSIZE - Max supported sector size -# CONFIG_FS_ROMFS - Enable ROMFS filesystem support -CONFIG_FS_FAT=n -CONFIG_FS_ROMFS=n - -# -# TCP/IP and UDP support via uIP -# CONFIG_NET - Enable or disable all network features -# CONFIG_NET_IPv6 - Build in support for IPv6 -# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. -# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options -# CONFIG_NET_BUFSIZE - uIP buffer size -# CONFIG_NET_TCP - TCP support on or off -# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) -# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers -# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) -# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until -# accept() is called. The size of the backlog is selected when listen() is called. -# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) -# CONFIG_NET_UDP - UDP support on or off -# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off -# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections -# CONFIG_NET_ICMP - ICMP ping response support on or off -# CONFIG_NET_ICMP_PING - ICMP ping request support on or off -# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address -# CONFIG_NET_STATISTICS - uIP statistics on or off -# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window -# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table -# CONFIG_NET_BROADCAST - Broadcast support -# CONFIG_NET_LLH_LEN - The link level header length -# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates -CONFIG_NET=y -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=5 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=1514 -CONFIG_NET_TCP=y -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=y -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=y -CONFIG_NET_ICMP_PING=y -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -CONFIG_NET_RECEIVE_WINDOW=128 -CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n -#CONFIG_NET_LLH_LEN=14 -#CONFIG_NET_FWCACHE_SIZE=2 - -# -# UIP Network Utilities -# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP -# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 - -# -# Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|0<<8|128) -CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|0<<8|1) -CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_UIP_DHCPC=n - -# -# Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) -CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) -CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer -# CONFIG_NSH_STRERROR - Use strerror(errno) -# CONFIG_NSH_LINELEN - Maximum length of one command line -# CONFIG_NSH_STACKSIZE - Stack size to use for new threads. -# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# -# If CONFIG_NSH_TELNET is selected: -# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size -# CONFIG_NSH_DHCPC - Obtain address using DHCP -# CONFIG_NSH_IPADDR - Provides static IP address -# CONFIG_NSH_DRIPADDR - Provides static router IP address -# CONFIG_NSH_NETMASK - Provides static network mask -# CONFIG_NSH_NOMAC - Use a bogus MAC address -# -# If CONFIG_NSH_ROMFSETC is selected: -# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint -# CONFIG_NSH_INITSCRIPT - Relative path to init script -# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor -# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size -# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor -# CONFIG_NSH_FATSECTSIZE - FAT FS sector size -# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors -# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint -# -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_CMD_SIZE=40 -CONFIG_NSH_STACKSIZE=4096 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=(192<<24|168<<16|10<<8|2) -CONFIG_NSH_DRIPADDR=(192<<24|168<<16|10<<8|1) -CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2 after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=4096 -CONFIG_USERMAIN_STACKSIZE=4096 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=8192 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= - - -########################################## -# RGMP specific configuration -########################################## - -# -# VNET -# -CONFIG_NET_VNET=y -CONFIG_VNET_NINTERFACES=1 - -# -# Serial port -# -CONFIG_COM1=y -CONFIG_COM2=y -CONFIG_COM3=n -CONFIG_COM4=n - -# -# E1000 -# -CONFIG_NET_E1000=n -CONFIG_E1000_N_TX_DESC=128 -CONFIG_E1000_N_RX_DESC=128 -CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/nsh/setenv.sh b/nuttx/configs/rgmp/nsh/setenv.sh deleted file mode 100755 index 6caf8de84..000000000 --- a/nuttx/configs/rgmp/nsh/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# config/rgmp/nsh/setenv.sh -# -# Copyright (C) 2011 Yu Qiang. All rights reserved. -# Copyright (C) 2011 Gregory Nutt. All rights reserved. -# Authors: Yu Qiang -# Gregory Nutt -# -# 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi - -#export NUTTX_BIN= -#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/x86/default/Make.defs b/nuttx/configs/rgmp/x86/default/Make.defs new file mode 100644 index 000000000..c5e7c532f --- /dev/null +++ b/nuttx/configs/rgmp/x86/default/Make.defs @@ -0,0 +1,116 @@ +############################################################################ +# configs/rgmp/default/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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}/.config + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 +ARCHSCRIPT = + +CROSSDEV = +CC = $(CROSSDEV)gcc +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/x86/default/appconfig b/nuttx/configs/rgmp/x86/default/appconfig new file mode 100644 index 000000000..e1397db20 --- /dev/null +++ b/nuttx/configs/rgmp/x86/default/appconfig @@ -0,0 +1,39 @@ +############################################################################ +# configs/sim/default/appconfig +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/rgmp + diff --git a/nuttx/configs/rgmp/x86/default/defconfig b/nuttx/configs/rgmp/x86/default/defconfig new file mode 100644 index 000000000..0e07b7f07 --- /dev/null +++ b/nuttx/configs/rgmp/x86/default/defconfig @@ -0,0 +1,417 @@ +############################################################################ +# configs/rgmp/default/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=rgmp +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD=rgmp +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=n +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_RECEIVE_WINDOW=128 +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Settings for examples/uip +CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|10<<8|2) +CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|10<<8|1) +CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_UIP_DHCPC=n + +# +# Settings for examples/nettest +CONFIG_EXAMPLE_NETTEST_SERVER=n +CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLE_NETTEST_NOMAC=n +CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) + +# +# Settings for examples/nsh +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_STACKSIZE=4096 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) +CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=x86 + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + +# +# Serial port +# +CONFIG_COM1=y +CONFIG_COM2=y +CONFIG_COM3=n +CONFIG_COM4=n + +# +# E1000 +# +CONFIG_NET_E1000=n +CONFIG_E1000_N_TX_DESC=128 +CONFIG_E1000_N_RX_DESC=128 +CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/x86/default/setenv.sh b/nuttx/configs/rgmp/x86/default/setenv.sh new file mode 100644 index 000000000..a6a533e47 --- /dev/null +++ b/nuttx/configs/rgmp/x86/default/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/default/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/rgmp/x86/nsh/Make.defs b/nuttx/configs/rgmp/x86/nsh/Make.defs new file mode 100644 index 000000000..22d29c35a --- /dev/null +++ b/nuttx/configs/rgmp/x86/nsh/Make.defs @@ -0,0 +1,116 @@ +############################################################################ +# configs/rgmp/nsh/Make.defs +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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}/.config + +RGMPLIBDIR := $(RGMP_INST_DIR)/lib +RGMPINCDIR := $(RGMP_INST_DIR)/include +RGMPLKSCPT := $(RGMP_INST_DIR)/etc/rgmp.ld + +HOSTOS = ${shell uname -o} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -O2 -gstabs +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin -nostdinc -fno-stack-protector +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include -I$(RGMPINCDIR) \ + -I$(TOPDIR)/configs/rgmp/include -I$(TOPDIR)/arch/rgmp/include/x86 +ARCHSCRIPT = + +CROSSDEV = +CC = $(CROSSDEV)gcc +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +LDFLAGS += -nostdlib +EXTRA_LIBS = + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/rgmp/x86/nsh/appconfig b/nuttx/configs/rgmp/x86/nsh/appconfig new file mode 100644 index 000000000..092554129 --- /dev/null +++ b/nuttx/configs/rgmp/x86/nsh/appconfig @@ -0,0 +1,54 @@ +############################################################################ +# configs/rgmp/nsh/appconfig +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nsh + +# The NSH Library + +CONFIGURED_APPS += nshlib + +# Networking support + +ifeq ($(CONFIG_NET),y) +CONFIGURED_APPS += netutils/uiplib +CONFIGURED_APPS += netutils/dhcpc +CONFIGURED_APPS += netutils/resolv +CONFIGURED_APPS += netutils/tftpc +CONFIGURED_APPS += netutils/webclient +endif + + diff --git a/nuttx/configs/rgmp/x86/nsh/defconfig b/nuttx/configs/rgmp/x86/nsh/defconfig new file mode 100644 index 000000000..89bc46643 --- /dev/null +++ b/nuttx/configs/rgmp/x86/nsh/defconfig @@ -0,0 +1,447 @@ +############################################################################ +# configs/rgmp/nsh/defconfig +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=rgmp +CONFIG_ARCH_RGMP=y +CONFIG_ARCH_BOARD=rgmp +CONFIG_ARCH_BOARD_RGMP=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=y +CONFIG_ARCH_MEMMOVE=y +CONFIG_ARCH_MEMSET=y +CONFIG_ARCH_STRCMP=y +CONFIG_ARCH_STRCPY=y +CONFIG_ARCH_STRNCPY=y +CONFIG_ARCH_STRLEN=y +CONFIG_ARCH_STRNLEN=y +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_MATH_H=y +CONFIG_ARCH_STDINT_H=y +CONFIG_ARCH_STDBOOL_H=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 +CONFIG_STDIO_LINEBUFFER=y + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=5 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=1514 +CONFIG_NET_TCP=y +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_PING=y +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +CONFIG_NET_RECEIVE_WINDOW=128 +CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Settings for examples/uip +CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_UIP_DHCPC=n + +# +# Settings for examples/nettest +CONFIG_EXAMPLE_NETTEST_SERVER=n +CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLE_NETTEST_NOMAC=n +CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_STACKSIZE - Stack size to use for new threads. +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +# +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_CMD_SIZE=40 +CONFIG_NSH_STACKSIZE=4096 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(192<<24|168<<16|10<<8|2) +CONFIG_NSH_DRIPADDR=(192<<24|168<<16|10<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2 after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + + +########################################## +# RGMP specific configuration +########################################## + +# +# arch +# +CONFIG_RGMP_SUBARCH=x86 + +# +# VNET +# +CONFIG_NET_VNET=y +CONFIG_VNET_NINTERFACES=1 + +# +# Serial port +# +CONFIG_COM1=y +CONFIG_COM2=y +CONFIG_COM3=n +CONFIG_COM4=n + +# +# E1000 +# +CONFIG_NET_E1000=n +CONFIG_E1000_N_TX_DESC=128 +CONFIG_E1000_N_RX_DESC=128 +CONFIG_E1000_BUFF_SIZE=0x800 diff --git a/nuttx/configs/rgmp/x86/nsh/setenv.sh b/nuttx/configs/rgmp/x86/nsh/setenv.sh new file mode 100644 index 000000000..6caf8de84 --- /dev/null +++ b/nuttx/configs/rgmp/x86/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# config/rgmp/nsh/setenv.sh +# +# Copyright (C) 2011 Yu Qiang. All rights reserved. +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Authors: Yu Qiang +# Gregory Nutt +# +# 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" diff --git a/nuttx/drivers/net/e1000.c b/nuttx/drivers/net/e1000.c index 481c2123e..ce6192ac0 100644 --- a/nuttx/drivers/net/e1000.c +++ b/nuttx/drivers/net/e1000.c @@ -58,10 +58,10 @@ #include #include -#include #include -#include #include +#include +#include #include "e1000.h" /**************************************************************************** diff --git a/nuttx/drivers/net/e1000.h b/nuttx/drivers/net/e1000.h index 04f986fef..6614ad77e 100644 --- a/nuttx/drivers/net/e1000.h +++ b/nuttx/drivers/net/e1000.h @@ -46,7 +46,7 @@ #include #include -#include +#include /**************************************************************************** * Pre-processor Definitions -- cgit v1.2.3