summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttX.html2
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html66
-rw-r--r--nuttx/Makefile14
-rw-r--r--nuttx/TODO2
-rw-r--r--nuttx/arch/sim/src/Makefile3
-rw-r--r--nuttx/arch/sim/src/up_blockdevice.c2
-rw-r--r--nuttx/arch/sim/src/up_idle.c8
-rw-r--r--nuttx/arch/sim/src/up_initialize.c3
-rw-r--r--nuttx/arch/sim/src/up_internal.h7
-rw-r--r--nuttx/arch/sim/src/up_uipdriver.c329
-rw-r--r--nuttx/configs/README.txt27
-rw-r--r--nuttx/configs/c5471evm/defconfig44
-rw-r--r--nuttx/configs/m68332evb/defconfig44
-rw-r--r--nuttx/configs/mcu123-lpc214x/defconfig44
-rw-r--r--nuttx/configs/ntosd-dm320/defconfig44
-rw-r--r--nuttx/configs/pjrc-8051/defconfig44
-rw-r--r--nuttx/configs/sim/defconfig44
18 files changed, 726 insertions, 3 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 73fcfb3e9..97d0b44a6 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -201,3 +201,5 @@
0.2.9 2007-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Imported uIP into the tree (see
+ http://www.sics.se/~adam/uip/index.php/Main_Page)
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 840879ef1..7f8f7d8d1 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -635,6 +635,8 @@ Other memory:
0.2.9 2007-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Imported uIP into the tree (see
+ http://www.sics.se/~adam/uip/index.php/Main_Page)
</pre></ul>
<table width ="100%">
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 38ab0c31e..26bf11055 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -1294,6 +1294,72 @@ The system can be re-made subsequently by just typing <code>make</code>.
</li>
</ul>
+<h2>Network Support</h2>
+<h3>TCP/IP support via uIP</h2>
+<ul>
+ <li>
+ <code>CONFIG_NET_UIP</code>: Enable or disable all uIP features
+ </li>
+ <li>
+ <code>CONFIG_NET_UIP_IPv6</code>: Build in support for IPv6
+ </li>
+ <li>
+ <code>CONFIG_UIP_MAX_CONNECTIONS</code>: Maximum number of TCP connections
+ </li>
+ <li>
+ <code>CONFIG_UIP_MAX_LISTENPORTS</code>: Maximum number of listening TCP ports
+ </li>
+ <li>
+ <code>CONFIG_UIP_BUFFER_SIZE</code>: uIP buffer size
+ </li>
+ <li>
+ <code>CONFIG_UIP_LOGGING</code>: Logging on or off
+ </li>
+ <li>
+ <code>CONFIG_UIP_UDP</code>: UDP support on or off
+ </li>
+ <li>
+ <code>CONFIG_UIP_UDP_CHECKSUMS</code>: UDP checksums on or off
+ </li>
+ <li>
+ <code>CONFIG_UIP_UDP_CONNS</code>: The maximum amount of concurrent UDP connections
+ </li>
+ <li>
+ <code>CONFIG_UIP_STATISTICS</code>: uIP statistics on or off
+ </li>
+ <li>
+ <code>CONFIG_UIP_PINGADDRCONF</code>: Use "ping" packet for setting IP address
+ </li>
+ <li>
+ <code>CONFIG_UIP_RECEIVE_WINDOW</code>: The size of the advertised receiver's window
+ </li>
+ <li>
+ <code>CONFIG_UIP_ARPTAB_SIZE</code>: The size of the ARP table
+ </li>
+ <li>
+ <code>CONFIG_UIP_BROADCAST</code>: Broadcast support
+ </li>
+ <li>
+ <code>CONFIG_UIP_LLH_LEN</code>: The link level header length
+ </li>
+ <li>
+ <code>CONFIG_UIP_EXTERNAL_BUFFER</code>: Incoming packet buffer (uip_buf) is defined externally
+ </li>
+ <li>
+ <code>CONFIG_UIP_FWCACHE_SIZE</code>: number of packets to remember when looking for duplicates
+ </li>
+</ul>
+
+<h3>UIP Network Utilities</h3>
+<ul>
+ <li>
+ <code>CONFIG_UIP_DHCP_LIGHT</code>: Reduces size of DHCP
+ </li>
+ <li>
+ <code>CONFIG_UIP_RESOLV_ENTRIES</code>: Number of resolver entries
+ </li>
+</ul>
+
<h2>Stack and heap information</h2>
<ul>
diff --git a/nuttx/Makefile b/nuttx/Makefile
index 2844bbf3b..5050b3086 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -51,6 +51,10 @@ BOARD_DIR = configs/$(CONFIG_ARCH_BOARD)
NONFSDIRS = sched lib $(ARCH_SRC) mm examples/$(CONFIG_EXAMPLE)
FSDIRS = fs drivers
+ifeq ($(CONFIG_NET_UIP),y)
+NONFSDIRS += net netutils
+endif
+
# CLEANDIRS are the directories that will clean in. These are
# all directories that we know about.
# MAKEDIRS are the directories in which we will build targets
@@ -75,6 +79,10 @@ ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
LINKLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT)
endif
+ifeq ($(CONFIG_NET_UIP),y)
+LINKLIBS += net/libnet$(LIBEXT) netutils/libnetutils$(LIBEXT)
+endif
+
# This is the name of the final target
BIN = nuttx$(EXEEXT)
@@ -184,6 +192,12 @@ $(ARCH_SRC)/libarch$(LIBEXT): context
mm/libmm$(LIBEXT): context
$(MAKE) -C mm TOPDIR=$(TOPDIR) libmm$(LIBEXT)
+net/libnet$(LIBEXT): context
+ $(MAKE) -C net TOPDIR=$(TOPDIR) libnet$(LIBEXT)
+
+netutils/libnetutils$(LIBEXT): context
+ $(MAKE) -C netutils TOPDIR=$(TOPDIR) libnetutils$(LIBEXT)
+
fs/libfs$(LIBEXT): context
$(MAKE) -C fs TOPDIR=$(TOPDIR) libfs$(LIBEXT)
diff --git a/nuttx/TODO b/nuttx/TODO
index c6f8b40f8..3f6825e73 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -29,7 +29,7 @@ o C++ Support
- Need to call static constructors
o Network
-- Port FreeBSD TCP/IP stack
+- Finish integratin of uIP
o USB
- Implement USB device support
diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
index 35ea8668a..70b570e32 100644
--- a/nuttx/arch/sim/src/Makefile
+++ b/nuttx/arch/sim/src/Makefile
@@ -49,6 +49,9 @@ CSRCS = up_initialize.c up_idle.c up_interruptcontext.c \
ifeq ($(CONFIG_FS_FAT),y)
CSRCS += up_blockdevice.c up_deviceimage.c
endif
+ifeq ($(CONFIG_NET_UIP),y)
+CSRCS += up_uipdriver.c
+endif
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/arch/sim/src/up_blockdevice.c b/nuttx/arch/sim/src/up_blockdevice.c
index 4bece0a2f..60dbcd021 100644
--- a/nuttx/arch/sim/src/up_blockdevice.c
+++ b/nuttx/arch/sim/src/up_blockdevice.c
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
diff --git a/nuttx/arch/sim/src/up_idle.c b/nuttx/arch/sim/src/up_idle.c
index 3ca8c094a..95e119240 100644
--- a/nuttx/arch/sim/src/up_idle.c
+++ b/nuttx/arch/sim/src/up_idle.c
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
@@ -80,5 +80,11 @@ void up_idle(void)
*/
sched_process_timer();
+
+ /* Run the network if enabled */
+
+#ifdef CONFIG_NET_UIP
+ uipdriver_loop();
+#endif
}
diff --git a/nuttx/arch/sim/src/up_initialize.c b/nuttx/arch/sim/src/up_initialize.c
index 805c88b45..427360c10 100644
--- a/nuttx/arch/sim/src/up_initialize.c
+++ b/nuttx/arch/sim/src/up_initialize.c
@@ -86,4 +86,7 @@ void up_initialize(void)
devnull_register(); /* Standard /dev/null */
up_devconsole(); /* Our private /dev/console */
up_registerblockdevice(); /* Our simulated block device /dev/blkdev */
+#ifdef CONFIG_NET_UIP
+ uipdriver_init(); /* Our "real" netwok driver */
+#endif
}
diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h
index d7e6588cb..ab3df0ff5 100644
--- a/nuttx/arch/sim/src/up_internal.h
+++ b/nuttx/arch/sim/src/up_internal.h
@@ -107,5 +107,12 @@ extern void up_registerblockdevice(void);
extern char *up_deviceimage(void);
+/* up_uipdriver.c *********************************************************/
+
+#ifdef CONFIG_NET_UIP
+extern int uipdriver_init(void);
+extern void uipdriver_loop(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_UP_INTERNAL_H */
diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c
new file mode 100644
index 000000000..e68c4fccd
--- /dev/null
+++ b/nuttx/arch/sim/src/up_uipdriver.c
@@ -0,0 +1,329 @@
+/****************************************************************************
+ * up_uipdriver.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based on code from uIP which also has a BSD-like license:
+ *
+ * Copyright (c) 2001, Adam Dunkels.
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sys/ioctl.h>
+#include <sys/socket.h>
+#include <sys/time.h>
+#include <sys/uio.h>
+#include <sys/socket.h>
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <unistd.h>
+#include <string.h>
+#include <fcntl.h>
+#include <string.h>
+#include <time.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/uip/uip.h>
+#include <net/uip/uip-arch.h>
+#include <net/uip/uip-arp.h>
+
+#ifdef linux
+# include <sys/ioctl.h>
+# include <linux/if.h>
+# include <linux/if_tun.h>
+# define DEVTAP "/dev/net/tun"
+#else /* linux */
+# define DEVTAP "/dev/tap0"
+#endif /* linux */
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+#define BUF ((struct uip_eth_hdr *)&uip_buf[0])
+
+#define UIP_DRIPADDR0 192
+#define UIP_DRIPADDR1 168
+#define UIP_DRIPADDR2 0
+#define UIP_DRIPADDR3 1
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct timer
+{
+ uint32 interval;
+ uint32 start;
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+static int drop = 0;
+#endif
+static int fd;
+static struct timer periodic_timer;
+static struct timer arp_timer;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static uint32 gettime( void )
+{
+ struct timespec tm;
+ (void)clock_gettime(CLOCK_REALTIME, &tm);
+ return tm.tv_sec*1000 + tm.tv_nsec/1000000;
+}
+
+static void timer_set( struct timer *t, unsigned int interval )
+{
+ t->interval = interval;
+ t->start = gettime();
+}
+
+static boolean timer_expired( struct timer *t )
+{
+ return (gettime() - t->start) >= t->interval;
+}
+
+void timer_reset(struct timer *t)
+{
+ t->start += t->interval;
+}
+
+static void tapdev_init(void)
+{
+ char buf[1024];
+
+ fd = open(DEVTAP, O_RDWR);
+ if(fd == -1)
+ {
+ lib_rawprintf("tapdev: tapdev_init: open");
+ return;
+ }
+
+#ifdef linux
+ {
+ struct ifreq ifr;
+ memset(&ifr, 0, sizeof(ifr));
+ ifr.ifr_flags = IFF_TAP|IFF_NO_PI;
+ if (ioctl(fd, TUNSETIFF, (void *) &ifr) < 0)
+ {
+ lib_rawprintf(buf);
+ return;
+ }
+ }
+#endif /* Linux */
+
+ snprintf(buf, sizeof(buf), "ifconfig tap0 inet %d.%d.%d.%d",
+ UIP_DRIPADDR0, UIP_DRIPADDR1, UIP_DRIPADDR2, UIP_DRIPADDR3);
+ system(buf);
+}
+
+static unsigned int tapdev_read(void)
+{
+ fd_set fdset;
+ struct timeval tv;
+ int ret;
+
+ tv.tv_sec = 0;
+ tv.tv_usec = 1000;
+
+ FD_ZERO(&fdset);
+ FD_SET(fd, &fdset);
+
+ ret = select(fd + 1, &fdset, NULL, NULL, &tv);
+ if(ret == 0)
+ {
+ return 0;
+ }
+ ret = read(fd, uip_buf, UIP_BUFSIZE);
+ if(ret == -1)
+ {
+ lib_rawprintf("tap_dev: tapdev_read: read");
+ }
+
+ dbg("tap_dev: tapdev_read: read %d bytes\n", ret);
+ {
+ int i;
+ for(i = 0; i < 20; i++)
+ {
+ vdbg("%x ", uip_buf[i]);
+ }
+ vdbg("\n");
+ }
+
+#ifdef CONFIG_DEBUG
+ check_checksum(uip_buf, ret);
+#endif
+ return ret;
+}
+
+static void tapdev_send(void)
+{
+ int ret;
+#ifdef CONFIG_DEBUG
+ dbg("tapdev_send: sending %d bytes\n", uip_len);
+ check_checksum(uip_buf, uip_len);
+
+ drop++;
+ if(drop % 8 == 7)
+ {
+ dbg("Dropped a packet!\n");
+ return;
+ }
+#endif
+
+ ret = write(fd, uip_buf, uip_len);
+ if(ret == -1)
+ {
+ perror("tap_dev: tapdev_send: writev");
+ exit(1);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void uipdriver_loop(void)
+{
+ int i;
+
+ uip_len = tapdev_read();
+ if (uip_len > 0)
+ {
+ if (BUF->type == htons(UIP_ETHTYPE_IP))
+ {
+ uip_arp_ipin();
+ uip_input();
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the global variable
+ * uip_len is set to a value > 0.
+ */
+
+ if (uip_len > 0)
+ {
+ uip_arp_out();
+ tapdev_send();
+ }
+ }
+ else if (BUF->type == htons(UIP_ETHTYPE_ARP))
+ {
+ uip_arp_arpin();
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the global variable
+ * uip_len is set to a value > 0.
+ */
+
+ if (uip_len > 0)
+ {
+ tapdev_send();
+ }
+ }
+ }
+ else if (timer_expired(&periodic_timer))
+ {
+ timer_reset(&periodic_timer);
+ for(i = 0; i < UIP_CONNS; i++)
+ {
+ uip_periodic(i);
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the global variable
+ * uip_len is set to a value > 0.
+ */
+
+ if (uip_len > 0)
+ {
+ uip_arp_out();
+ tapdev_send();
+ }
+ }
+
+#if UIP_UDP
+ for(i = 0; i < UIP_UDP_CONNS; i++)
+ {
+ uip_udp_periodic(i);
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the global variable
+ * uip_len is set to a value > 0.
+ */
+
+ if (uip_len > 0)
+ {
+ uip_arp_out();
+ tapdev_send();
+ }
+ }
+#endif /* UIP_UDP */
+
+ /* Call the ARP timer function every 10 seconds. */
+
+ if (timer_expired(&arp_timer))
+ {
+ timer_reset(&arp_timer);
+ uip_arp_timer();
+ }
+ }
+}
+
+int uipdriver_init(void)
+{
+ timer_set(&periodic_timer, CLK_TCK / 2);
+ timer_set(&arp_timer, CLK_TCK * 10);
+
+ tapdev_init();
+ uip_init();
+ return OK;
+}
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index df1516c66..3d7cc69db 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -208,6 +208,33 @@ defconfig -- This is a configuration file similar to the Linux
structures. The system manages a pool of preallocated
watchdog structures to minimize dynamic allocations
+ TCP/IP support via uIP
+ CONFIG_NET_UIP - Enable or disable all uIP features
+ CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+ CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+ CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+ CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+ CONFIG_UIP_LOGGING - Logging on or off
+ CONFIG_UIP_UDP - UDP support on or off
+ CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+ CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP
+ connections
+ CONFIG_UIP_STATISTICS - uIP statistics on or off
+ CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+ CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's
+ window
+ CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+ CONFIG_UIP_BROADCAST - Broadcast support
+ CONFIG_UIP_LLH_LEN - The link level header length
+ CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf)
+ is defined externally
+ CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when
+ looking for duplicates
+
+ UIP Network Utilities
+ CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+ CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+
Stack and heap information
CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/c5471evm/defconfig b/nuttx/configs/c5471evm/defconfig
index 840b410ed..4c7acd09a 100644
--- a/nuttx/configs/c5471evm/defconfig
+++ b/nuttx/configs/c5471evm/defconfig
@@ -250,6 +250,50 @@ CONFIG_PREALLOC_WDOGS=32
CONFIG_PREALLOC_TIMERS=8
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=n
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/m68332evb/defconfig b/nuttx/configs/m68332evb/defconfig
index 521045356..2621de854 100644
--- a/nuttx/configs/m68332evb/defconfig
+++ b/nuttx/configs/m68332evb/defconfig
@@ -239,6 +239,50 @@ CONFIG_PREALLOC_WDOGS=32
CONFIG_PREALLOC_TIMERS=8
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=n
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/mcu123-lpc214x/defconfig b/nuttx/configs/mcu123-lpc214x/defconfig
index 43b575fcf..40692b853 100644
--- a/nuttx/configs/mcu123-lpc214x/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/defconfig
@@ -263,6 +263,50 @@ CONFIG_PREALLOC_WDOGS=32
CONFIG_PREALLOC_TIMERS=8
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=n
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/ntosd-dm320/defconfig b/nuttx/configs/ntosd-dm320/defconfig
index 55753fdc0..0a95f364d 100644
--- a/nuttx/configs/ntosd-dm320/defconfig
+++ b/nuttx/configs/ntosd-dm320/defconfig
@@ -248,6 +248,50 @@ CONFIG_PREALLOC_WDOGS=32
CONFIG_PREALLOC_TIMERS=8
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=y
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/pjrc-8051/defconfig b/nuttx/configs/pjrc-8051/defconfig
index 6ae70d592..3857c85d8 100644
--- a/nuttx/configs/pjrc-8051/defconfig
+++ b/nuttx/configs/pjrc-8051/defconfig
@@ -236,6 +236,50 @@ CONFIG_PREALLOC_WDOGS=4
CONFIG_PREALLOC_TIMERS=0
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=y
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
diff --git a/nuttx/configs/sim/defconfig b/nuttx/configs/sim/defconfig
index e60848b0a..e2cd2a3a9 100644
--- a/nuttx/configs/sim/defconfig
+++ b/nuttx/configs/sim/defconfig
@@ -210,6 +210,50 @@ CONFIG_PREALLOC_TIMERS=8
CONFIG_FS_FAT=y
#
+# TCP/IP support via uIP
+# CONFIG_NET_UIP - Enable or disable all uIP features
+# CONFIG_NET_UIP_IPv6 - Build in support for IPv6
+# CONFIG_UIP_MAX_CONNECTIONS - Maximum number of TCP connections
+# CONFIG_UIP_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_UIP_BUFFER_SIZE - uIP buffer size
+# CONFIG_UIP_LOGGING - Logging on or off
+# CONFIG_UIP_UDP - UDP support on or off
+# CONFIG_UIP_UDP_CHECKSUMS - UDP checksums on or off
+# CONFIG_UIP_UDP_CONNS - The maximum amount of concurrent UDP connections
+# CONFIG_UIP_STATISTICS - uIP statistics on or off
+# CONFIG_UIP_PINGADDRCONF - Use "ping" packet for setting IP address
+# CONFIG_UIP_RECEIVE_WINDOW - The size of the advertised receiver's window
+# CONFIG_UIP_ARPTAB_SIZE - The size of the ARP table
+# CONFIG_UIP_BROADCAST - Broadcast support
+# CONFIG_UIP_LLH_LEN - The link level header length
+# CONFIG_UIP_EXTERNAL_BUFFER - Incoming packet buffer (uip_buf) is defined externally
+# CONFIG_UIP_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+CONFIG_NET_UIP=n
+CONFIG_NET_UIP_IPv6=n
+CONFIG_UIP_MAX_CONNECTIONS=40
+CONFIG_UIP_MAX_LISTENPORTS=40
+CONFIG_UIP_BUFFER_SIZE=420
+CONFIG_UIP_LOGGING=y
+CONFIG_UIP_UDP=n
+CONFIG_UIP_UDP_CHECKSUMS=y
+#CONFIG_UIP_UDP_CONNS=10
+CONFIG_UIP_STATISTICS=y
+#CONFIG_UIP_PINGADDRCONF=0
+#CONFIG_UIP_RECEIVE_WINDOW=
+#CONFIG_UIP_ARPTAB_SIZE=8
+CONFIG_UIP_BROADCAST=n
+#CONFIG_UIP_LLH_LEN=14
+CONFIG_UIP_EXTERNAL_BUFFER=n
+#CONFIG_UIP_FWCACHE_SIZE=2
+
+#
+# UIP Network Utilities
+# CONFIG_UIP_DHCP_LIGHT - Reduces size of DHCP
+# CONFIG_UIP_RESOLV_ENTRIES - Number of resolver entries
+CONFIG_UIP_DHCP_LIGHT=n
+CONFIG_UIP_RESOLV_ENTRIES=4
+
+#
# Stack and heap information
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP