aboutsummaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
committerpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
commit8a365179eafdf3aea98e60ab9f5882b200d4c759 (patch)
tree4f38d6d4cd80bd0b6e22e2bb534c3f117ce44e56 /nuttx/net
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Kconfig271
-rw-r--r--nuttx/net/Makefile123
-rw-r--r--nuttx/net/accept.c462
-rw-r--r--nuttx/net/bind.c197
-rw-r--r--nuttx/net/connect.c591
-rw-r--r--nuttx/net/getsockname.c218
-rw-r--r--nuttx/net/getsockopt.c289
-rw-r--r--nuttx/net/listen.c149
-rw-r--r--nuttx/net/net_arptimer.c134
-rw-r--r--nuttx/net/net_checksd.c88
-rw-r--r--nuttx/net/net_clone.c119
-rw-r--r--nuttx/net/net_close.c330
-rw-r--r--nuttx/net/net_dsec2timeval.c80
-rw-r--r--nuttx/net/net_dup.c149
-rw-r--r--nuttx/net/net_dup2.c125
-rw-r--r--nuttx/net/net_internal.h237
-rw-r--r--nuttx/net/net_monitor.c187
-rw-r--r--nuttx/net/net_poll.c354
-rw-r--r--nuttx/net/net_sockets.c313
-rw-r--r--nuttx/net/net_timeo.c85
-rw-r--r--nuttx/net/net_timeval2dsec.c76
-rw-r--r--nuttx/net/net_vfcntl.c234
-rw-r--r--nuttx/net/netdev_count.c102
-rw-r--r--nuttx/net/netdev_findbyaddr.c130
-rw-r--r--nuttx/net/netdev_findbyname.c111
-rw-r--r--nuttx/net/netdev_foreach.c114
-rw-r--r--nuttx/net/netdev_ioctl.c419
-rw-r--r--nuttx/net/netdev_register.c149
-rw-r--r--nuttx/net/netdev_sem.c178
-rw-r--r--nuttx/net/netdev_txnotify.c106
-rw-r--r--nuttx/net/netdev_unregister.c159
-rw-r--r--nuttx/net/recv.c77
-rw-r--r--nuttx/net/recvfrom.c1308
-rw-r--r--nuttx/net/send.c596
-rw-r--r--nuttx/net/sendto.c440
-rw-r--r--nuttx/net/setsockopt.c304
-rw-r--r--nuttx/net/socket.c286
-rw-r--r--nuttx/net/uip/Make.defs106
-rw-r--r--nuttx/net/uip/uip_arp.c431
-rw-r--r--nuttx/net/uip/uip_arptab.c257
-rw-r--r--nuttx/net/uip/uip_callback.c251
-rw-r--r--nuttx/net/uip/uip_chksum.c230
-rw-r--r--nuttx/net/uip/uip_icmpinput.c317
-rw-r--r--nuttx/net/uip/uip_icmpping.c379
-rw-r--r--nuttx/net/uip/uip_icmppoll.c103
-rw-r--r--nuttx/net/uip/uip_icmpsend.c168
-rwxr-xr-xnuttx/net/uip/uip_igmpgroup.c391
-rwxr-xr-xnuttx/net/uip/uip_igmpinit.c122
-rwxr-xr-xnuttx/net/uip/uip_igmpinput.c280
-rwxr-xr-xnuttx/net/uip/uip_igmpjoin.c160
-rwxr-xr-xnuttx/net/uip/uip_igmpleave.c182
-rwxr-xr-xnuttx/net/uip/uip_igmpmsg.c139
-rwxr-xr-xnuttx/net/uip/uip_igmppoll.c176
-rwxr-xr-xnuttx/net/uip/uip_igmpsend.c182
-rwxr-xr-xnuttx/net/uip/uip_igmptimer.c257
-rw-r--r--nuttx/net/uip/uip_initialize.c155
-rw-r--r--nuttx/net/uip/uip_input.c545
-rw-r--r--nuttx/net/uip/uip_internal.h272
-rw-r--r--nuttx/net/uip/uip_listen.c288
-rw-r--r--nuttx/net/uip/uip_lock.c218
-rwxr-xr-xnuttx/net/uip/uip_mcastmac.c132
-rw-r--r--nuttx/net/uip/uip_neighbor.c162
-rw-r--r--nuttx/net/uip/uip_neighbor.h61
-rw-r--r--nuttx/net/uip/uip_poll.c353
-rw-r--r--nuttx/net/uip/uip_send.c106
-rw-r--r--nuttx/net/uip/uip_setipid.c78
-rw-r--r--nuttx/net/uip/uip_tcpappsend.c215
-rw-r--r--nuttx/net/uip/uip_tcpbacklog.c403
-rw-r--r--nuttx/net/uip/uip_tcpcallback.c339
-rw-r--r--nuttx/net/uip/uip_tcpconn.c636
-rw-r--r--nuttx/net/uip/uip_tcpinput.c839
-rw-r--r--nuttx/net/uip/uip_tcppoll.c127
-rw-r--r--nuttx/net/uip/uip_tcpreadahead.c130
-rw-r--r--nuttx/net/uip/uip_tcpsend.c369
-rwxr-xr-xnuttx/net/uip/uip_tcpseqno.c173
-rw-r--r--nuttx/net/uip/uip_tcptimer.c250
-rw-r--r--nuttx/net/uip/uip_udpcallback.c90
-rw-r--r--nuttx/net/uip/uip_udpconn.c492
-rw-r--r--nuttx/net/uip/uip_udpinput.c156
-rw-r--r--nuttx/net/uip/uip_udppoll.c126
-rw-r--r--nuttx/net/uip/uip_udpsend.c177
81 files changed, 20313 insertions, 0 deletions
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
new file mode 100644
index 000000000..dc16150ba
--- /dev/null
+++ b/nuttx/net/Kconfig
@@ -0,0 +1,271 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config NET
+ bool "Networking support"
+ default n
+ ---help---
+ Enable or disable all network features
+
+if NET
+
+config NET_NOINTS
+ bool "Not interrupt driven"
+ default n
+ ---help---
+ NET_NOINT indicates that uIP not called from the interrupt level.
+ If NET_NOINTS is defined, critical sections will be managed with semaphores;
+ Otherwise, it assumed that uIP will be called from interrupt level handling
+ and critical sections will be managed by enabling and disabling interrupts.
+
+config NET_MULTIBUFFER
+ bool "Use multiple device-side I/O buffers"
+ default n
+ ---help---
+ Traditionally, uIP has used a single buffer for all incoming and
+ outgoing traffic. If this configuration is selected, then the
+ driver can manage multiple I/O buffers and can, for example,
+ be filling one input buffer while sending another output buffer.
+ Or, as another example, the driver may support queuing of concurrent
+ input/ouput and output transfers for better performance.
+
+config NET_IPv6
+ bool "IPv6"
+ default n
+ ---help---
+ Build in support for IPv6. Not fully implemented.
+
+config NSOCKET_DESCRIPTORS
+ int "Number of socket descriptor"
+ default 8
+ ---help---
+ Maximum number of socket descriptors per task/thread.
+
+config NET_NACTIVESOCKETS
+ int "Max socket operations"
+ ---help---
+ Maximum number of concurrent socket operations (recv, send, etc.).
+ Default: NET_TCP_CONNS+NET_UCP_CONNS
+
+config NET_SOCKOPTS
+ bool "Socket options"
+ default n
+ ---help---
+ Enable or disable support for socket options
+
+config NET_BUFSIZE
+ int "Network packet size"
+ default 562 if !NET_TCP && NET_UDP && !NET_SLIP
+ default 420 if NET_TCP && !NET_UDP && !NET_SLIP
+ default 296 if NET_SLIP
+ ---help---
+ uIP buffer size. Default: 562
+
+config NET_TCPURGDATA
+ bool "Urgent data"
+ default n
+ ---help---
+ Determines if support for TCP urgent data notification should be
+ compiled in. Urgent data (out-of-band data) is a rarely used TCP feature
+ that is very seldom would be required.
+
+config NET_TCP
+ bool "TCP/IP Networking"
+ default n
+ ---help---
+ TCP support on or off
+
+endif
+
+if NET_TCP
+config NET_TCP_CONNS
+ int "Number of TCP/IP connections"
+ default 8
+ ---help---
+ Maximum number of TCP/IP connections (all tasks)
+
+config NET_MAX_LISTENPORTS
+ int "Number of listening ports"
+ default 20
+ ---help---
+ Maximum number of listening TCP/IP ports (all tasks). Default: 20
+
+config NET_TCP_READAHEAD_BUFSIZE
+ bool "TCP/IP read-ahead buffer size"
+ default 562
+ ---help---
+ Size of TCP/IP read-ahead buffers
+
+config NET_NTCP_READAHEAD_BUFFERS
+ int "Number of TCP/IP read-ahead buffers"
+ default 8
+ ---help---
+ Number of TCP/IP read-ahead buffers (may be zero)
+
+config NET_TCPBACKLOG
+ bool "TCP/IP backlog support"
+ default n
+ ---help---
+ Incoming connections pend in a backlog until accept() is called.
+ The size of the backlog is selected when listen() is called.
+
+endif
+
+config NET_UDP
+ bool "UDP Networking"
+ default n
+ depends on NET
+ ---help---
+ Enable or disable UDP networking support.
+
+if NET_UDP
+config NET_UDP_CHECKSUMS
+ bool "UDP checksums"
+ default n
+ ---help---
+ Enable/disable UDP checksum support
+
+config NET_UDP_CONNS
+ int "Number of UDP sockets"
+ default 8
+ ---help---
+ The maximum amount of open concurrent UDP sockets
+
+config NET_BROADCAST
+ bool "UDP broadcast Rx support"
+ default n
+ ---help---
+ Incoming UDP broadcast support
+
+endif
+
+config NET_ICMP
+ bool "ICMP networking support"
+ default n
+ depends on NET
+ ---help---
+ Enable minimal ICMP support. Includes built-in support
+ for sending replies to received ECHO (ping) requests.
+
+if NET_ICMP
+config NET_ICMP_PING
+ bool "ICMP ping interfaces"
+ default n
+ ---help---
+ Provide interfaces to support application level support for
+ for sending ECHO (ping) requests and associating ECHO replies.
+
+config NET_PINGADDRCONF
+ bool "Ping address configuration"
+ default n
+ ---help---
+ Use "ping" packet for setting IP address
+
+endif
+
+config NET_IGMP
+ bool "IGMPv2 clientsupport"
+ default n
+ depends on NET
+ ---help---
+ Enable IGMPv2 client support.
+
+if NET_IGMP
+config PREALLOC_IGMPGROUPS
+ int "Number of pre-allocated IGMP groups"
+ default 4
+ ---help---
+ Pre-allocated IGMP groups are used only if needed from interrupt
+ level group created (by the IGMP server). Default: 4.
+
+endif
+
+if NET
+
+config NET_STATISTICS
+ bool "Collect network statistics"
+ default n
+ ---help---
+ uIP statistics on or off
+
+config NET_RECEIVE_WINDOW
+ int "Receive window size"
+ ---help---
+ The size of the advertised receiver's window
+
+config NET_ARPTAB_SIZE
+ int "ARP table size"
+ default 16
+ ---help---
+ The size of the ARP table
+
+config NET_ARP_IPIN
+ bool "ARP address harvesting"
+ default n
+ ---help---
+ Harvest IP/MAC address mappings from the ARP table
+ from incoming IP packets.
+
+config NET_MULTICAST
+ bool "Multi-cast Tx support"
+ default n
+ ---help---
+ Outgoing multi-cast address support
+
+config NET_FWCACHE_SIZE
+ int "FW cache size"
+ ---help---
+ Number of packets to remember when looking for duplicates
+
+config NET_SLIP
+ bool "SLIP support"
+ default n
+ ---help---
+ Enables building of the SLIP driver. SLIP requires
+ at least one IP protocol selected and the following additional
+ network settings: NET_NOINTS and NET_MULTIBUFFER.
+
+ NET_BUFSIZE *must* be set to 296. Other optional configuration
+ settings that affect the SLIP driver: NET_STATISTICS.
+ Default: Ethernet
+
+ SLIP supports point-to-point IP communications over a serial port.
+ The default data link layer for uIP is Ethernet. If NET_SLIP is
+ defined in the NuttX configuration file, then SLIP will be supported.
+ The basic differences between the SLIP and Ethernet configurations is
+ that when SLIP is selected:
+
+ * The link level header (that comes before the IP header) is omitted.
+ * All MAC address processing is suppressed.
+ * ARP is disabled.
+
+ If NET_SLIP is not selected, then Ethernet will be used (there is
+ no need to define anything special in the configuration file to use
+ Ethernet -- it is the default).
+
+endif
+if NET_SLIP
+
+config SLIP_NINTERFACES
+ int "Number of SLIP interfaces"
+ default 1
+ ---help---
+ Selects the number of physical SLIP
+ interfaces to support.
+ Default: 1
+
+config SLIP_STACKSIZE
+ int "SLIP stack size"
+ default 2048
+ ---help---
+ Select the stack size of the SLIP RX and TX tasks. Default: 2048
+
+config SLIP_DEFPRIO
+ int "SLIP priority"
+ default 128
+ ---help---
+ The priority of the SLIP RX and TX tasks. Default: 128
+
+endif
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
new file mode 100644
index 000000000..506ef8213
--- /dev/null
+++ b/nuttx/net/Makefile
@@ -0,0 +1,123 @@
+############################################################################
+# net/Makefile
+#
+# Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+ifeq ($(CONFIG_NET),y)
+
+# Basic networking support
+
+SOCK_ASRCS =
+SOCK_CSRCS = bind.c connect.c getsockname.c recv.c recvfrom.c socket.c \
+ sendto.c net_sockets.c net_close.c net_dup.c net_dup2.c net_clone.c \
+ net_vfcntl.c
+
+# TCP/IP support
+
+ifeq ($(CONFIG_NET_TCP),y)
+SOCK_CSRCS += send.c listen.c accept.c net_monitor.c
+endif
+
+# Socket options
+
+ifeq ($(CONFIG_NET_SOCKOPTS),y)
+SOCK_CSRCS += setsockopt.c getsockopt.c
+ifneq ($(CONFIG_DISABLE_CLOCK),y)
+SOCK_CSRCS += net_timeo.c net_dsec2timeval.c net_timeval2dsec.c
+ifneq ($(CONFIG_NET_SLIP),y)
+SOCK_CSRCS += net_arptimer.c
+endif
+endif
+endif
+
+# Support for network access using streams
+
+ifneq ($(CONFIG_NFILE_STREAMS),0)
+SOCK_CSRCS += net_checksd.c
+endif
+
+# Support for operations on network devices
+
+NETDEV_ASRCS =
+NETDEV_CSRCS = netdev_register.c netdev_ioctl.c net_poll.c netdev_txnotify.c \
+ netdev_findbyname.c netdev_findbyaddr.c netdev_count.c \
+ netdev_foreach.c netdev_unregister.c netdev_sem.c
+
+include uip/Make.defs
+endif
+
+ASRCS = $(SOCK_ASRCS) $(NETDEV_ASRCS) $(UIP_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = $(SOCK_CSRCS) $(NETDEV_CSRCS) $(UIP_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = libnet$(LIBEXT)
+
+VPATH = uip
+
+all: $(BIN)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+$(BIN): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ifeq ($(CONFIG_NET),y)
+ @$(MKDEP) --dep-path . --dep-path uip $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+endif
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f $(BIN) *~ .*.swp
+ @rm -f uip/*~ uip/.*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
new file mode 100644
index 000000000..07e3f983e
--- /dev/null
+++ b/nuttx/net/accept.c
@@ -0,0 +1,462 @@
+/****************************************************************************
+ * net/accept.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET_TCP)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct accept_s
+{
+ sem_t acpt_sem; /* Wait for interrupt event */
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *acpt_addr; /* Return connection adress */
+#else
+ FAR struct sockaddr_in *acpt_addr; /* Return connection adress */
+#endif
+ FAR struct uip_conn *acpt_newconn; /* The accepted connection */
+ int acpt_result; /* The result of the wait */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: accept_tcpsender
+ *
+ * Description:
+ * Getting the sender's address from the UDP packet
+ *
+ * Parameters:
+ * conn - The newly accepted TCP connection
+ * pstate - the recvfrom state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+#ifdef CONFIG_NET_IPv6
+static inline void accept_tcpsender(FAR struct uip_conn *conn,
+ FAR struct sockaddr_in6 *addr)
+{
+ if (addr)
+ {
+ addr->sin_family = AF_INET6;
+ addr->sin_port = conn->rport;
+ uip_ipaddr_copy(addr->sin6_addr.s6_addr, conn->ripaddr);
+ }
+}
+#else
+static inline void accept_tcpsender(FAR struct uip_conn *conn,
+ FAR struct sockaddr_in *addr)
+{
+ if (addr)
+ {
+ addr->sin_family = AF_INET;
+ addr->sin_port = conn->rport;
+ uip_ipaddr_copy(addr->sin_addr.s_addr, conn->ripaddr);
+ }
+}
+#endif /* CONFIG_NET_IPv6 */
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: accept_interrupt
+ *
+ * Description:
+ * Receive interrupt level callbacks when connections occur
+ *
+ * Parameters:
+ * listener The conection stucture of the listener
+ * conn The connection stucture that was just accepted
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static int accept_interrupt(struct uip_conn *listener, struct uip_conn *conn)
+{
+ struct accept_s *pstate = (struct accept_s *)listener->accept_private;
+ int ret = -EINVAL;
+
+ if (pstate)
+ {
+ /* Get the connection address */
+
+ accept_tcpsender(conn, pstate->acpt_addr);
+
+ /* Save the connection structure */
+
+ pstate->acpt_newconn = conn;
+ pstate->acpt_result = OK;
+
+ /* There should be a reference of one on the new connection */
+
+ DEBUGASSERT(conn->crefs == 1);
+
+ /* Wake-up the waiting caller thread */
+
+ sem_post(&pstate->acpt_sem);
+
+ /* Stop any further callbacks */
+
+ listener->accept_private = NULL;
+ listener->accept = NULL;
+ ret = OK;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: accept
+ *
+ * Description:
+ * The accept function is used with connection-based socket types
+ * (SOCK_STREAM, SOCK_SEQPACKET and SOCK_RDM). It extracts the first
+ * connection request on the queue of pending connections, creates a new
+ * connected socket with mostly the same properties as 'sockfd', and
+ * allocates a new socket descriptor for the socket, which is returned. The
+ * newly created socket is no longer in the listening state. The original
+ * socket 'sockfd' is unaffected by this call. Per file descriptor flags
+ * are not inherited across an accept.
+ *
+ * The 'sockfd' argument is a socket descriptor that has been created with
+ * socket(), bound to a local address with bind(), and is listening for
+ * connections after a call to listen().
+ *
+ * On return, the 'addr' structure is filled in with the address of the
+ * connecting entity. The 'addrlen' argument initially contains the size
+ * of the structure pointed to by 'addr'; on return it will contain the
+ * actual length of the address returned.
+ *
+ * If no pending connections are present on the queue, and the socket is
+ * not marked as non-blocking, accept blocks the caller until a connection
+ * is present. If the socket is marked non-blocking and no pending
+ * connections are present on the queue, accept returns EAGAIN.
+ *
+ * Parameters:
+ * sockfd The listening socket descriptior
+ * addr Receives the address of the connecting client
+ * addrlen Input: allocated size of 'addr', Return: returned size of 'addr'
+ *
+ * Returned Value:
+ * Returns -1 on error. If it succeeds, it returns a non-negative integer
+ * that is a descriptor for the accepted socket.
+ *
+ * EAGAIN or EWOULDBLOCK
+ * The socket is marked non-blocking and no connections are present to
+ * be accepted.
+ * EBADF
+ * The descriptor is invalid.
+ * ENOTSOCK
+ * The descriptor references a file, not a socket.
+ * EOPNOTSUPP
+ * The referenced socket is not of type SOCK_STREAM.
+ * EINTR
+ * The system call was interrupted by a signal that was caught before
+ * a valid connection arrived.
+ * ECONNABORTED
+ * A connection has been aborted.
+ * EINVAL
+ * Socket is not listening for connections.
+ * EMFILE
+ * The per-process limit of open file descriptors has been reached.
+ * ENFILE
+ * The system maximum for file descriptors has been reached.
+ * EFAULT
+ * The addr parameter is not in a writable part of the user address
+ * space.
+ * ENOBUFS or ENOMEM
+ * Not enough free memory.
+ * EPROTO
+ * Protocol error.
+ * EPERM
+ * Firewall rules forbid connection.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ FAR struct socket *pnewsock;
+ FAR struct uip_conn *conn;
+ struct accept_s state;
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *inaddr = (struct sockaddr_in6 *)addr;
+#else
+ FAR struct sockaddr_in *inaddr = (struct sockaddr_in *)addr;
+#endif
+ uip_lock_t save;
+ int newfd;
+ int err;
+ int ret;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ /* It is not a valid socket description. Distinguish between the cases
+ * where sockfd is a just valid and when it is a valid file descriptor used
+ * in the wrong context.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if ((unsigned int)sockfd < CONFIG_NFILE_DESCRIPTORS)
+ {
+ err = ENOTSOCK;
+ }
+ else
+#endif
+ {
+ err = EBADF;
+ }
+ goto errout;
+ }
+
+ /* We have a socket descriptor, but it is a stream? */
+
+ if (psock->s_type != SOCK_STREAM)
+ {
+ err = EOPNOTSUPP;
+ goto errout;
+ }
+
+ /* Is the socket listening for a connection? */
+
+ if (!_SS_ISLISTENING(psock->s_flags))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Verify that a valid memory block has been provided to receive the
+ * address
+ */
+
+ if (addr)
+ {
+#ifdef CONFIG_NET_IPv6
+ if (*addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (*addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+ }
+
+ /* Allocate a socket descriptor for the new connection now (so that it
+ * cannot fail later)
+ */
+
+ newfd = sockfd_allocate(0);
+ if (newfd < 0)
+ {
+ err = ENFILE;
+ goto errout;
+ }
+
+ pnewsock = sockfd_socket(newfd);
+ if (!pnewsock)
+ {
+ err = ENFILE;
+ goto errout_with_socket;
+ }
+
+ /* Check the backlog to see if there is a connection already pending for
+ * this listener.
+ */
+
+ save = uip_lock();
+ conn = (struct uip_conn *)psock->s_conn;
+
+#ifdef CONFIG_NET_TCPBACKLOG
+ state.acpt_newconn = uip_backlogremove(conn);
+ if (state.acpt_newconn)
+ {
+ /* Yes... get the address of the connected client */
+
+ nvdbg("Pending conn=%p\n", state.acpt_newconn);
+ accept_tcpsender(state.acpt_newconn, inaddr);
+ }
+
+ /* In general, this uIP-based implementation will not support non-blocking
+ * socket operations... except in a few cases: Here for TCP accept with backlog
+ * enabled. If this socket is configured as non-blocking then return EAGAIN
+ * if there is no pending connection in the backlog.
+ */
+
+ else if (_SS_ISNONBLOCK(psock->s_flags))
+ {
+ err = EAGAIN;
+ goto errout_with_lock;
+ }
+ else
+#endif
+ {
+ /* Set the socket state to accepting */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_ACCEPT);
+
+ /* Perform the TCP accept operation */
+
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ state.acpt_addr = inaddr;
+ state.acpt_newconn = NULL;
+ state.acpt_result = OK;
+ sem_init(&state.acpt_sem, 0, 0);
+
+ /* Set up the callback in the connection */
+
+ conn->accept_private = (void*)&state;
+ conn->accept = accept_interrupt;
+
+ /* Wait for the send to complete or an error to occur: NOTES: (1)
+ * uip_lockedwait will also terminate if a signal is received, (2) interrupts
+ * may be disabled! They will be re-enabled while the task sleeps and
+ * automatically re-enabled when the task restarts.
+ */
+
+ ret = uip_lockedwait(&state.acpt_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ conn->accept_private = NULL;
+ conn->accept = NULL;
+
+ sem_destroy(&state. acpt_sem);
+
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+
+ /* Check for a errors. Errors are signaled by negative errno values
+ * for the send length.
+ */
+
+ if (state.acpt_result != 0)
+ {
+ err = state.acpt_result;
+ goto errout_with_lock;
+ }
+
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
+ */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout_with_lock;
+ }
+ }
+
+ /* Initialize the socket structure and mark the socket as connected.
+ * (The reference count on the new connection structure was set in the
+ * interrupt handler).
+ */
+
+ pnewsock->s_type = SOCK_STREAM;
+ pnewsock->s_conn = state.acpt_newconn;
+ pnewsock->s_flags |= _SF_CONNECTED;
+ pnewsock->s_flags &= ~_SF_CLOSED;
+
+ /* Begin monitoring for TCP connection events on the newly connected socket */
+
+ net_startmonitor(pnewsock);
+ uip_unlock(save);
+ return newfd;
+
+errout_with_lock:
+ uip_unlock(save);
+
+errout_with_socket:
+ sockfd_release(newfd);
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS && CONFIG_NET_TCP */
diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c
new file mode 100644
index 000000000..da912e017
--- /dev/null
+++ b/nuttx/net/bind.c
@@ -0,0 +1,197 @@
+/****************************************************************************
+ * net/bind.c
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_bind
+ *
+ * Description:
+ * bind() gives the socket 'psock' the local address 'addr'. 'addr' is
+ * 'addrlen' bytes long. Traditionally, this is called "assigning a name to
+ * a socket." When a socket is created with socket, it exists in a name
+ * space (address family) but has no name assigned.
+ *
+ * Parameters:
+ * psock Socket structure of the socket to bind
+ * addr Socket local address
+ * addrlen Length of 'addr'
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES
+ * The address is protected, and the user is not the superuser.
+ * EADDRINUSE
+ * The given address is already in use.
+ * EINVAL
+ * The socket is already bound to an address.
+ * ENOTSOCK
+ * psock is a descriptor for a file, not a socket.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_bind(FAR struct socket *psock, const struct sockaddr *addr,
+ socklen_t addrlen)
+{
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *inaddr = (const struct sockaddr_in6 *)addr;
+#else
+ FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr;
+#endif
+#endif
+
+ int err;
+ int ret;
+
+ /* Verify that the psock corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = ENOTSOCK;
+ goto errout;
+ }
+
+ /* Verify that a valid address has been provided */
+
+#ifdef CONFIG_NET_IPv6
+ if (addr->sa_family != AF_INET6 || addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (addr->sa_family != AF_INET || addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Perform the binding depending on the protocol type */
+
+ switch (psock->s_type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ ret = uip_tcpbind(psock->s_conn, inaddr);
+ psock->s_flags |= _SF_BOUND;
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ ret = uip_udpbind(psock->s_conn, inaddr);
+ break;
+#endif
+
+ default:
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Was the bind successful */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ return OK;
+
+errout:
+ *get_errno_ptr() = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: bind
+ *
+ * Description:
+ * bind() gives the socket 'sockfd' the local address 'addr'. 'addr' is
+ * 'addrlen' bytes long. Traditionally, this is called "assigning a name to
+ * a socket." When a socket is created with socket, it exists in a name
+ * space (address family) but has no name assigned.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of the socket to bind
+ * addr Socket local address
+ * addrlen Length of 'addr'
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES
+ * The address is protected, and the user is not the superuser.
+ * EADDRINUSE
+ * The given address is already in use.
+ * EBADF
+ * sockfd is not a valid descriptor.
+ * EINVAL
+ * The socket is already bound to an address.
+ * ENOTSOCK
+ * sockfd is a descriptor for a file, not a socket.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
+{
+ /* Make the socket descriptor to the underlying socket structure */
+
+ FAR struct socket *psock = sockfd_socket(sockfd);
+
+ /* Then let psock_bind do all of the work */
+
+ return psock_bind(psock, addr, addrlen);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
new file mode 100644
index 000000000..fdbb34f55
--- /dev/null
+++ b/nuttx/net/connect.c
@@ -0,0 +1,591 @@
+/****************************************************************************
+ * net/connect.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+struct tcp_connect_s
+{
+ FAR struct uip_conn *tc_conn; /* Reference to TCP connection structure */
+ FAR struct uip_callback_s *tc_cb; /* Reference to callback instance */
+ sem_t tc_sem; /* Semaphore signals recv completion */
+ int tc_result; /* OK on success, otherwise a negated errno. */
+};
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline int tcp_setup_callbacks(FAR struct socket *psock,
+ FAR struct tcp_connect_s *pstate);
+static inline void tcp_teardown_callbacks(struct tcp_connect_s *pstate, int status);
+static uint16_t tcp_connect_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvpriv, uint16_t flags);
+#ifdef CONFIG_NET_IPv6
+static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in6 *inaddr);
+#else
+static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in *inaddr);
+#endif
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: tcp_setup_callbacks
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline int tcp_setup_callbacks(FAR struct socket *psock,
+ FAR struct tcp_connect_s *pstate)
+{
+ FAR struct uip_conn *conn = psock->s_conn;
+ int ret = -EBUSY;
+
+ /* Initialize the TCP state structure */
+
+ (void)sem_init(&pstate->tc_sem, 0, 0); /* Doesn't really fail */
+ pstate->tc_conn = conn;
+ pstate->tc_result = -EAGAIN;
+
+ /* Set up the callbacks in the connection */
+
+ pstate->tc_cb = uip_tcpcallbackalloc(conn);
+ if (pstate->tc_cb)
+ {
+ /* Set up the connection "interrupt" handler */
+
+ pstate->tc_cb->flags = UIP_NEWDATA|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT|UIP_CONNECTED;
+ pstate->tc_cb->priv = (void*)pstate;
+ pstate->tc_cb->event = tcp_connect_interrupt;
+
+ /* Set up the connection event monitor */
+
+ net_startmonitor(psock);
+ ret = OK;
+ }
+ return ret;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Name: tcp_teardown_callbacks
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline void tcp_teardown_callbacks(struct tcp_connect_s *pstate,
+ int status)
+{
+ FAR struct uip_conn *conn = pstate->tc_conn;
+
+ /* Make sure that no further interrupts are processed */
+
+ uip_tcpcallbackfree(conn, pstate->tc_cb);
+
+ /* If we successfully connected, we will continue to monitor the connection
+ * state via callbacks.
+ */
+
+ if (status < 0)
+ {
+ /* Failed to connect. Stop the connection event monitor */
+
+ net_stopmonitor(conn);
+ }
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Name: tcp_connect_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * connection operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * pvconn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * The new flags setting
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static uint16_t tcp_connect_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvpriv, uint16_t flags)
+{
+ struct tcp_connect_s *pstate = (struct tcp_connect_s *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ /* 'priv' might be null in some race conditions (?) */
+
+ if (pstate)
+ {
+ /* The following errors should be detected here (someday)
+ *
+ * ECONNREFUSED
+ * No one listening on the remote address.
+ * ENETUNREACH
+ * Network is unreachable.
+ * ETIMEDOUT
+ * Timeout while attempting connection. The server may be too busy
+ * to accept new connections.
+ */
+
+ /* UIP_CLOSE: The remote host has closed the connection
+ * UIP_ABORT: The remote host has aborted the connection
+ */
+
+ if ((flags & (UIP_CLOSE|UIP_ABORT)) != 0)
+ {
+ /* Indicate that remote host refused the connection */
+
+ pstate->tc_result = -ECONNREFUSED;
+ }
+
+ /* UIP_TIMEDOUT: Connection aborted due to too many retransmissions. */
+
+ else if ((flags & UIP_TIMEDOUT) != 0)
+ {
+ /* Indicate that the remote host is unreachable (or should this be timedout?) */
+
+ pstate->tc_result = -ETIMEDOUT;
+ }
+
+ /* UIP_CONNECTED: The socket is successfully connected */
+
+ else if ((flags & UIP_CONNECTED) != 0)
+ {
+ /* Indicate that the socket is no longer connected */
+
+ pstate->tc_result = OK;
+ }
+
+ /* Otherwise, it is not an event of importance to us at the moment */
+
+ else
+ {
+ /* Drop data received in this state */
+
+ dev->d_len = 0;
+ return flags & ~UIP_NEWDATA;
+ }
+
+ nllvdbg("Resuming: %d\n", pstate->tc_result);
+
+ /* Stop further callbacks */
+
+ tcp_teardown_callbacks(pstate, pstate->tc_result);
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->tc_sem);
+ }
+
+ return flags;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Name: tcp_connect
+ *
+ * Description:
+ * Perform a TCP connection
+ *
+ * Parameters:
+ * psock A reference to the socket structure of the socket to be connected
+ * inaddr The address of the remote server to connect to
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+#ifdef CONFIG_NET_IPv6
+static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in6 *inaddr)
+#else
+static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in *inaddr)
+#endif
+{
+ struct tcp_connect_s state;
+ uip_lock_t flags;
+ int ret = OK;
+
+ /* Interrupts must be disabled through all of the following because
+ * we cannot allow the network callback to occur until we are completely
+ * setup.
+ */
+
+ flags = uip_lock();
+
+ /* Get the connection reference from the socket */
+
+ if (!psock->s_conn) /* Should always be non-NULL */
+ {
+ ret = -EINVAL;
+ }
+ else
+ {
+ /* Perform the uIP connection operation */
+
+ ret = uip_tcpconnect(psock->s_conn, inaddr);
+ }
+
+ if (ret >= 0)
+ {
+ /* Set up the callbacks in the connection */
+
+ ret = tcp_setup_callbacks(psock, &state);
+ if (ret >= 0)
+ {
+ /* Wait for either the connect to complete or for an error/timeout
+ * to occur. NOTES: (1) uip_lockedwait will also terminate if a signal
+ * is received, (2) interrupts may be disabled! They will be re-
+ * enabled while the task sleeps and automatically re-disabled
+ * when the task restarts.
+ */
+
+ ret = uip_lockedwait(&state.tc_sem);
+
+ /* Uninitialize the state structure */
+
+ (void)sem_destroy(&state.tc_sem);
+
+ /* If uip_lockedwait failed, recover the negated error (probably -EINTR) */
+
+ if (ret < 0)
+ {
+ ret = -errno;
+ }
+ else
+ {
+ /* If the wait succeeded, then get the new error value from
+ * the state structure
+ */
+
+ ret = state.tc_result;
+ }
+
+ /* Make sure that no further interrupts are processed */
+
+ tcp_teardown_callbacks(&state, ret);
+ }
+
+ /* Mark the connection bound and connected */
+
+ if (ret >= 0)
+ {
+ psock->s_flags |= (_SF_BOUND|_SF_CONNECTED);
+ }
+ }
+
+ uip_unlock(flags);
+ return ret;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: psock_connect
+ *
+ * Description:
+ * connect() connects the socket referred to by the structure 'psock'
+ * to the address specified by 'addr'. The addrlen argument specifies
+ * the size of 'addr'. The format of the address in 'addr' is
+ * determined by the address space of the socket 'psock'.
+ *
+ * If the socket 'psock' is of type SOCK_DGRAM then 'addr' is the address
+ * to which datagrams are sent by default, and the only address from which
+ * datagrams are received. If the socket is of type SOCK_STREAM or
+ * SOCK_SEQPACKET, this call attempts to make a connection to the socket
+ * that is bound to the address specified by 'addr'.
+ *
+ * Generally, connection-based protocol sockets may successfully connect()
+ * only once; connectionless protocol sockets may use connect() multiple
+ * times to change their association. Connectionless sockets may dissolve
+ * the association by connecting to an address with the sa_family member of
+ * sockaddr set to AF_UNSPEC.
+ *
+ * Parameters:
+ * psock Pointer to a socket structure initialized by psock_socket()
+ * addr Server address (form depends on type of socket)
+ * addrlen Length of actual 'addr'
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES, EPERM
+ * The user tried to connect to a broadcast address without having the
+ * socket broadcast flag enabled or the connection request failed
+ * because of a local firewall rule.
+ * EADDRINUSE
+ * Local address is already in use.
+ * EAFNOSUPPORT
+ * The passed address didn't have the correct address family in its
+ * sa_family field.
+ * EAGAIN
+ * No more free local ports or insufficient entries in the routing
+ * cache.
+ * EALREADY
+ * The socket is non-blocking and a previous connection attempt has
+ * not yet been completed.
+ * EBADF
+ * The file descriptor is not a valid index in the descriptor table.
+ * ECONNREFUSED
+ * No one listening on the remote address.
+ * EFAULT
+ * The socket structure address is outside the user's address space.
+ * EINPROGRESS
+ * The socket is non-blocking and the connection cannot be completed
+ * immediately.
+ * EINTR
+ * The system call was interrupted by a signal that was caught.
+ * EISCONN
+ * The socket is already connected.
+ * ENETUNREACH
+ * Network is unreachable.
+ * ENOTSOCK
+ * The file descriptor is not associated with a socket.
+ * ETIMEDOUT
+ * Timeout while attempting connection. The server may be too busy
+ * to accept new connections.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr,
+ socklen_t addrlen)
+{
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *inaddr = (const struct sockaddr_in6 *)addr;
+#else
+ FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr;
+#endif
+ int ret;
+#endif
+
+ int err;
+
+ /* Verify that the psock corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Verify that a valid address has been provided */
+
+#ifdef CONFIG_NET_IPv6
+ if (addr->sa_family != AF_INET6 || addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (addr->sa_family != AF_INET || addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Perform the connection depending on the protocol type */
+
+ switch (psock->s_type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ /* Verify that the socket is not already connected */
+
+ if (_SS_ISCONNECTED(psock->s_flags))
+ {
+ err = EISCONN;
+ goto errout;
+ }
+
+ /* Its not ... connect it */
+
+ ret = tcp_connect(psock, inaddr);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ ret = uip_udpconnect(psock->s_conn, inaddr);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+ }
+ break;
+#endif
+
+ default:
+ err = EBADF;
+ goto errout;
+ }
+
+ return OK;
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Name: connect
+ *
+ * Description:
+ * connect() connects the socket referred to by the file descriptor 'sockfd'
+ * to the address specified by 'addr'. The addrlen argument specifies
+ * the size of 'addr'. The format of the address in 'addr' is
+ * determined by the address space of the socket 'sockfd'.
+ *
+ * If the socket 'sockfd' is of type SOCK_DGRAM then 'addr' is the address
+ * to which datagrams are sent by default, and the only address from which
+ * datagrams are received. If the socket is of type SOCK_STREAM or
+ * SOCK_SEQPACKET, this call attempts to make a connection to the socket
+ * that is bound to the address specified by 'addr'.
+ *
+ * Generally, connection-based protocol sockets may successfully connect()
+ * only once; connectionless protocol sockets may use connect() multiple
+ * times to change their association. Connectionless sockets may dissolve
+ * the association by connecting to an address with the sa_family member of
+ * sockaddr set to AF_UNSPEC.
+ *
+ * Parameters:
+ * sockfd Socket descriptor returned by socket()
+ * addr Server address (form depends on type of socket)
+ * addrlen Length of actual 'addr'
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES, EPERM
+ * The user tried to connect to a broadcast address without having the
+ * socket broadcast flag enabled or the connection request failed
+ * because of a local firewall rule.
+ * EADDRINUSE
+ * Local address is already in use.
+ * EAFNOSUPPORT
+ * The passed address didn't have the correct address family in its
+ * sa_family field.
+ * EAGAIN
+ * No more free local ports or insufficient entries in the routing
+ * cache.
+ * EALREADY
+ * The socket is non-blocking and a previous connection attempt has
+ * not yet been completed.
+ * EBADF
+ * The file descriptor is not a valid index in the descriptor table.
+ * ECONNREFUSED
+ * No one listening on the remote address.
+ * EFAULT
+ * The socket structure address is outside the user's address space.
+ * EINPROGRESS
+ * The socket is non-blocking and the connection cannot be completed
+ * immediately.
+ * EINTR
+ * The system call was interrupted by a signal that was caught.
+ * EISCONN
+ * The socket is already connected.
+ * ENETUNREACH
+ * Network is unreachable.
+ * ENOTSOCK
+ * The file descriptor is not associated with a socket.
+ * ETIMEDOUT
+ * Timeout while attempting connection. The server may be too busy
+ * to accept new connections.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int connect(int sockfd, FAR const struct sockaddr *addr, socklen_t addrlen)
+{
+ /* Get the underlying socket structure */
+
+ FAR struct socket *psock = sockfd_socket(sockfd);
+
+ /* Then let psock_connect() do all of the work */
+
+ return psock_connect(psock, addr, addrlen);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/getsockname.c b/nuttx/net/getsockname.c
new file mode 100644
index 000000000..c5cae2f3b
--- /dev/null
+++ b/nuttx/net/getsockname.c
@@ -0,0 +1,218 @@
+/****************************************************************************
+ * net/getsockname.c
+ *
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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/socket.h>
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/net/net.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+#ifdef CONFIG_NET
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: getsockname
+ *
+ * Description:
+ * The getsockname() function retrieves the locally-bound name of the
+ * specified socket, stores this address in the sockaddr structure pointed
+ * to by the 'addr' argument, and stores the length of this address in the
+ * object pointed to by the 'addrlen' argument.
+ *
+ * If the actual length of the address is greater than the length of the
+ * supplied sockaddr structure, the stored address will be truncated.
+ *
+ * If the socket has not been bound to a local name, the value stored in
+ * the object pointed to by address is unspecified.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket [in]
+ * addr sockaddr structure to receive data [out]
+ * addrlen Length of sockaddr structure [in/out]
+ *
+ * Returned Value:
+ * On success, 0 is returned, the 'addr' argument points to the address
+ * of the socket, and the 'addrlen' argument points to the length of the
+ * address. Otherwise, -1 is returned and errno is set to indicate the error.
+ * Possible errno values that may be returned include:
+ *
+ * EBADF - The socket argument is not a valid file descriptor.
+ * EOPNOTSUPP - The operation is not supported for this socket's protocol.
+ * EINVAL - The socket has been shut down.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ FAR struct uip_driver_s *dev;
+
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *outaddr = (FAR struct sockaddr_in6 *)addr;
+#else
+ FAR struct sockaddr_in *outaddr = (FAR struct sockaddr_in *)addr;
+#endif
+#endif
+
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Some sanity checking... Shouldn't need this on a buckled up embedded
+ * system (?)
+ */
+
+#ifdef CONFIG_DEBUG
+ if (!addr || !addrlen)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+#endif
+
+ /* Check if enough space has been provided for the full address */
+
+#ifdef CONFIG_NET_IPv6
+ if (*addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (*addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ /* This function is supposed to return the partial address if
+ * a smaller buffer has been provided. This support has not
+ * been implemented.
+ */
+
+ err = ENOSYS;
+ goto errout;
+ }
+
+ /* Set the port number */
+
+ switch (psock->s_type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ struct uip_conn *tcp_conn = (struct uip_conn *)psock->s_conn;
+ outaddr->sin_port = tcp_conn->lport; /* Already in network byte order */
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ struct uip_udp_conn *udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ outaddr->sin_port = udp_conn->lport; /* Already in network byte order */
+ }
+ break;
+#endif
+
+ default:
+ err = EOPNOTSUPP;
+ goto errout;
+ }
+
+ /* ISSUE: As of this writing, the socket/connection does not know its IP
+ * address. This is because the uIP design is only intended to support
+ * a single network device and, therefore, only the network device knows
+ * the IP address.
+ *
+ * Right now, we can just pick the first network device. But that may
+ * not work in the future.
+ */
+
+ netdev_semtake();
+ dev = g_netdevices;
+ if (!dev)
+ {
+ netdev_semgive();
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Set the address family and the IP address */
+
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+#ifdef CONFIG_NET_IPv6
+ outaddr->sin_family = AF_INET6;
+ memcpy(outaddr->sin6_addr.in6_u.u6_addr8, dev->d_ipaddr, 16);
+ *addrlen = sizeof(struct sockaddr_in6);
+#else
+ outaddr->sin_family = AF_INET;
+ outaddr->sin_addr.s_addr = dev->d_ipaddr;
+ *addrlen = sizeof(struct sockaddr_in);
+#endif
+#endif
+ netdev_semgive();
+
+ /* Return success */
+
+ return OK;
+
+errout:
+ set_errno(err);
+ return ERROR;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/getsockopt.c b/nuttx/net/getsockopt.c
new file mode 100644
index 000000000..c3afb29c9
--- /dev/null
+++ b/nuttx/net/getsockopt.c
@@ -0,0 +1,289 @@
+/****************************************************************************
+ * net/getsockopt.c
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_getsockopt
+ *
+ * Description:
+ * getsockopt() retrieve thse value for the option specified by the
+ * 'option' argument for the socket specified by the 'psock' argument. If
+ * the size of the option value is greater than 'value_len', the value
+ * stored in the object pointed to by the 'value' argument will be silently
+ * truncated. Otherwise, the length pointed to by the 'value_len' argument
+ * will be modified to indicate the actual length of the'value'.
+ *
+ * The 'level' argument specifies the protocol level of the option. To
+ * retrieve options at the socket level, specify the level argument as
+ * SOL_SOCKET.
+ *
+ * See <sys/socket.h> a complete list of values for the 'option' argument.
+ *
+ * Parameters:
+ * psock Socket structure of the socket to query
+ * level Protocol level to set the option
+ * option identifies the option to get
+ * value Points to the argument value
+ * value_len The length of the argument value
+ *
+ * Returned Value:
+ *
+ * EINVAL
+ * The specified option is invalid at the specified socket 'level' or the
+ * socket has been shutdown.
+ * ENOPROTOOPT
+ * The 'option' is not supported by the protocol.
+ * ENOTSOCK
+ * The 'psock' argument does not refer to a socket.
+ * ENOBUFS
+ * Insufficient resources are available in the system to complete the
+ * call.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_getsockopt(FAR struct socket *psock, int level, int option,
+ FAR void *value, FAR socklen_t *value_len)
+{
+ int err;
+
+ /* Verify that the socket option if valid (but might not be supported ) */
+
+ if (!_SO_GETVALID(option) || !value || !value_len)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Process the option */
+
+ switch (option)
+ {
+ /* The following options take a point to an integer boolean value.
+ * We will blindly report the bit here although the implementation
+ * is outside of the scope of getsockopt.
+ */
+
+ case SO_DEBUG: /* Enables recording of debugging information */
+ case SO_BROADCAST: /* Permits sending of broadcast messages */
+ case SO_REUSEADDR: /* Allow reuse of local addresses */
+ case SO_KEEPALIVE: /* Keeps connections active by enabling the
+ * periodic transmission */
+ case SO_OOBINLINE: /* Leaves received out-of-band data inline */
+ case SO_DONTROUTE: /* Requests outgoing messages bypass standard routing */
+ {
+ sockopt_t optionset;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (*value_len < sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Sample the current options. This is atomic operation and so
+ * should not require any special steps for thread safety. We
+ * this outside of the macro because you can never be sure what
+ * a macro will do.
+ */
+
+ optionset = psock->s_options;
+ *(int*)value = _SO_GETOPT(optionset, option);
+ *value_len = sizeof(int);
+ }
+ break;
+
+ case SO_TYPE: /* Reports the socket type */
+ {
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (*value_len < sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Return the socket type */
+
+ *(int*)value = psock->s_type;
+ *value_len = sizeof(int);
+ }
+ break;
+
+ /* The following are valid only if the OS CLOCK feature is enabled */
+
+ case SO_RCVTIMEO:
+ case SO_SNDTIMEO:
+#ifndef CONFIG_DISABLE_CLOCK
+ {
+ socktimeo_t timeo;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (*value_len < sizeof(struct timeval))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the timeout value. This is a atomic operation and should
+ * require no special operation.
+ */
+
+ if (option == SO_RCVTIMEO)
+ {
+ timeo = psock->s_rcvtimeo;
+ }
+ else
+ {
+ timeo = psock->s_sndtimeo;
+ }
+
+ /* Then return the timeout value to the caller */
+
+ net_dsec2timeval(timeo, (struct timeval *)value);
+ *value_len = sizeof(struct timeval);
+ }
+ break;
+#endif
+
+ /* The following are not yet implemented */
+
+ case SO_ACCEPTCONN: /* Reports whether socket listening is enabled */
+ case SO_LINGER:
+ case SO_SNDBUF: /* Sets send buffer size */
+ case SO_RCVBUF: /* Sets receive buffer size */
+ case SO_ERROR: /* Reports and clears error status. */
+ case SO_RCVLOWAT: /* Sets the minimum number of bytes to input */
+ case SO_SNDLOWAT: /* Sets the minimum number of bytes to output */
+
+ default:
+ err = ENOPROTOOPT;
+ goto errout;
+ }
+ return OK;
+
+errout:
+ set_errno(err);
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: getsockopt
+ *
+ * Description:
+ * getsockopt() retrieve thse value for the option specified by the
+ * 'option' argument for the socket specified by the 'sockfd' argument. If
+ * the size of the option value is greater than 'value_len', the value
+ * stored in the object pointed to by the 'value' argument will be silently
+ * truncated. Otherwise, the length pointed to by the 'value_len' argument
+ * will be modified to indicate the actual length of the'value'.
+ *
+ * The 'level' argument specifies the protocol level of the option. To
+ * retrieve options at the socket level, specify the level argument as
+ * SOL_SOCKET.
+ *
+ * See <sys/socket.h> a complete list of values for the 'option' argument.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * level Protocol level to set the option
+ * option identifies the option to get
+ * value Points to the argument value
+ * value_len The length of the argument value
+ *
+ * Returned Value:
+ *
+ * EBADF
+ * The 'sockfd' argument is not a valid socket descriptor.
+ * EINVAL
+ * The specified option is invalid at the specified socket 'level' or the
+ * socket has been shutdown.
+ * ENOPROTOOPT
+ * The 'option' is not supported by the protocol.
+ * ENOTSOCK
+ * The 'sockfd' argument does not refer to a socket.
+ * ENOBUFS
+ * Insufficient resources are available in the system to complete the
+ * call.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int getsockopt(int sockfd, int level, int option, void *value, socklen_t *value_len)
+{
+ FAR struct socket *psock;
+
+ /* Get the underlying socket structure */
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ set_errno(EBADF);
+ return ERROR;
+ }
+
+ /* Then let psock_getsockopt() do all of the work */
+
+ return psock_getsockopt(psock, level, option, value, value_len);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS */
diff --git a/nuttx/net/listen.c b/nuttx/net/listen.c
new file mode 100644
index 000000000..bddb0ab08
--- /dev/null
+++ b/nuttx/net/listen.c
@@ -0,0 +1,149 @@
+/****************************************************************************
+ * net/listen.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: listen
+ *
+ * Description:
+ * To accept connections, a socket is first created with socket(), a
+ * willingness to accept incoming connections and a queue limit for incoming
+ * connections are specified with listen(), and then the connections are
+ * accepted with accept(). The listen() call applies only to sockets of
+ * type SOCK_STREAM or SOCK_SEQPACKET.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of the bound socket
+ * backlog The maximum length the queue of pending connections may grow.
+ * If a connection request arrives with the queue full, the client
+ * may receive an error with an indication of ECONNREFUSED or,
+ * if the underlying protocol supports retransmission, the request
+ * may be ignored so that retries succeed.
+ *
+ * Returned Value:
+ * On success, zero is returned. On error, -1 is returned, and errno is set
+ * appropriately.
+ *
+ * EADDRINUSE
+ * Another socket is already listening on the same port.
+ * EBADF
+ * The argument 'sockfd' is not a valid descriptor.
+ * ENOTSOCK
+ * The argument 'sockfd' is not a socket.
+ * EOPNOTSUPP
+ * The socket is not of a type that supports the listen operation.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int listen(int sockfd, int backlog)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ struct uip_conn *conn;
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ /* It is not a valid socket description. Distinguish between the cases
+ * where sockfd is a just invalid and when it is a valid file descriptor used
+ * in the wrong context.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if ((unsigned int)sockfd < CONFIG_NFILE_DESCRIPTORS)
+ {
+ err = ENOTSOCK;
+ }
+ else
+#endif
+ {
+ err = EBADF;
+ }
+ goto errout;
+ }
+
+ /* Verify that the sockfd corresponds to a connected SOCK_STREAM */
+
+ conn = (struct uip_conn *)psock->s_conn;
+ if (psock->s_type != SOCK_STREAM || !psock->s_conn || conn->lport <= 0)
+ {
+ err = EOPNOTSUPP;
+ goto errout;
+ }
+
+ /* Set up the backlog for this connection */
+
+#ifdef CONFIG_NET_TCPBACKLOG
+ err = uip_backlogcreate(conn, backlog);
+ if (err < 0)
+ {
+ err = -err;
+ goto errout;
+ }
+#endif
+
+ /* Start listening to the bound port. This enables callbacks when accept()
+ * is called and enables poll()/select() logic.
+ */
+
+ uip_listen(conn);
+ psock->s_flags |= _SF_LISTENING;
+ return OK;
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/net_arptimer.c b/nuttx/net/net_arptimer.c
new file mode 100644
index 000000000..89db9f656
--- /dev/null
+++ b/nuttx/net/net_arptimer.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * net/net_arptimer.c
+ *
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <time.h>
+#include <wdog.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip-arp.h>
+
+#include "net_internal.h"
+
+#ifdef CONFIG_NET_ARP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* ARP timer interval = 10 seconds. CLK_TCK is the number of clock ticks
+ * per second
+ */
+
+#define ARPTIMER_WDINTERVAL (10*CLK_TCK)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static WDOG_ID g_arptimer; /* ARP timer */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: arptimer_poll
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void arptimer_poll(int argc, uint32_t arg, ...)
+{
+ /* Call the ARP timer function every 10 seconds. */
+
+ uip_arp_timer();
+
+ /* Setup the watchdog timer again */
+
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: arptimer_init
+ *
+ * Description:
+ * Initialized the 10 second timer that is need by uIP to age ARP
+ * associations
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called once at system initialization time
+ *
+ ****************************************************************************/
+
+void arptimer_init(void)
+{
+ /* Create and start the ARP timer */
+
+ g_arptimer = wd_create();
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+#endif /* CONFIG_NET_ARP */
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/net_checksd.c b/nuttx/net/net_checksd.c
new file mode 100644
index 000000000..3da3cea62
--- /dev/null
+++ b/nuttx/net/net_checksd.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * net/net_checksd.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/socket.h>
+
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: net_checksd
+ *
+ * Description:
+ * Check if the socket descriptor is valid for the provided TCB and if it
+ * supports the requested access. This trivial operation is part of the
+ * fdopen() operation when the fdopen() is performed on a socket descriptor.
+ * It simply performs some sanity checking before permitting the socket
+ * descriptor to be wrapped as a C FILE stream.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET) && CONFIG_NFILE_DESCRIPTORS > 0
+int net_checksd(int sd, int oflags)
+{
+ FAR struct socket *psock = sockfd_socket(sd);
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ nvdbg("No valid socket for sd: %d\n", sd);
+ return -EBADF;
+ }
+
+ /* NOTE: We permit the socket FD to be "wrapped" in a stream as
+ * soon as the socket descriptor is created by socket(). Therefore
+ * (1) we don't care if the socket is connected yet, and (2) there
+ * are no access restrictions that can be enforced yet.
+ */
+
+ return OK;
+}
+#endif /* CONIG_NET && CONFIG_NFILE_DESCRIPTORS > 0 */
+
diff --git a/nuttx/net/net_clone.c b/nuttx/net/net_clone.c
new file mode 100644
index 000000000..ada223484
--- /dev/null
+++ b/nuttx/net/net_clone.c
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * net/net_clone.c
+ *
+ * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/socket.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_clone
+ *
+ * Description:
+ * Performs the low level, common portion of net_dup() and net_dup2()
+ *
+ ****************************************************************************/
+
+int net_clone(FAR struct socket *psock1, FAR struct socket *psock2)
+{
+ uip_lock_t flags;
+ int ret = OK;
+
+ /* Parts of this operation need to be atomic */
+
+ flags = uip_lock();
+
+ /* Duplicate the socket state */
+
+ psock2->s_type = psock1->s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
+ psock2->s_flags = psock1->s_flags; /* See _SF_* definitions */
+#ifdef CONFIG_NET_SOCKOPTS
+ psock2->s_options = psock1->s_options; /* Selected socket options */
+#endif
+#ifndef CONFIG_DISABLE_CLOCK
+ psock2->s_rcvtimeo = psock1->s_rcvtimeo; /* Receive timeout value (in deciseconds) */
+ psock2->s_sndtimeo = psock1->s_sndtimeo; /* Send timeout value (in deciseconds) */
+#endif
+ psock2->s_conn = psock1->s_conn; /* UDP or TCP connection structure */
+
+ /* Increment the reference count on the connection */
+
+ DEBUGASSERT(psock2->s_conn);
+ psock2->s_crefs = 1; /* One reference on the new socket itself */
+
+#ifdef CONFIG_NET_TCP
+ if (psock2->s_type == SOCK_STREAM)
+ {
+ struct uip_conn *conn = psock2->s_conn;
+ DEBUGASSERT(conn->crefs > 0 && conn->crefs < 255);
+ conn->crefs++;
+ }
+ else
+#endif
+#ifdef CONFIG_NET_UDP
+ if (psock2->s_type == SOCK_DGRAM)
+ {
+ struct uip_udp_conn *conn = psock2->s_conn;
+ DEBUGASSERT(conn->crefs > 0 && conn->crefs < 255);
+ conn->crefs++;
+ }
+ else
+#endif
+ {
+ ndbg("Unsupported type: %d\n", psock2->s_type);
+ ret = -EBADF;
+ }
+
+ uip_unlock(flags);
+ return ret;
+}
+
+#endif /* CONFIG_NET */
+
+
diff --git a/nuttx/net/net_close.c b/nuttx/net/net_close.c
new file mode 100644
index 000000000..dce87ba47
--- /dev/null
+++ b/nuttx/net/net_close.c
@@ -0,0 +1,330 @@
+/****************************************************************************
+ * net/net_close.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+struct tcp_close_s
+{
+ FAR struct socket *cl_psock; /* Reference to the TCP socket */
+ FAR struct uip_callback_s *cl_cb; /* Reference to TCP callback instance */
+ sem_t cl_sem; /* Semaphore signals disconnect completion */
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netclose_interrupt
+ *
+ * Description:
+ * Handle uIP callback events.
+ *
+ * Parameters:
+ * conn - uIP TCP connection structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user-level logic
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static uint16_t netclose_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvpriv, uint16_t flags)
+{
+ struct tcp_close_s *pstate = (struct tcp_close_s *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ if (pstate)
+ {
+ /* UIP_CLOSE: The remote host has closed the connection
+ * UIP_ABORT: The remote host has aborted the connection
+ */
+
+ if ((flags & (UIP_CLOSE|UIP_ABORT)) != 0)
+ {
+ /* The disconnection is complete */
+
+ pstate->cl_cb->flags = 0;
+ pstate->cl_cb->priv = NULL;
+ pstate->cl_cb->event = NULL;
+ sem_post(&pstate->cl_sem);
+ nllvdbg("Resuming\n");
+ }
+ else
+ {
+ /* Drop data received in this state and make sure that UIP_CLOSE
+ * is set in the response
+ */
+
+ dev->d_len = 0;
+ return (flags & ~UIP_NEWDATA) | UIP_CLOSE;
+ }
+ }
+
+ return flags;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: netclose_disconnect
+ *
+ * Description:
+ * Break any current TCP connection
+ *
+ * Parameters:
+ * conn - uIP TCP connection structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user-level logic
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline void netclose_disconnect(FAR struct socket *psock)
+{
+ struct tcp_close_s state;
+ uip_lock_t flags;
+
+ /* Interrupts are disabled here to avoid race conditions */
+
+ flags = uip_lock();
+
+ /* Is the TCP socket in a connected state? */
+
+ if (_SS_ISCONNECTED(psock->s_flags))
+ {
+ struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
+
+ /* Check for the case where the host beat us and disconnected first */
+
+ if (conn->tcpstateflags == UIP_ESTABLISHED)
+ {
+ /* Set up to receive TCP data event callbacks */
+
+ state.cl_cb = uip_tcpcallbackalloc(conn);
+ if (state.cl_cb)
+ {
+ state.cl_psock = psock;
+ sem_init(&state.cl_sem, 0, 0);
+
+ state.cl_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT;
+ state.cl_cb->priv = (void*)&state;
+ state.cl_cb->event = netclose_interrupt;
+
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&conn->ripaddr);
+
+ /* Wait for the disconnect event */
+
+ (void)uip_lockedwait(&state.cl_sem);
+
+ /* We are now disconnected */
+
+ sem_destroy(&state.cl_sem);
+ uip_tcpcallbackfree(conn, state.cl_cb);
+ }
+ }
+ }
+
+ uip_unlock(flags);
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_close
+ *
+ * Description:
+ * Performs the close operation on a socket instance
+ *
+ * Parameters:
+ * psock Socket instance
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_close(FAR struct socket *psock)
+{
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* We perform the uIP close operation only if this is the last count on the socket.
+ * (actually, I think the socket crefs only takes the values 0 and 1 right now).
+ */
+
+ if (psock->s_crefs <= 1)
+ {
+ /* Perform uIP side of the close depending on the protocol type */
+
+ switch (psock->s_type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ struct uip_conn *conn = psock->s_conn;
+
+ /* Is this the last reference to the connection structure (there
+ * could be more if the socket was dup'ed.
+ */
+
+ if (conn->crefs <= 1)
+ {
+ /* Yes... free the connection structure */
+
+ uip_unlisten(conn); /* No longer accepting connections */
+ netclose_disconnect(psock); /* Break any current connections */
+ conn->crefs = 0; /* No more references on the connection */
+ uip_tcpfree(conn); /* Free uIP resources */
+ }
+ else
+ {
+ /* No.. Just decrement the reference count */
+
+ conn->crefs--;
+ }
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ struct uip_udp_conn *conn = psock->s_conn;
+
+ /* Is this the last reference to the connection structure (there
+ * could be more if the socket was dup'ed.
+ */
+
+ if (conn->crefs <= 1)
+ {
+ /* Yes... free the connection structure */
+
+ conn->crefs = 0; /* No more references on the connection */
+ uip_udpfree(psock->s_conn); /* Free uIP resources */
+ }
+ else
+ {
+ /* No.. Just decrement the reference count */
+
+ conn->crefs--;
+ }
+ }
+ break;
+#endif
+
+ default:
+ err = EBADF;
+ goto errout;
+ }
+ }
+
+ /* Then release our reference on the socket structure containing the connection */
+
+ sock_release(psock);
+ return OK;
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: net_close
+ *
+ * Description:
+ * Performs the close operation on socket descriptors
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int net_close(int sockfd)
+{
+ return psock_close(sockfd_socket(sockfd));
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/net_dsec2timeval.c b/nuttx/net/net_dsec2timeval.c
new file mode 100644
index 000000000..c9d3aeb66
--- /dev/null
+++ b/nuttx/net/net_dsec2timeval.c
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * net/net_dsec2timeval.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/socket.h>
+#include <stdint.h>
+#include <errno.h>
+#include <nuttx/clock.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dsec2timeval
+ *
+ * Description:
+ * Convert a decisecond timeout value to a struct timeval. Needed by
+ * getsockopt() to report timeout values.
+ *
+ * Parameters:
+ * dsec The decisecond value to convert
+ * tv The struct timeval to receive the converted value
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void net_dsec2timeval(uint16_t dsec, struct timeval *tv)
+{
+ uint16_t remainder;
+ tv->tv_sec = dsec / DSEC_PER_SEC;
+ remainder = dsec - tv->tv_sec * DSEC_PER_SEC;
+ tv->tv_usec = remainder * USEC_PER_DSEC;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/net/net_dup.c b/nuttx/net/net_dup.c
new file mode 100644
index 000000000..8465b7ce4
--- /dev/null
+++ b/nuttx/net/net_dup.c
@@ -0,0 +1,149 @@
+/****************************************************************************
+ * net/net_dup.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/socket.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dup
+ *
+ * Description:
+ * Clone a socket descriptor to an arbitray descriptor number. If file
+ * descriptors are implemented, then this is called by dup() for the case
+ * of socket file descriptors. If file descriptors are not implemented,
+ * then this function IS dup().
+ *
+ ****************************************************************************/
+
+int net_dup(int sockfd, int minsd)
+{
+ FAR struct socket *psock1 = sockfd_socket(sockfd);
+ FAR struct socket *psock2;
+ int sockfd2;
+ int err;
+ int ret;
+
+ /* Make sure that the minimum socket descriptor is within the legal range.
+ * the minimum value we receive is relative to file descriptor 0; we need
+ * map it relative of the first socket descriptor.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ if (minsd >= CONFIG_NFILE_DESCRIPTORS)
+ {
+ minsd -= CONFIG_NFILE_DESCRIPTORS;
+ }
+ else
+ {
+ minsd = 0;
+ }
+#endif
+
+ /* Lock the scheduler throughout the following */
+
+ sched_lock();
+
+ /* Get the socket structure underlying sockfd */
+
+ psock1 = sockfd_socket(sockfd);
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock1 || psock1->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Allocate a new socket descriptor */
+
+ sockfd2 = sockfd_allocate(minsd);
+ if (sockfd2 < 0)
+ {
+ err = ENFILE;
+ goto errout;
+ }
+
+ /* Get the socket structure underlying the new descriptor */
+
+ psock2 = sockfd_socket(sockfd2);
+ if (!psock2)
+ {
+ err = ENOSYS; /* should not happen */
+ goto errout;
+ }
+
+ /* Duplicate the socket state */
+
+ ret = net_clone(psock1, psock2);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+
+ }
+
+ sched_unlock();
+ return sockfd2;
+
+errout:
+ sched_unlock();
+ errno = err;
+ return ERROR;
+}
+
+#endif /* defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
+
diff --git a/nuttx/net/net_dup2.c b/nuttx/net/net_dup2.c
new file mode 100644
index 000000000..b27bb6967
--- /dev/null
+++ b/nuttx/net/net_dup2.c
@@ -0,0 +1,125 @@
+/****************************************************************************
+ * net/net_dup2.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/socket.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dup2
+ *
+ * Description:
+ * Clone a socket descriptor to an arbitray descriptor number. If file
+ * descriptors are implemented, then this is called by dup2() for the case
+ * of socket file descriptors. If file descriptors are not implemented,
+ * then this function IS dup2().
+ *
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+int net_dup2(int sockfd1, int sockfd2)
+#else
+int dup2(int sockfd1, int sockfd2)
+#endif
+{
+ FAR struct socket *psock1;
+ FAR struct socket *psock2;
+ int err;
+ int ret;
+
+ /* Lock the scheduler throughout the following */
+
+ sched_lock();
+
+ /* Get the socket structures underly both descriptors */
+
+ psock1 = sockfd_socket(sockfd1);
+ psock2 = sockfd_socket(sockfd2);
+
+ /* Verify that the sockfd1 and sockfd2 both refer to valid socket
+ * descriptors and that sockfd2 corresponds to allocated socket
+ */
+
+ if (!psock1 || !psock2 || psock1->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* If sockfd2 also valid, allocated socket, then we will have to
+ * close it!
+ */
+
+ if (psock2->s_crefs > 0)
+ {
+ net_close(sockfd2);
+ }
+
+ /* Duplicate the socket state */
+
+ ret = net_clone(psock1, psock2);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ sched_unlock();
+ return OK;
+
+errout:
+ sched_unlock();
+ errno = err;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
+
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
new file mode 100644
index 000000000..ed2f12aa7
--- /dev/null
+++ b/nuttx/net/net_internal.h
@@ -0,0 +1,237 @@
+/****************************************************************************
+ * net/net_internal.h
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __NET_INTERNAL_H
+#define __NET_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <time.h>
+
+#include <nuttx/net/net.h>
+#include <nuttx/net/uip/uip.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Definitions of 8-bit socket flags */
+
+ /* Bits 0-2: Socket state */
+#define _SF_IDLE 0x00 /* - There is no socket activity */
+#define _SF_ACCEPT 0x01 /* - Socket is waiting to accept a connection */
+#define _SF_RECV 0x02 /* - Waiting for recv action to complete */
+#define _SF_SEND 0x03 /* - Waiting for send action to complete */
+#define _SF_MASK 0x03 /* - Mask to isolate the above actions */
+
+#define _SF_NONBLOCK 0x08 /* Bit 3: Don't block if no data (TCP/READ only) */
+#define _SF_LISTENING 0x10 /* Bit 4: SOCK_STREAM is listening */
+#define _SF_BOUND 0x20 /* Bit 5: SOCK_STREAM is bound to an address */
+ /* Bits 6-7: Connection state */
+#define _SF_CONNECTED 0x40 /* Bit 6: SOCK_STREAM is connected */
+#define _SF_CLOSED 0x80 /* Bit 7: SOCK_STREAM was gracefully disconnected */
+
+/* Connection state encoding:
+ *
+ * _SF_CONNECTED==1 && _SF_CLOSED==0 - the socket is connected
+ * _SF_CONNECTED==0 && _SF_CLOSED==1 - the socket was gracefully disconnected
+ * _SF_CONNECTED==0 && _SF_CLOSED==0 - the socket was rudely disconnected
+ */
+
+/* Macro to manage the socket state and flags */
+
+#define _SS_SETSTATE(s,f) (((s) & ~_SF_MASK) | (f))
+#define _SS_GETSTATE(s) ((s) & _SF_MASK)
+#define _SS_ISBUSY(s) (_SS_GETSTATE(s) != _SF_IDLE)
+
+#define _SS_ISNONBLOCK(s) (((s) & _SF_NONBLOCK) != 0)
+#define _SS_ISLISTENING(s) (((s) & _SF_LISTENING) != 0)
+#define _SS_ISBOUND(s) (((s) & _SF_CONNECTED) != 0)
+#define _SS_ISCONNECTED(s) (((s) & _SF_CONNECTED) != 0)
+#define _SS_ISCLOSED(s) (((s) & _SF_CLOSED) != 0)
+
+/* This macro converts a socket option value into a bit setting */
+
+#define _SO_BIT(o) (1 << (o))
+
+/* These define bit positions for each socket option (see sys/socket.h) */
+
+#define _SO_DEBUG _SO_BIT(SO_DEBUG)
+#define _SO_ACCEPTCONN _SO_BIT(SO_ACCEPTCONN)
+#define _SO_BROADCAST _SO_BIT(SO_BROADCAST)
+#define _SO_REUSEADDR _SO_BIT(SO_REUSEADDR)
+#define _SO_KEEPALIVE _SO_BIT(SO_KEEPALIVE)
+#define _SO_LINGER _SO_BIT(SO_LINGER)
+#define _SO_OOBINLINE _SO_BIT(SO_OOBINLINE)
+#define _SO_SNDBUF _SO_BIT(SO_SNDBUF)
+#define _SO_RCVBUF _SO_BIT(SO_RCVBUF)
+#define _SO_ERROR _SO_BIT(SO_ERROR)
+#define _SO_TYPE _SO_BIT(SO_TYPE)
+#define _SO_DONTROUTE _SO_BIT(SO_DONTROUTE)
+#define _SO_RCVLOWAT _SO_BIT(SO_RCVLOWAT)
+#define _SO_RCVTIMEO _SO_BIT(SO_RCVTIMEO)
+#define _SO_SNDLOWAT _SO_BIT(SO_SNDLOWAT)
+#define _SO_SNDTIMEO _SO_BIT(SO_SNDTIMEO)
+
+/* This is the larget option value */
+
+#define _SO_MAXOPT (15)
+
+/* Macros to set, test, clear options */
+
+#define _SO_SETOPT(s,o) ((s) |= _SO_BIT(o))
+#define _SO_CLROPT(s,o) ((s) &= ~_SO_BIT(o))
+#define _SO_GETOPT(s,o) (((s) & _SO_BIT(o)) != 0)
+
+/* These are macros that can be used to determine if socket option code is
+ * valid (in range) and supported by API.
+ */
+
+#define _SO_GETONLYSET (_SO_ACCEPTCONN|_SO_ERROR|_SO_TYPE)
+#define _SO_GETONLY(o) ((_SO_BIT(o) & _SO_GETONLYSET) != 0)
+#define _SO_GETVALID(o) (((unsigned int)(o)) <= _SO_MAXOPT)
+#define _SO_SETVALID(o) ((((unsigned int)(o)) <= _SO_MAXOPT) && !_SO_GETONLY(o))
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/* List of registered ethernet device drivers */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+extern struct uip_driver_s *g_netdevices;
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* net_sockets.c *************************************************************/
+
+EXTERN int sockfd_allocate(int minsd);
+EXTERN void sock_release(FAR struct socket *psock);
+EXTERN void sockfd_release(int sockfd);
+EXTERN FAR struct socket *sockfd_socket(int sockfd);
+
+/* net_connect.c *************************************************************/
+
+#ifdef CONFIG_NET_TCP
+EXTERN int net_startmonitor(FAR struct socket *psock);
+EXTERN void net_stopmonitor(FAR struct uip_conn *conn);
+#endif
+
+/* net_close.c ***************************************************************/
+
+EXTERN int psock_close(FAR struct socket *psock);
+
+/* sockopt support ***********************************************************/
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+EXTERN int net_timeo(uint32_t start_time, socktimeo_t timeo);
+EXTERN socktimeo_t net_timeval2dsec(struct timeval *tv);
+EXTERN void net_dsec2timeval(uint16_t dsec, struct timeval *tv);
+#endif
+
+/* net_register.c ************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN void netdev_seminit(void);
+EXTERN void netdev_semtake(void);
+EXTERN void netdev_semgive(void);
+#endif
+
+/* net_findbyname.c **********************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN FAR struct uip_driver_s *netdev_findbyname(const char *ifname);
+#endif
+
+/* net_findbyaddr.c **********************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr);
+#endif
+
+/* net_txnotify.c ************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN void netdev_txnotify(const uip_ipaddr_t *raddr);
+#endif
+
+/* net_count.c ***************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN int netdev_count(void);
+#endif
+
+/* net_arptimer.c ************************************************************/
+
+#ifdef CONFIG_NET_ARP
+EXTERN void arptimer_init(void);
+#else
+# define arptimer_init()
+#endif
+
+/* send.c ********************************************************************/
+
+EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
+ size_t len, int flags);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* CONFIG_NET */
+#endif /* __NET_INTERNAL_H */
diff --git a/nuttx/net/net_monitor.c b/nuttx/net/net_monitor.c
new file mode 100644
index 000000000..4bdae4ccf
--- /dev/null
+++ b/nuttx/net/net_monitor.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * net/net_monitor.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void connection_event(struct uip_conn *conn, uint16_t flags);
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: connection_event
+ *
+ * Description:
+ * Some connection related event has occurred
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static void connection_event(struct uip_conn *conn, uint16_t flags)
+{
+ FAR struct socket *psock = (FAR struct socket *)conn->connection_private;
+
+ if (psock)
+ {
+ nllvdbg("flags: %04x s_flags: %02x\n", flags, psock->s_flags);
+
+ /* These loss-of-connection events may be reported:
+ *
+ * UIP_CLOSE: The remote host has closed the connection
+ * UIP_ABORT: The remote host has aborted the connection
+ * UIP_TIMEDOUT: Connection aborted due to too many retransmissions.
+ *
+ * And we need to set these two socket status bits appropriately:
+ *
+ * _SF_CONNECTED==1 && _SF_CLOSED==0 - the socket is connected
+ * _SF_CONNECTED==0 && _SF_CLOSED==1 - the socket was gracefully disconnected
+ * _SF_CONNECTED==0 && _SF_CLOSED==0 - the socket was rudely disconnected
+ */
+
+ if ((flags & UIP_CLOSE) != 0)
+ {
+ /* The peer gracefully closed the connection. Marking the
+ * connection as disconnected will suppress some subsequent
+ * ENOTCONN errors from receive. A graceful disconnection is
+ * not handle as an error but as an "end-of-file"
+ */
+
+ psock->s_flags &= ~_SF_CONNECTED;
+ psock->s_flags |= _SF_CLOSED;
+ }
+ else if ((flags & (UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ /* The loss of connection was less than graceful. This will (eventually)
+ * be reported as an ENOTCONN error.
+ */
+
+ psock->s_flags &= ~(_SF_CONNECTED |_SF_CLOSED);
+ }
+
+ /* UIP_CONNECTED: The socket is successfully connected */
+
+ else if ((flags & UIP_CONNECTED) != 0)
+ {
+ /* Indicate that the socket is now connected */
+
+ psock->s_flags |= _SF_CONNECTED;
+ psock->s_flags &= ~_SF_CLOSED;
+ }
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: net_startmonitor
+ *
+ * Description:
+ * Set up to receive TCP connection state changes for a given socket
+ *
+ * Input Parameters:
+ * psock - The socket of interest
+ *
+ * Returned Value:
+ * For now, this function always returns OK.
+ *
+ ****************************************************************************/
+
+int net_startmonitor(FAR struct socket *psock)
+{
+ FAR struct uip_conn *conn = psock->s_conn;
+
+ DEBUGASSERT(psock && conn);
+
+ /* Set up to receive callbacks on connection-related events */
+
+ conn->connection_private = (void*)psock;
+ conn->connection_event = connection_event;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: net_stopmonitor
+ *
+ * Description:
+ * Stop monitoring TCP connection changes for a given socket
+ *
+ * Input Parameters:
+ * conn - The TCP connection of interest
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void net_stopmonitor(FAR struct uip_conn *conn)
+{
+ DEBUGASSERT(conn);
+
+ conn->connection_private = NULL;
+ conn->connection_event = NULL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c
new file mode 100644
index 000000000..ca594c10f
--- /dev/null
+++ b/nuttx/net/net_poll.c
@@ -0,0 +1,354 @@
+/****************************************************************************
+ * net/net_poll.c
+ *
+ * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && !defined(CONFIG_DISABLE_POLL)
+
+#include <sys/socket.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <poll.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/net.h>
+#include <nuttx/arch.h>
+
+#include <uip/uip_internal.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Network polling can only be supported on TCP and only if read-ahead buffering
+ * is enabled (it could be supported on UDP as will if it also had read-ahead
+ * buffering.
+ */
+
+#if !defined(CONFIG_DISABLE_POLL) && CONFIG_NSOCKET_DESCRIPTORS > 0 && \
+ defined(CONFIG_NET_TCP) && CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+# define HAVE_NETPOLL 1
+#else
+# undef HAVE_NETPOLL
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: poll_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * TCP receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The structure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_NETPOLL
+static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
+ FAR void *pvpriv, uint16_t flags)
+{
+ FAR struct pollfd *fds = (FAR struct pollfd *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ /* 'priv' might be null in some race conditions (?) */
+
+ if (fds)
+ {
+ pollevent_t eventset = 0;
+
+ /* Check for data or connection availability events. */
+
+ if ((flags & (UIP_NEWDATA|UIP_BACKLOG)) != 0)
+ {
+ eventset |= POLLIN & fds->events;
+ }
+
+ /* A poll is a sign that we are free to send data. */
+
+ if ((flags & UIP_POLL) != 0)
+ {
+ eventset |= POLLOUT & fds->events;
+ }
+
+ /* Check for a loss of connection events */
+
+ if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ eventset |= (POLLERR|POLLHUP);
+ }
+
+ if (eventset)
+ {
+ fds->revents |= eventset;
+ sem_post(fds->sem);
+ }
+ }
+ return flags;
+}
+#endif /* HAVE_NETPOLL */
+
+/****************************************************************************
+ * Function: net_pollsetup
+ *
+ * Description:
+ * Setup to monitor events on one TCP/IP socket
+ *
+ * Input Parameters:
+ * conn - The TCP/IP connection of interest
+ * fds - The structure describing the events to be monitored, OR NULL if
+ * this is a request to stop monitoring events.
+ *
+ * Returned Value:
+ * 0: Success; Negated errno on failure
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_NETPOLL
+static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
+{
+ FAR struct uip_conn *conn = psock->s_conn;
+ FAR struct uip_callback_s *cb;
+ uip_lock_t flags;
+ int ret;
+
+ /* Sanity check */
+
+#ifdef CONFIG_DEBUG
+ if (!conn || !fds)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Some of the following must be atomic */
+
+ flags = uip_lock();
+
+ /* Allocate a TCP/IP callback structure */
+
+ cb = uip_tcpcallbackalloc(conn);
+ if (!cb)
+ {
+ ret = -EBUSY;
+ goto errout_with_irq;
+ }
+
+ /* Initialize the callbcack structure */
+
+ cb->flags = UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ cb->priv = (FAR void *)fds;
+ cb->event = poll_interrupt;
+
+ /* Save the nps reference in the poll structure for use at teardown as well */
+
+ fds->priv = (FAR void *)cb;
+
+#ifdef CONFIG_NET_TCPBACKLOG
+ /* Check for read data or backlogged connection availability now */
+
+ if (!sq_empty(&conn->readahead) || uip_backlogavailable(conn))
+#else
+ /* Check for read data availability now */
+
+ if (!sq_empty(&conn->readahead))
+#endif
+ {
+ fds->revents = fds->events & POLLIN;
+ if (fds->revents != 0)
+ {
+ /* If data is available now, the signal the poll logic */
+
+ sem_post(fds->sem);
+ }
+ }
+ uip_unlock(flags);
+ return OK;
+
+errout_with_irq:
+ uip_unlock(flags);
+ return ret;
+}
+#endif /* HAVE_NETPOLL */
+
+/****************************************************************************
+ * Function: net_pollteardown
+ *
+ * Description:
+ * Teardown monitoring of events on an TCP/IP socket
+ *
+ * Input Parameters:
+ * conn - The TCP/IP connection of interest
+ *
+ * Returned Value:
+ * 0: Success; Negated errno on failure
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_NETPOLL
+static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
+{
+ FAR struct uip_conn *conn = psock->s_conn;
+ FAR struct uip_callback_s *cb;
+ uip_lock_t flags;
+
+ /* Sanity check */
+
+#ifdef CONFIG_DEBUG
+ if (!conn || !fds->priv)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Recover the socket descriptor poll state info from the poll structure */
+
+ cb = (FAR struct uip_callback_s *)fds->priv;
+ if (cb)
+ {
+ /* Release the callback */
+
+ flags = uip_lock();
+ uip_tcpcallbackfree(conn, cb);
+ uip_unlock(flags);
+
+ /* Release the poll/select data slot */
+
+ fds->priv = NULL;
+ }
+
+ return OK;
+}
+#endif /* HAVE_NETPOLL */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_poll
+ *
+ * Description:
+ * The standard poll() operation redirects operations on socket descriptors
+ * to this function.
+ *
+ * Input Parameters:
+ * fd - The socket descriptor of interest
+ * fds - The structure describing the events to be monitored, OR NULL if
+ * this is a request to stop monitoring events.
+ * setup - true: Setup up the poll; false: Teardown the poll
+ *
+ * Returned Value:
+ * 0: Success; Negated errno on failure
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_POLL
+int net_poll(int sockfd, struct pollfd *fds, bool setup)
+{
+#ifndef HAVE_NETPOLL
+ return -ENOSYS;
+#else
+ FAR struct socket *psock;
+ int ret;
+
+ /* Get the underlying socket structure and verify that the sockfd
+ * corresponds to valid, allocated socket
+ */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ ret = -EBADF;
+ goto errout;
+ }
+
+#ifdef CONFIG_NET_UDP
+ /* poll() not supported for UDP */
+
+ if (psock->s_type != SOCK_STREAM)
+ {
+ ret = -ENOSYS;
+ goto errout;
+ }
+#endif
+
+ /* Check if we are setting up or tearing down the poll */
+
+ if (setup)
+ {
+ /* Perform the TCP/IP poll() setup */
+
+ ret = net_pollsetup(psock, fds);
+ }
+ else
+ {
+ /* Perform the TCP/IP poll() teardown */
+
+ ret = net_pollteardown(psock, fds);
+ }
+
+errout:
+ return ret;
+#endif /* HAVE_NETPOLL */
+}
+#endif /* !CONFIG_DISABLE_POLL */
+
+#endif /* CONFIG_NET && !CONFIG_DISABLE_POLL */
diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c
new file mode 100644
index 000000000..81e48c121
--- /dev/null
+++ b/nuttx/net/net_sockets.c
@@ -0,0 +1,313 @@
+/****************************************************************************
+ * net/net_sockets.c
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <string.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/net.h>
+#include <nuttx/kmalloc.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+static void _net_semtake(FAR struct socketlist *list)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (uip_lockedwait(&list->sl_sem) != 0)
+ {
+ /* The only case that an error should occr here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(*get_errno_ptr() == EINTR);
+ }
+}
+
+# define _net_semgive(list) sem_post(&list->sl_sem)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/* This is called from the initialization logic to configure the socket layer */
+
+void net_initialize(void)
+{
+ /* Initialize the uIP layer */
+
+ uip_initialize();
+
+ /* Initialize the socket layer */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ netdev_seminit();
+#endif
+
+ /* Initialize the periodic ARP timer */
+
+ arptimer_init();
+}
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/* Allocate a list of files for a new task */
+
+FAR struct socketlist *net_alloclist(void)
+{
+ FAR struct socketlist *list;
+ list = (FAR struct socketlist*)kzalloc(sizeof(struct socketlist));
+ if (list)
+ {
+ /* Start with a reference count of one */
+
+ list->sl_crefs = 1;
+
+ /* Initialize the list access mutex */
+
+ (void)sem_init(&list->sl_sem, 0, 1);
+ }
+ return list;
+}
+
+/* Increase the reference count on a file list */
+
+int net_addreflist(FAR struct socketlist *list)
+{
+ if (list)
+ {
+ /* Increment the reference count on the list.
+ * NOTE: that we disable interrupts to do this
+ * (vs. taking the list semaphore). We do this
+ * because file cleanup operations often must be
+ * done from the IDLE task which cannot wait
+ * on semaphores.
+ */
+
+ register uip_lock_t flags = uip_lock();
+ list->sl_crefs++;
+ uip_unlock(flags);
+ }
+ return OK;
+}
+
+/* Release a reference to the file list */
+
+int net_releaselist(FAR struct socketlist *list)
+{
+ int crefs;
+ int ndx;
+
+ if (list)
+ {
+ /* Decrement the reference count on the list.
+ * NOTE: that we disable interrupts to do this
+ * (vs. taking the list semaphore). We do this
+ * because file cleanup operations often must be
+ * done from the IDLE task which cannot wait
+ * on semaphores.
+ */
+
+ uip_lock_t flags = uip_lock();
+ crefs = --(list->sl_crefs);
+ uip_unlock(flags);
+
+ /* If the count decrements to zero, then there is no reference
+ * to the structure and it should be deallocated. Since there
+ * are references, it would be an error if any task still held
+ * a reference to the list's semaphore.
+ */
+
+ if (crefs <= 0)
+ {
+ /* Close each open socket in the list
+ * REVISIT: psock_close() will attempt to use semaphores.
+ * If we actually are in the IDLE thread, then could this cause
+ * problems? Probably not, if the task has exited and crefs is
+ * zero, then there probably could not be a contender for the
+ * semaphore.
+ */
+
+ for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++)
+ {
+ FAR struct socket *psock = &list->sl_sockets[ndx];
+ if (psock->s_crefs > 0)
+ {
+ (void)psock_close(psock);
+ }
+ }
+
+ /* Destroy the semaphore and release the filelist */
+
+ (void)sem_destroy(&list->sl_sem);
+ sched_free(list);
+ }
+ }
+ return OK;
+}
+
+int sockfd_allocate(int minsd)
+{
+ FAR struct socketlist *list;
+ int i;
+
+ /* Get the socket list for this task/thread */
+
+ list = sched_getsockets();
+ if (list)
+ {
+ /* Search for a socket structure with no references */
+
+ _net_semtake(list);
+ for (i = minsd; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
+ {
+ /* Are there references on this socket? */
+
+ if (!list->sl_sockets[i].s_crefs)
+ {
+ /* No take the reference and return the index + an offset
+ * as the socket descriptor.
+ */
+
+ memset(&list->sl_sockets[i], 0, sizeof(struct socket));
+ list->sl_sockets[i].s_crefs = 1;
+ _net_semgive(list);
+ return i + __SOCKFD_OFFSET;
+ }
+ }
+ _net_semgive(list);
+ }
+
+ return ERROR;
+}
+
+void sock_release(FAR struct socket *psock)
+{
+#if CONFIG_DEBUG
+ if (psock)
+#endif
+ {
+ /* Take the list semaphore so that there will be no accesses
+ * to this socket structure.
+ */
+
+ FAR struct socketlist *list = sched_getsockets();
+ if (list)
+ {
+ /* Decrement the count if there the socket will persist
+ * after this.
+ */
+
+ _net_semtake(list);
+ if (psock && psock->s_crefs > 1)
+ {
+ psock->s_crefs--;
+ }
+ else
+ {
+ /* The socket will not persist... reset it */
+
+ memset(psock, 0, sizeof(struct socket));
+ }
+ _net_semgive(list);
+ }
+ }
+}
+
+void sockfd_release(int sockfd)
+{
+ /* Get the socket structure for this sockfd */
+
+ FAR struct socket *psock = sockfd_socket(sockfd);
+
+ /* Get the socket structure for this sockfd */
+
+ if (psock)
+ {
+ sock_release(psock);
+ }
+}
+
+FAR struct socket *sockfd_socket(int sockfd)
+{
+ FAR struct socketlist *list;
+ int ndx = sockfd - __SOCKFD_OFFSET;
+
+ if (ndx >=0 && ndx < CONFIG_NSOCKET_DESCRIPTORS)
+ {
+ list = sched_getsockets();
+ if (list)
+ {
+ return &list->sl_sockets[ndx];
+ }
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/net_timeo.c b/nuttx/net/net_timeo.c
new file mode 100644
index 000000000..c593c45c7
--- /dev/null
+++ b/nuttx/net/net_timeo.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * net/net_timeo.c
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/clock.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_timeo
+ *
+ * Description:
+ * Check if a timeout has elapsed. This can be called from a socket poll
+ * function to determine if a timeout has occurred.
+ *
+ * Parameters:
+ * start_time Timeout start time in system clock ticks
+ * timeout Timeout value in deciseconds.
+ *
+ * Returned Value:
+ * 0 (FALSE) if not timeout; 1 (TRUE) if timeout
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int net_timeo(uint32_t start_time, socktimeo_t timeo)
+{
+ uint32_t timeo_ticks = DSEC2TICK(timeo);
+ uint32_t elapsed = clock_systimer() - start_time;
+
+ if (elapsed >= timeo_ticks)
+ {
+ return TRUE;
+ }
+ return FALSE;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+
diff --git a/nuttx/net/net_timeval2dsec.c b/nuttx/net/net_timeval2dsec.c
new file mode 100644
index 000000000..4ca5ecb5f
--- /dev/null
+++ b/nuttx/net/net_timeval2dsec.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * net/net_timeval2dsec.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/socket.h>
+#include <stdint.h>
+#include <errno.h>
+#include <nuttx/clock.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_timeval2dsec
+ *
+ * Description:
+ * Convert a struct timeval to deciseconds. Needed by setsockopt() to
+ * save new timeout values.
+ *
+ * Parameters:
+ * tv The struct timeval to convert
+ *
+ * Returned Value:
+ * the converted value
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+socktimeo_t net_timeval2dsec(struct timeval *tv)
+{
+ return (uint16_t)(tv->tv_sec* DSEC_PER_SEC + tv->tv_usec / USEC_PER_DSEC);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/net/net_vfcntl.c b/nuttx/net/net_vfcntl.c
new file mode 100644
index 000000000..7650264bf
--- /dev/null
+++ b/nuttx/net/net_vfcntl.c
@@ -0,0 +1,234 @@
+/****************************************************************************
+ * net/net_vfcntl.c
+ *
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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/socket.h>
+#include <stdint.h>
+#include <stdarg.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include <arch/irq.h>
+#include <nuttx/net/net.h>
+#include "net_internal.h"
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+int net_vfcntl(int sockfd, int cmd, va_list ap)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ uip_lock_t flags;
+ int err = 0;
+ int ret = 0;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Interrupts must be disabled in order to perform operations on socket structures */
+
+ flags = uip_lock();
+ switch (cmd)
+ {
+ case F_DUPFD:
+ /* Return a new file descriptor which shall be the lowest numbered
+ * available (that is, not already open) file descriptor greater than
+ * or equal to the third argument, arg, taken as an integer of type
+ * int. The new file descriptor shall refer to the same open file
+ * description as the original file descriptor, and shall share any
+ * locks. The FD_CLOEXEC flag associated with the new file descriptor
+ * shall be cleared to keep the file open across calls to one of the
+ * exec functions.
+ */
+
+ {
+ ret = net_dup(sockfd, va_arg(ap, int));
+ }
+ break;
+
+ case F_GETFD:
+ /* Get the file descriptor flags defined in <fcntl.h> that are associated
+ * with the file descriptor fildes. File descriptor flags are associated
+ * with a single file descriptor and do not affect other file descriptors
+ * that refer to the same file.
+ */
+
+ case F_SETFD:
+ /* Set the file descriptor flags defined in <fcntl.h>, that are associated
+ * with fildes, to the third argument, arg, taken as type int. If the
+ * FD_CLOEXEC flag in the third argument is 0, the file shall remain open
+ * across the exec functions; otherwise, the file shall be closed upon
+ * successful execution of one of the exec functions.
+ */
+
+ err = ENOSYS; /* F_GETFD and F_SETFD not implemented */
+ break;
+
+ case F_GETFL:
+ /* Get the file status flags and file access modes, defined in <fcntl.h>,
+ * for the file description associated with fildes. The file access modes
+ * can be extracted from the return value using the mask O_ACCMODE, which is
+ * defined in <fcntl.h>. File status flags and file access modes are associated
+ * with the file description and do not affect other file descriptors that
+ * refer to the same file with different open file descriptions.
+ */
+
+ {
+ /* This summarizes the behavior of the NuttX/uIP sockets */
+
+ ret = O_RDWR | O_SYNC | O_RSYNC;
+
+ /* TCP/IP sockets may also be non-blocking if read-ahead is enabled */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ if (psock->s_type == SOCK_STREAM && _SS_ISNONBLOCK(psock->s_flags))
+ {
+ ret |= O_NONBLOCK;
+ }
+#endif
+ }
+ break;
+
+ case F_SETFL:
+ /* Set the file status flags, defined in <fcntl.h>, for the file description
+ * associated with fildes from the corresponding bits in the third argument,
+ * arg, taken as type int. Bits corresponding to the file access mode and
+ * the file creation flags, as defined in <fcntl.h>, that are set in arg shall
+ * be ignored. If any bits in arg other than those mentioned here are changed
+ * by the application, the result is unspecified.
+ */
+
+ {
+ /* Non-blocking is the only configurable option. And it applies only to
+ * read operations on TCP/IP sockets when read-ahead is enabled.
+ */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ int mode = va_arg(ap, int);
+ if (psock->s_type == SOCK_STREAM)
+ {
+ if ((mode & O_NONBLOCK) != 0)
+ {
+ psock->s_flags |= _SF_NONBLOCK;
+ }
+ else
+ {
+ psock->s_flags &= ~_SF_NONBLOCK;
+ }
+ }
+#endif
+ }
+ break;
+
+ case F_GETOWN:
+ /* If fildes refers to a socket, get the process or process group ID specified
+ * to receive SIGURG signals when out-of-band data is available. Positive values
+ * indicate a process ID; negative values, other than -1, indicate a process group
+ * ID. If fildes does not refer to a socket, the results are unspecified.
+ */
+
+ case F_SETOWN:
+ /* If fildes refers to a socket, set the process or process group ID specified
+ * to receive SIGURG signals when out-of-band data is available, using the value
+ * of the third argument, arg, taken as type int. Positive values indicate a
+ * process ID; negative values, other than -1, indicate a process group ID. If
+ * fildes does not refer to a socket, the results are unspecified.
+ */
+
+ case F_GETLK:
+ /* Get the first lock which blocks the lock description pointed to by the third
+ * argument, arg, taken as a pointer to type struct flock, defined in <fcntl.h>.
+ * The information retrieved shall overwrite the information passed to fcntl() in
+ * the structure flock. If no lock is found that would prevent this lock from being
+ * created, then the structure shall be left unchanged except for the lock type
+ * which shall be set to F_UNLCK.
+ */
+
+ case F_SETLK:
+ /* Set or clear a file segment lock according to the lock description pointed to
+ * by the third argument, arg, taken as a pointer to type struct flock, defined in
+ * <fcntl.h>. F_SETLK can establish shared (or read) locks (F_RDLCK) or exclusive
+ * (or write) locks (F_WRLCK), as well as to remove either type of lock (F_UNLCK).
+ * F_RDLCK, F_WRLCK, and F_UNLCK are defined in <fcntl.h>. If a shared or exclusive
+ * lock cannot be set, fcntl() shall return immediately with a return value of -1.
+ */
+
+ case F_SETLKW:
+ /* This command shall be equivalent to F_SETLK except that if a shared or exclusive
+ * lock is blocked by other locks, the thread shall wait until the request can be
+ * satisfied. If a signal that is to be caught is received while fcntl() is waiting
+ * for a region, fcntl() shall be interrupted. Upon return from the signal handler,
+ * fcntl() shall return -1 with errno set to [EINTR], and the lock operation shall
+ * not be done.
+ */
+
+ err = ENOSYS; /* F_GETOWN, F_SETOWN, F_GETLK, F_SETLK, F_SETLKW */
+ break;
+
+ default:
+ err = EINVAL;
+ break;
+ }
+
+ uip_unlock(flags);
+
+errout:
+ if (err != 0)
+ {
+ errno = err;
+ return ERROR;
+ }
+ return ret;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
diff --git a/nuttx/net/netdev_count.c b/nuttx/net/netdev_count.c
new file mode 100644
index 000000000..17f0894da
--- /dev/null
+++ b/nuttx/net/netdev_count.c
@@ -0,0 +1,102 @@
+/****************************************************************************
+ * net/netdev_count.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_count
+ *
+ * Description:
+ * Return the number of network devices
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * The number of network devices
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_count(void)
+{
+ struct uip_driver_s *dev;
+ int ndev;
+
+ netdev_semtake();
+ for (dev = g_netdevices, ndev = 0; dev; dev = dev->flink, ndev++);
+ netdev_semgive();
+ return ndev;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_findbyaddr.c b/nuttx/net/netdev_findbyaddr.c
new file mode 100644
index 000000000..50a246f67
--- /dev/null
+++ b/nuttx/net/netdev_findbyaddr.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ * net/netdev_findbyaddr.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_maskcmp
+ ****************************************************************************/
+
+static inline bool netdev_maskcmp(const uip_ipaddr_t *ipaddr,
+ const uip_ipaddr_t *raddr,
+ const uip_ipaddr_t *netmask)
+{
+#ifndef CONFIG_NET_IPv6
+ return (*ipaddr & *netmask) == (*raddr & *netmask);
+#else
+# warning "Not implemented for IPv6"
+ return false;
+#endif
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_findbyaddr
+ *
+ * Description:
+ * Find a previously registered network device by matching a remote address
+ * with the subnet served by the device
+ *
+ * Parameters:
+ * raddr - Pointer to the remote address of a connection
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr)
+{
+ struct uip_driver_s *dev;
+
+ if (raddr)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (netdev_maskcmp(&dev->d_ipaddr, raddr, &dev->d_netmask))
+ {
+ netdev_semgive();
+ return dev;
+ }
+ }
+ netdev_semgive();
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_findbyname.c b/nuttx/net/netdev_findbyname.c
new file mode 100644
index 000000000..a6ddf0452
--- /dev/null
+++ b/nuttx/net/netdev_findbyname.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ * net/netdev_findbyname.c
+ *
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_findbyname
+ *
+ * Description:
+ * Find a previously registered network device using its assigned
+ * network interface name
+ *
+ * Parameters:
+ * ifname The interface name of the device of interest
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+FAR struct uip_driver_s *netdev_findbyname(const char *ifname)
+{
+ struct uip_driver_s *dev;
+ if (ifname)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (strcmp(ifname, dev->d_ifname) == 0)
+ {
+ netdev_semgive();
+ return dev;
+ }
+ }
+ netdev_semgive();
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_foreach.c b/nuttx/net/netdev_foreach.c
new file mode 100644
index 000000000..f88444ad8
--- /dev/null
+++ b/nuttx/net/netdev_foreach.c
@@ -0,0 +1,114 @@
+/****************************************************************************
+ * net/netdev_foreach.c
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <debug.h>
+#include <nuttx/net/net.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_foreach
+ *
+ * Description:
+ * Enumerate each registered network device.
+ *
+ * NOTE: netdev semaphore held throughout enumeration.
+ *
+ * Parameters:
+ * callback - Will be called for each registered device
+ * arg - User argument passed to callback()
+ *
+ * Returned Value:
+ * 0:Enumeration completed 1:Enumeration terminated early by callback
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_foreach(netdev_callback_t callback, void *arg)
+{
+ struct uip_driver_s *dev;
+ int ret = 0;
+
+ if (callback)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (callback(dev, arg) != 0)
+ {
+ ret = 1;
+ break;
+ }
+ }
+ netdev_semgive();
+ }
+ return ret;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c
new file mode 100644
index 000000000..4b5876efa
--- /dev/null
+++ b/nuttx/net/netdev_ioctl.c
@@ -0,0 +1,419 @@
+/****************************************************************************
+ * net/netdev_ioctl.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/net.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/uip/uip-arch.h>
+#include <nuttx/net/uip/uip.h>
+
+#ifdef CONFIG_NET_IGMP
+# include "sys/sockio.h"
+# include "nuttx/net/uip/uip-igmp.h"
+#endif
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+# define AF_INETX AF_INET6
+#else
+# define AF_INETX AF_INET
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ioctl_getipaddr
+ *
+ * Description:
+ * Copy IP addresses from device structure to user memory.
+ *
+ * Input Parameters:
+ * outaddr - Pointer to the user-provided memory to receive the address.
+ * Actual type may be either 'struct sockaddr' (IPv4 only) or type
+ * 'struct sockaddr_storage' (both IPv4 and IPv6).
+ * inaddr - The source IP adress in the device structure.
+ *
+ ****************************************************************************/
+
+static void ioctl_getipaddr(FAR void *outaddr, FAR const uip_ipaddr_t *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *dest = (FAR struct sockaddr_in6 *)outaddr;
+ dest->sin_family = AF_INET6;
+ dest->sin_port = 0;
+ memcpy(dest->sin6_addr.in6_u.u6_addr8, inaddr, 16);
+#else
+ FAR struct sockaddr_in *dest = (FAR struct sockaddr_in *)outaddr;
+ dest->sin_family = AF_INET;
+ dest->sin_port = 0;
+ dest->sin_addr.s_addr = *inaddr;
+#endif
+}
+
+/****************************************************************************
+ * Name: ioctl_setipaddr
+ *
+ * Description:
+ * Copy IP addresses from user memory into the device structure
+ *
+ * Input Parameters:
+ * outaddr - Pointer to the source IP address in the device structure.
+ * inaddr - Pointer to the user-provided memory to containing the new IP
+ * address. Actual type may be either 'struct sockaddr' (IPv4 only) or
+ * type 'struct sockaddr_storage' (both IPv4 and IPv6).
+ *
+ ****************************************************************************/
+
+static void ioctl_setipaddr(FAR uip_ipaddr_t *outaddr, FAR const void *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *src = (FAR const struct sockaddr_in6 *)inaddr;
+ memcpy(outaddr, src->sin6_addr.in6_u.u6_addr8, 16);
+#else
+ FAR const struct sockaddr_in *src = (FAR const struct sockaddr_in *)inaddr;
+ *outaddr = src->sin_addr.s_addr;
+#endif
+}
+
+/****************************************************************************
+ * Name: ioctl_ifup / ioctl_ifdown
+ *
+ * Description:
+ * Bring the interface up/down
+ *
+ ****************************************************************************/
+
+static inline void ioctl_ifup(FAR struct uip_driver_s *dev)
+{
+ if (dev->d_ifup)
+ {
+ dev->d_ifup(dev);
+ }
+}
+
+static inline void ioctl_ifdown(FAR struct uip_driver_s *dev)
+{
+ if (dev->d_ifdown)
+ {
+ dev->d_ifdown(dev);
+ }
+}
+
+/****************************************************************************
+ * Name: netdev_ioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * psock Socket structure
+ * dev Ethernet driver device structure
+ * cmd The ioctl command
+ * req The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * Negated errno returned on failure.
+ *
+ ****************************************************************************/
+
+static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req)
+{
+ FAR struct uip_driver_s *dev;
+ int ret = OK;
+
+ nvdbg("cmd: %d\n", cmd);
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ dev = netdev_findbyname(req->ifr_name);
+ if (!dev)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCGIFADDR: /* Get IP address */
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr);
+ break;
+
+ case SIOCSIFADDR: /* Set IP address */
+ ioctl_ifdown(dev);
+ ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr);
+ ioctl_ifup(dev);
+ break;
+
+ case SIOCGIFDSTADDR: /* Get P-to-P address */
+ ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr);
+ break;
+
+ case SIOCSIFDSTADDR: /* Set P-to-P address */
+ ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr);
+ break;
+
+ case SIOCGIFNETMASK: /* Get network mask */
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask);
+ break;
+
+ case SIOCSIFNETMASK: /* Set network mask */
+ ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr);
+ break;
+
+ case SIOCGIFMTU: /* Get MTU size */
+ req->ifr_mtu = CONFIG_NET_BUFSIZE;
+ break;
+
+ /* MAC address operations only make sense if Ethernet is supported */
+
+#ifdef CONFIG_NET_ETHERNET
+ case SIOCGIFHWADDR: /* Get hardware address */
+ req->ifr_hwaddr.sa_family = AF_INETX;
+ memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.ether_addr_octet, IFHWADDRLEN);
+ break;
+
+ case SIOCSIFHWADDR: /* Set hardware address -- will not take effect until ifup */
+ req->ifr_hwaddr.sa_family = AF_INETX;
+ memcpy(dev->d_mac.ether_addr_octet, req->ifr_hwaddr.sa_data, IFHWADDRLEN);
+ break;
+#endif
+
+ case SIOCDIFADDR: /* Delete IP address */
+ ioctl_ifdown(dev);
+ memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t));
+ break;
+
+ case SIOCGIFCOUNT: /* Get number of devices */
+ req->ifr_count = netdev_count();
+ ret = -ENOSYS;
+ break;
+
+ case SIOCGIFBRDADDR: /* Get broadcast IP address */
+ case SIOCSIFBRDADDR: /* Set broadcast IP address */
+ ret = -ENOSYS;
+ break;
+
+#ifdef CONFIG_NET_ARPIOCTLS
+ case SIOCSARP: /* Set a ARP mapping */
+ case SIOCDARP: /* Delete an ARP mapping */
+ case SIOCGARP: /* Get an ARP mapping */
+# error "IOCTL Commands not implemented"
+#endif
+
+ default:
+ ret = -EINVAL;
+ break;;
+ }
+
+errout:
+ return ret;
+}
+
+/****************************************************************************
+ * Name: netdev_imsfioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * psock Socket structure
+ * dev Ethernet driver device structure
+ * cmd The ioctl command
+ * imsf The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * Negated errno returned on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int netdev_imsfioctl(FAR struct socket *psock, int cmd, struct ip_msfilter *imsf)
+{
+ FAR struct uip_driver_s *dev;
+ int ret = OK;
+
+ nvdbg("cmd: %d\n", cmd);
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ dev = netdev_findbyname(imsf->imsf_name);
+ if (!dev)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCSIPMSFILTER: /* Set source filter content */
+ {
+ if (imsf->imsf_fmode == MCAST_INCLUDE)
+ {
+ ret = igmp_joingroup(dev, &imsf->imsf_multiaddr);
+ }
+ else
+ {
+ DEBUGASSERT(imsf->imsf_fmode == MCAST_EXCLUDE);
+ ret = igmp_leavegroup(dev, &imsf->imsf_multiaddr);
+ }
+ }
+ break;
+
+ case SIOCGIPMSFILTER: /* Retrieve source filter addresses */
+ default:
+ ret = -EINVAL;
+ break;
+ }
+
+errout:
+ return ret;
+}
+#endif
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: netdev_ioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of device
+ * cmd The ioctl command
+ * req The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * On a failure, -1 is returned with errno set appropriately
+ *
+ * EBADF
+ * 'sockfd' is not a valid descriptor.
+ * EFAULT
+ * 'req' references an inaccessible memory area.
+ * EINVAL
+ * 'cmd' or 'req' is not valid.
+ * ENOTTY
+ * 'sockfd' is not associated with a network device.
+ * ENOTTY
+ * The specified request does not apply to the kind of object that the
+ * descriptor 'sockfd' references.
+ *
+ ****************************************************************************/
+
+int netdev_ioctl(int sockfd, int cmd, unsigned long arg)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ int ret;
+
+ /* Check if this is a valid command. In all cases, arg is a pointer that has
+ * been cast to unsigned long. Verify that the value of the to-be-pointer is
+ * non-NULL.
+ */
+
+ if (!_SIOCVALID(cmd) || !arg)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ ret = -EBADF;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq*)arg);
+#ifdef CONFIG_NET_IGMP
+ if (ret == -EINVAL)
+ {
+ ret = netdev_imsfioctl(psock, cmd, (FAR struct ip_msfilter*)arg);
+ }
+#endif
+
+ /* Check for success or failure */
+
+ if (ret >= 0)
+ {
+ return ret;
+ }
+
+/* On failure, set the errno and return -1 */
+
+errout:
+ errno = -ret;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_register.c b/nuttx/net/netdev_register.c
new file mode 100644
index 000000000..31cf884e4
--- /dev/null
+++ b/nuttx/net/netdev_register.c
@@ -0,0 +1,149 @@
+/****************************************************************************
+ * net/netdev_register.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_SLIP
+# define NETDEV_FORMAT "sl%d"
+#else
+# define NETDEV_FORMAT "eth%d"
+#endif
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int g_next_devnum = 0;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* List of registered ethernet device drivers */
+
+struct uip_driver_s *g_netdevices = NULL;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_register
+ *
+ * Description:
+ * Register a network device driver and assign a name to it so tht it can
+ * be found in subsequent network ioctl operations on the device.
+ *
+ * Parameters:
+ * dev - The device driver structure to register
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ * Assumptions:
+ * Called during system initialization from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_register(FAR struct uip_driver_s *dev)
+{
+ if (dev)
+ {
+ int devnum;
+ netdev_semtake();
+
+ /* Assign a device name to the interface */
+
+ devnum = g_next_devnum++;
+ snprintf(dev->d_ifname, IFNAMSIZ, NETDEV_FORMAT, devnum );
+
+ /* Add the device to the list of known network devices */
+
+ dev->flink = g_netdevices;
+ g_netdevices = dev;
+
+ /* Configure the device for IGMP support */
+
+#ifdef CONFIG_NET_IGMP
+ uip_igmpdevinit(dev);
+#endif
+ netdev_semgive();
+
+#ifdef CONFIG_NET_ETHERNET
+ nlldbg("Registered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
+ dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
+ dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
+ dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5],
+ dev->d_ifname);
+#else
+ nlldbg("Registered dev: %s\n", dev->d_ifname);
+#endif
+ return OK;
+ }
+ return -EINVAL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_sem.c b/nuttx/net/netdev_sem.c
new file mode 100644
index 000000000..ba6299c62
--- /dev/null
+++ b/nuttx/net/netdev_sem.c
@@ -0,0 +1,178 @@
+/****************************************************************************
+ * net/netdev_sem.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+
+#include <unistd.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define NO_HOLDER (pid_t)-1
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/* There is at least on context in which recursive semaphores are required:
+ * When netdev_foreach is used with a telnet client, we will deadlock if we
+ * do not provide this capability.
+ */
+
+struct netdev_sem_s
+{
+ sem_t sem;
+ pid_t holder;
+ unsigned int count;
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+static struct netdev_sem_s g_devlock;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_seminit
+ *
+ * Description:
+ * Initialize the network device semaphore.
+ *
+ ****************************************************************************/
+
+void netdev_seminit(void)
+{
+ sem_init(&g_devlock.sem, 0, 1);
+ g_devlock.holder = NO_HOLDER;
+ g_devlock.count = 0;
+}
+
+/****************************************************************************
+ * Function: netdev_semtake
+ *
+ * Description:
+ * Get exclusive access to the network device list.
+ *
+ ****************************************************************************/
+
+void netdev_semtake(void)
+{
+ pid_t me = getpid();
+
+ /* Does this thread already hold the semaphore? */
+
+ if (g_devlock.holder == me)
+ {
+ /* Yes.. just increment the reference count */
+
+ g_devlock.count++;
+ }
+ else
+ {
+ /* No.. take the semaphore (perhaps waiting) */
+
+ while (uip_lockedwait(&g_devlock.sem) != 0)
+ {
+ /* The only case that an error should occur here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+
+ /* Now this thread holds the semaphore */
+
+ g_devlock.holder = me;
+ g_devlock.count = 1;
+ }
+}
+
+/****************************************************************************
+ * Function: netdev_semtake
+ *
+ * Description:
+ * Release exclusive access to the network device list
+ *
+ ****************************************************************************/
+
+void netdev_semgive(void)
+{
+ DEBUGASSERT(g_devlock.holder == getpid() && g_devlock.count > 0);
+
+ /* If the count would go to zero, then release the semaphore */
+
+ if (g_devlock.count == 1)
+ {
+ /* We no longer hold the semaphore */
+
+ g_devlock.holder = NO_HOLDER;
+ g_devlock.count = 0;
+ sem_post(&g_devlock.sem);
+ }
+ else
+ {
+ /* We still hold the semaphore. Just decrement the count */
+
+ g_devlock.count--;
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_txnotify.c b/nuttx/net/netdev_txnotify.c
new file mode 100644
index 000000000..4cb705ea8
--- /dev/null
+++ b/nuttx/net/netdev_txnotify.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * net/netdev_txnotify.c
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_txnotify
+ *
+ * Description:
+ * Notify the device driver that new TX data is available.
+ *
+ * Parameters:
+ * raddr - Pointer to the remote address to send the data
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+void netdev_txnotify(const uip_ipaddr_t *raddr)
+{
+ /* Find the device driver that serves the subnet of the remote address */
+
+ struct uip_driver_s *dev = netdev_findbyaddr(raddr);
+ if (dev && dev->d_txavail)
+ {
+ /* Notify the device driver that new TX data is available. */
+
+ (void)dev->d_txavail(dev);
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev_unregister.c b/nuttx/net/netdev_unregister.c
new file mode 100644
index 000000000..e1aec0e4d
--- /dev/null
+++ b/nuttx/net/netdev_unregister.c
@@ -0,0 +1,159 @@
+/****************************************************************************
+ * net/netdev_unregister.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_SLIP
+# define NETDEV_FORMAT "sl%d"
+#else
+# define NETDEV_FORMAT "eth%d"
+#endif
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_unregister
+ *
+ * Description:
+ * Unregister a network device driver.
+ *
+ * Parameters:
+ * dev - The device driver structure to un-register
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ * Assumptions:
+ * Currently only called for USB networking devices when the device is
+ * physically removed from the slot
+ *
+ ****************************************************************************/
+
+int netdev_unregister(FAR struct uip_driver_s *dev)
+{
+ struct uip_driver_s *prev;
+ struct uip_driver_s *curr;
+
+ if (dev)
+ {
+ netdev_semtake();
+
+ /* Find the device in the list of known network devices */
+
+ for (prev = NULL, curr = g_netdevices;
+ curr && curr != dev;
+ prev = curr, curr = curr->flink);
+
+ /* Remove the device to the list of known network devices */
+
+ if (curr)
+ {
+ /* Where was the entry */
+
+ if (prev)
+ {
+ /* The entry was in the middle or at the end of the list */
+
+ prev->flink = curr->flink;
+ }
+ else
+ {
+ /* The entry was at the beginning of the list */
+
+ g_netdevices = curr;
+ }
+
+ curr->flink = NULL;
+ }
+
+ netdev_semgive();
+
+#ifdef CONFIG_NET_ETHERNET
+ nlldbg("Unregistered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
+ dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
+ dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
+ dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5],
+ dev->d_ifname);
+#else
+ nlldbg("Registered dev: %s\n", dev->d_ifname);
+#endif
+ return OK;
+ }
+
+ return -EINVAL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/recv.c b/nuttx/net/recv.c
new file mode 100644
index 000000000..1571a7377
--- /dev/null
+++ b/nuttx/net/recv.c
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * net/recv.c
+ *
+ * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: recv
+ *
+ * Description:
+ * The recv() call is identical to recvfrom() with a NULL from parameter.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * buf Buffer to receive data
+ * len Length of buffer
+ * flags Receive flags
+ *
+ * Returned Value:
+ * (see recvfrom)
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t recv(int sockfd, FAR void *buf, size_t len, int flags)
+{
+ return recvfrom(sockfd, buf, len, flags, NULL, 0);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
new file mode 100644
index 000000000..741cd4c72
--- /dev/null
+++ b/nuttx/net/recvfrom.c
@@ -0,0 +1,1308 @@
+/****************************************************************************
+ * net/recvfrom.c
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <stdint.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/clock.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define TCP_TIMEO 10 /* Deciseconds after data received before recv() returns */
+
+#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define TCPBUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+struct recvfrom_s
+{
+ FAR struct socket *rf_sock; /* The parent socket structure */
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ uint32_t rf_starttime; /* rcv start time for determining timeout */
+#endif
+ FAR struct uip_callback_s *rf_cb; /* Reference to callback instance */
+ sem_t rf_sem; /* Semaphore signals recv completion */
+ size_t rf_buflen; /* Length of receive buffer */
+ char *rf_buffer; /* Pointer to receive buffer */
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *rf_from; /* Address of sender */
+#else
+ FAR struct sockaddr_in *rf_from; /* Address of sender */
+#endif
+ size_t rf_recvlen; /* The received length */
+ int rf_result; /* OK:success, failure:negated errno */
+};
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: recvfrom_newdata
+ *
+ * Description:
+ * Copy the read data from the packet
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * The number of bytes taken from the packet.
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+static size_t recvfrom_newdata(FAR struct uip_driver_s *dev,
+ FAR struct recvfrom_s *pstate)
+{
+ size_t recvlen;
+
+ /* Get the length of the data to return */
+
+ if (dev->d_len > pstate->rf_buflen)
+ {
+ recvlen = pstate->rf_buflen;
+ }
+ else
+ {
+ recvlen = dev->d_len;
+ }
+
+ /* Copy the new appdata into the user buffer */
+
+ memcpy(pstate->rf_buffer, dev->d_appdata, recvlen);
+ nllvdbg("Received %d bytes (of %d)\n", (int)recvlen, (int)dev->d_len);
+
+ /* Update the accumulated size of the data read */
+
+ pstate->rf_recvlen += recvlen;
+ pstate->rf_buffer += recvlen;
+ pstate->rf_buflen -= recvlen;
+
+ return recvlen;
+}
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_newtcpdata
+ *
+ * Description:
+ * Copy the read data from the packet
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * None.
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline void recvfrom_newtcpdata(FAR struct uip_driver_s *dev,
+ FAR struct recvfrom_s *pstate)
+{
+ /* Take as much data from the packet as we can */
+
+ size_t recvlen = recvfrom_newdata(dev, pstate);
+
+ /* If there is more data left in the packet that we could not buffer, than
+ * add it to the read-ahead buffers.
+ */
+
+ if (recvlen < dev->d_len)
+ {
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ FAR struct uip_conn *conn = (FAR struct uip_conn *)pstate->rf_sock->s_conn;
+ FAR uint8_t *buffer = (FAR uint8_t *)dev->d_appdata + recvlen;
+ uint16_t buflen = dev->d_len - recvlen;
+ uint16_t nsaved;
+
+ nsaved = uip_datahandler(conn, buffer, buflen);
+
+ /* There are complicated buffering issues that are not addressed fully
+ * here. For example, what if up_datahandler() cannot buffer the
+ * remainder of the packet? In that case, the data will be dropped but
+ * still ACKed. Therefore it would not be resent.
+ *
+ * This is probably not an issue here because we only get here if the
+ * read-ahead buffers are empty and there would have to be something
+ * serioulsy wrong with the configuration not to be able to buffer a
+ * partial packet in this context.
+ */
+
+#ifdef CONFIG_DEBUG_NET
+ if (nsaved < buflen)
+ {
+ ndbg("ERROR: packet data not saved (%d bytes)\n", buflen - nsaved);
+ }
+#endif
+#else
+ ndbg("ERROR: packet data lost (%d bytes)\n", dev->d_len - recvlen);
+#endif
+ }
+
+ /* Indicate no data in the buffer */
+
+ dev->d_len = 0;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_newudpdata
+ *
+ * Description:
+ * Copy the read data from the packet
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * None.
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+static inline void recvfrom_newudpdata(FAR struct uip_driver_s *dev,
+ FAR struct recvfrom_s *pstate)
+{
+ /* Take as much data from the packet as we can */
+
+ (void)recvfrom_newdata(dev, pstate);
+
+ /* Indicate no data in the buffer */
+
+ dev->d_len = 0;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_readahead
+ *
+ * Description:
+ * Copy the read data from the packet
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_TCP) && CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+static inline void recvfrom_readahead(struct recvfrom_s *pstate)
+{
+ FAR struct uip_conn *conn = (FAR struct uip_conn *)pstate->rf_sock->s_conn;
+ FAR struct uip_readahead_s *readahead;
+ size_t recvlen;
+
+ /* Check there is any TCP data already buffered in a read-ahead
+ * buffer.
+ */
+
+ do
+ {
+ /* Get the read-ahead buffer at the head of the list (if any) */
+
+ readahead = (struct uip_readahead_s *)sq_remfirst(&conn->readahead);
+ if (readahead)
+ {
+ /* We have a new buffer... transfer that buffered data into
+ * the user buffer.
+ *
+ * First, get the length of the data to transfer.
+ */
+
+ if (readahead->rh_nbytes > pstate->rf_buflen)
+ {
+ recvlen = pstate->rf_buflen;
+ }
+ else
+ {
+ recvlen = readahead->rh_nbytes;
+ }
+
+ if (recvlen > 0)
+ {
+ /* Copy the read-ahead data into the user buffer */
+
+ memcpy(pstate->rf_buffer, readahead->rh_buffer, recvlen);
+ nllvdbg("Received %d bytes (of %d)\n", recvlen, readahead->rh_nbytes);
+
+ /* Update the accumulated size of the data read */
+
+ pstate->rf_recvlen += recvlen;
+ pstate->rf_buffer += recvlen;
+ pstate->rf_buflen -= recvlen;
+ }
+
+ /* If the read-ahead buffer is empty, then release it. If not, then
+ * we will have to move the data down and return the buffer to the
+ * front of the list.
+ */
+
+ if (recvlen < readahead->rh_nbytes)
+ {
+ readahead->rh_nbytes -= recvlen;
+ memcpy(readahead->rh_buffer, &readahead->rh_buffer[recvlen],
+ readahead->rh_nbytes);
+ sq_addfirst(&readahead->rh_node, &conn->readahead);
+ }
+ else
+ {
+ uip_tcpreadaheadrelease(readahead);
+ }
+ }
+ }
+ while (readahead && pstate->rf_buflen > 0);
+}
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_timeout
+ *
+ * Description:
+ * Check for recvfrom timeout.
+ *
+ * Parameters:
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * TRUE:timeout FALSE:no timeout
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+static int recvfrom_timeout(struct recvfrom_s *pstate)
+{
+ FAR struct socket *psock = 0;
+ socktimeo_t timeo = 0;
+
+ /* If this is a TCP socket that has already received some data,
+ * than we will always use a short timeout.
+ */
+
+ if (pstate->rf_recvlen > 0)
+ {
+ /* Use the short timeout */
+
+ timeo = TCP_TIMEO;
+ }
+
+ /* No.. check for a timeout configured via setsockopts(SO_RCVTIMEO).
+ * If none... we well let the read hang forever.
+ */
+
+ else
+ {
+ /* Get the socket reference from the private data */
+
+ psock = pstate->rf_sock;
+ if (psock)
+ {
+ timeo = psock->s_rcvtimeo;
+ }
+ }
+
+ /* Is there an effective timeout? */
+
+ if (timeo)
+ {
+ /* Yes.. Check if the timeout has elapsed */
+
+ return net_timeo(pstate->rf_starttime, timeo);
+ }
+
+ /* No timeout */
+
+ return FALSE;
+}
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_tcpsender
+ *
+ * Description:
+ * Getting the sender's address from the UDP packet
+ *
+ * Parameters:
+ * dev - The device driver data structure
+ * pstate - the recvfrom state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline void recvfrom_tcpsender(struct uip_driver_s *dev, struct recvfrom_s *pstate)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *infrom = pstate->rf_from;
+#else
+ FAR struct sockaddr_in *infrom = pstate->rf_from;
+#endif
+
+ if (infrom)
+ {
+ infrom->sin_family = AF_INET;
+ infrom->sin_port = TCPBUF->srcport;
+
+#ifdef CONFIG_NET_IPv6
+ uip_ipaddr_copy(infrom->sin6_addr.s6_addr, TCPBUF->srcipaddr);
+#else
+ uip_ipaddr_copy(infrom->sin_addr.s_addr, uip_ip4addr_conv(TCPBUF->srcipaddr));
+#endif
+ }
+}
+#endif
+
+/****************************************************************************
+ * Function: recvfrom_tcpinterrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * TCP receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The structure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
+ void *pvpriv, uint16_t flags)
+{
+ struct recvfrom_s *pstate = (struct recvfrom_s *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ /* 'priv' might be null in some race conditions (?) */
+
+ if (pstate)
+ {
+ /* If new data is available, then complete the read action. */
+
+ if ((flags & UIP_NEWDATA) != 0)
+ {
+ /* Copy the data from the packet (saving any unused bytes from the
+ * packet in the read-ahead buffer).
+ */
+
+ recvfrom_newtcpdata(dev, pstate);
+
+ /* Save the sender's address in the caller's 'from' location */
+
+ recvfrom_tcpsender(dev, pstate);
+
+ /* Indicate that the data has been consumed and that an ACK
+ * should be sent.
+ */
+
+ flags = (flags & ~UIP_NEWDATA) | UIP_SNDACK;
+
+ /* If the user buffer has been filled, then we are finished. */
+
+ if (pstate->rf_buflen == 0)
+ {
+ nllvdbg("TCP resume\n");
+
+ /* The TCP receive buffer is full. Return now and don't allow
+ * any further TCP call backs.
+ */
+
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->priv = NULL;
+ pstate->rf_cb->event = NULL;
+
+ /* Wake up the waiting thread, returning the number of bytes
+ * actually read.
+ */
+
+ sem_post(&pstate->rf_sem);
+ }
+
+ /* Reset the timeout. We will want a short timeout to terminate
+ * the TCP receive.
+ */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ pstate->rf_starttime = clock_systimer();
+#endif
+ }
+
+ /* Check for a loss of connection.
+ *
+ * UIP_CLOSE: The remote host has closed the connection
+ * UIP_ABORT: The remote host has aborted the connection
+ * UIP_TIMEDOUT: Connection aborted due to too many retransmissions.
+ */
+
+ else if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ nllvdbg("error\n");
+
+ /* Stop further callbacks */
+
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->priv = NULL;
+ pstate->rf_cb->event = NULL;
+
+ /* If the peer gracefully closed the connection, then return zero
+ * (end-of-file). Otherwise, report a not-connected error
+ */
+
+ if ((flags & UIP_CLOSE) != 0)
+ {
+ pstate->rf_result = 0;
+ }
+ else
+ {
+ pstate->rf_result = -ENOTCONN;
+ }
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->rf_sem);
+ }
+
+ /* No data has been received -- this is some other event... probably a
+ * poll -- check for a timeout.
+ */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ else if (recvfrom_timeout(pstate))
+ {
+ /* Yes.. the timeout has elapsed... do not allow any further
+ * callbacks
+ */
+
+ nllvdbg("TCP timeout\n");
+
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->priv = NULL;
+ pstate->rf_cb->event = NULL;
+
+ /* Report an error only if no data has been received */
+
+ if (pstate->rf_recvlen == 0)
+ {
+ /* Report the timeout error */
+
+ pstate->rf_result = -EAGAIN;
+ }
+
+ /* Wake up the waiting thread, returning either the error -EAGAIN
+ * that signals the timeout event or the data received up to
+ * the point tht the timeout occured (no error).
+ */
+
+ sem_post(&pstate->rf_sem);
+ }
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+ }
+ return flags;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_udpsender
+ *
+ * Description:
+ * Getting the sender's address from the UDP packet
+ *
+ * Parameters:
+ * dev - The device driver data structure
+ * pstate - the recvfrom state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+static inline void recvfrom_udpsender(struct uip_driver_s *dev, struct recvfrom_s *pstate)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *infrom = pstate->rf_from;
+#else
+ FAR struct sockaddr_in *infrom = pstate->rf_from;
+#endif
+
+ if (infrom)
+ {
+ infrom->sin_family = AF_INET;
+ infrom->sin_port = UDPBUF->srcport;
+
+#ifdef CONFIG_NET_IPv6
+ uip_ipaddr_copy(infrom->sin6_addr.s6_addr, UDPBUF->srcipaddr);
+#else
+ uip_ipaddr_copy(infrom->sin_addr.s_addr, uip_ip4addr_conv(UDPBUF->srcipaddr));
+#endif
+ }
+}
+#endif
+
+/****************************************************************************
+ * Function: recvfrom_udpinterrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * UDP receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+static uint16_t recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvpriv, uint16_t flags)
+{
+ struct recvfrom_s *pstate = (struct recvfrom_s *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ /* 'priv' might be null in some race conditions (?) */
+
+ if (pstate)
+ {
+ /* If new data is available, then complete the read action. */
+
+ if ((flags & UIP_NEWDATA) != 0)
+ {
+ /* Copy the data from the packet */
+
+ recvfrom_newudpdata(dev, pstate);
+
+ /* We are finished. */
+
+ nllvdbg("UDP done\n");
+
+ /* Don't allow any further UDP call backs. */
+
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->priv = NULL;
+ pstate->rf_cb->event = NULL;
+
+ /* Save the sender's address in the caller's 'from' location */
+
+ recvfrom_udpsender(dev, pstate);
+
+ /* Indicate that the data has been consumed */
+
+ flags &= ~UIP_NEWDATA;
+
+ /* Wake up the waiting thread, returning the number of bytes
+ * actually read.
+ */
+
+ sem_post(&pstate->rf_sem);
+ }
+
+ /* No data has been received -- this is some other event... probably a
+ * poll -- check for a timeout.
+ */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ else if (recvfrom_timeout(pstate))
+ {
+ /* Yes.. the timeout has elapsed... do not allow any further
+ * callbacks
+ */
+
+ nllvdbg("UDP timeout\n");
+
+ /* Stop further callbacks */
+
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->priv = NULL;
+ pstate->rf_cb->event = NULL;
+
+ /* Report a timeout error */
+
+ pstate->rf_result = -EAGAIN;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->rf_sem);
+ }
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+ }
+ return flags;
+}
+#endif /* CONFIG_NET_UDP */
+
+/****************************************************************************
+ * Function: recvfrom_init
+ *
+ * Description:
+ * Initialize the state structure
+ *
+ * Parameters:
+ * psock Pointer to the socket structure for the socket
+ * buf Buffer to receive data
+ * len Length of buffer
+ * pstate A pointer to the state structure to be initialized
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+static void recvfrom_init(FAR struct socket *psock, FAR void *buf, size_t len,
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *infrom,
+#else
+ FAR struct sockaddr_in *infrom,
+#endif
+ struct recvfrom_s *pstate)
+{
+ /* Initialize the state structure. */
+
+ memset(pstate, 0, sizeof(struct recvfrom_s));
+ (void)sem_init(&pstate->rf_sem, 0, 0); /* Doesn't really fail */
+ pstate->rf_buflen = len;
+ pstate->rf_buffer = buf;
+ pstate->rf_from = infrom;
+
+ /* Set up the start time for the timeout */
+
+ pstate->rf_sock = psock;
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ pstate->rf_starttime = clock_systimer();
+#endif
+}
+
+/* The only uninitialization that has to be performed is destroying the
+ * semaphore.
+ */
+
+#define recvfrom_uninit(s) sem_destroy(&(s)->rf_sem)
+
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: recvfrom_result
+ *
+ * Description:
+ * Evaluate the result of the recv operations
+ *
+ * Parameters:
+ * result The result of the uip_lockedwait operation (may indicate EINTR)
+ * pstate A pointer to the state structure to be initialized
+ *
+ * Returned Value:
+ * The result of the recv operation with errno set appropriately
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
+{
+ int save_errno = errno; /* In case something we do changes it */
+
+ /* Check for a error/timeout detected by the interrupt handler. Errors are
+ * signaled by negative errno values for the rcv length
+ */
+
+ if (pstate->rf_result < 0)
+ {
+ /* This might return EGAIN on a timeout or ENOTCONN on loss of
+ * connection (TCP only)
+ */
+
+ return pstate->rf_result;
+ }
+
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
+ */
+
+ if (result < 0)
+ {
+ return -save_errno;
+ }
+
+ return pstate->rf_recvlen;
+}
+#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Function: udp_recvfrom
+ *
+ * Description:
+ * Perform the recvfrom operation for a UDP SOCK_DGRAM
+ *
+ * Parameters:
+ * psock Pointer to the socket structure for the SOCK_DRAM socket
+ * buf Buffer to receive data
+ * len Length of buffer
+ * infrom INET ddress of source (may be NULL)
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -errno is returned (see recvfrom for list of errnos).
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_IPv6
+static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR struct sockaddr_in6 *infrom )
+#else
+static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR struct sockaddr_in *infrom )
+#endif
+{
+ struct uip_udp_conn *conn = (struct uip_udp_conn *)psock->s_conn;
+ struct recvfrom_s state;
+ uip_lock_t save;
+ int ret;
+
+ /* Perform the UDP recvfrom() operation */
+
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ save = uip_lock();
+ recvfrom_init(psock, buf, len, infrom, &state);
+
+ /* Setup the UDP remote connection */
+
+ ret = uip_udpconnect(conn, NULL);
+ if (ret < 0)
+ {
+ goto errout_with_state;
+ }
+
+ /* Set up the callback in the connection */
+
+ state.rf_cb = uip_udpcallbackalloc(conn);
+ if (state.rf_cb)
+ {
+ /* Set up the callback in the connection */
+
+ state.rf_cb->flags = UIP_NEWDATA|UIP_POLL;
+ state.rf_cb->priv = (void*)&state;
+ state.rf_cb->event = recvfrom_udpinterrupt;
+
+ /* Enable the UDP socket */
+
+ uip_udpenable(conn);
+
+ /* Wait for either the receive to complete or for an error/timeout to occur.
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
+ * interrupts are disabled! They will be re-enabled while the task sleeps
+ * and automatically re-enabled when the task restarts.
+ */
+
+ ret = uip_lockedwait(&state. rf_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ uip_udpdisable(conn);
+ uip_udpcallbackfree(conn, state.rf_cb);
+ ret = recvfrom_result(ret, &state);
+ }
+ else
+ {
+ ret = -EBUSY;
+ }
+
+errout_with_state:
+ uip_unlock(save);
+ recvfrom_uninit(&state);
+ return ret;
+}
+#endif /* CONFIG_NET_UDP */
+
+/****************************************************************************
+ * Function: tcp_recvfrom
+ *
+ * Description:
+ * Perform the recvfrom operation for a TCP/IP SOCK_STREAM
+ *
+ * Parameters:
+ * psock Pointer to the socket structure for the SOCK_DRAM socket
+ * buf Buffer to receive data
+ * len Length of buffer
+ * infrom INET ddress of source (may be NULL)
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -errno is returned (see recvfrom for list of errnos).
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+#ifdef CONFIG_NET_IPv6
+static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR struct sockaddr_in6 *infrom )
+#else
+static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR struct sockaddr_in *infrom )
+#endif
+{
+ struct recvfrom_s state;
+ uip_lock_t save;
+ int ret;
+
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ save = uip_lock();
+ recvfrom_init(psock, buf, len, infrom, &state);
+
+ /* Handle any any TCP data already buffered in a read-ahead buffer. NOTE
+ * that there may be read-ahead data to be retrieved even after the
+ * socket has been disconnected.
+ */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ recvfrom_readahead(&state);
+
+ /* The default return value is the number of bytes that we just copied into
+ * the user buffer. We will return this if the socket has become disconnected
+ * or if the user request was completely satisfied with data from the readahead
+ * buffers.
+ */
+
+ ret = state.rf_recvlen;
+
+#else
+ /* Otherwise, the default return value of zero is used (only for the case
+ * where len == state.rf_buflen is zero).
+ */
+
+ ret = 0;
+#endif
+
+ /* Verify that the SOCK_STREAM has been and still is connected */
+
+ if (!_SS_ISCONNECTED(psock->s_flags))
+ {
+ /* Was any data transferred from the readahead buffer after we were
+ * disconnected? If so, then return the number of bytes received. We
+ * will wait to return end disconnection indications the next time that
+ * recvfrom() is called.
+ *
+ * If no data was received (i.e., ret == 0 -- it will not be negative)
+ * and the connection was gracefully closed by the remote peer, then return
+ * success. If rf_recvlen is zero, the caller of recvfrom() will get an
+ * end-of-file indication.
+ */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ if (ret <= 0 && !_SS_ISCLOSED(psock->s_flags))
+#else
+ if (!_SS_ISCLOSED(psock->s_flags))
+#endif
+ {
+ /* Nothing was previously received from the readahead buffers.
+ * The SOCK_STREAM must be (re-)connected in order to receive any
+ * additional data.
+ */
+
+ ret = -ENOTCONN;
+ }
+ }
+
+ /* In general, this uIP-based implementation will not support non-blocking
+ * socket operations... except in a few cases: Here for TCP receive with read-ahead
+ * enabled. If this socket is configured as non-blocking then return EAGAIN
+ * if no data was obtained from the read-ahead buffers.
+ */
+
+ else
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ if (_SS_ISNONBLOCK(psock->s_flags))
+ {
+ /* Return the number of bytes read from the read-ahead buffer if
+ * something was received (already in 'ret'); EGAIN if not.
+ */
+
+ if (ret <= 0)
+ {
+ /* Nothing was received */
+
+ ret = -EAGAIN;
+ }
+ }
+
+ /* It is okay to block if we need to. If there is space to receive anything
+ * more, then we will wait to receive the data. Otherwise return the number
+ * of bytes read from the read-ahead buffer (already in 'ret').
+ */
+
+ else
+#endif
+ if (state.rf_buflen > 0)
+ {
+ struct uip_conn *conn = (struct uip_conn *)psock->s_conn;
+
+ /* Set up the callback in the connection */
+
+ state.rf_cb = uip_tcpcallbackalloc(conn);
+ if (state.rf_cb)
+ {
+ state.rf_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.rf_cb->priv = (void*)&state;
+ state.rf_cb->event = recvfrom_tcpinterrupt;
+
+ /* Wait for either the receive to complete or for an error/timeout to occur.
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
+ * interrupts may be disabled! They will be re-enabled while the task sleeps
+ * and automatically re-enabled when the task restarts.
+ */
+
+ ret = uip_lockedwait(&state.rf_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ uip_tcpcallbackfree(conn, state.rf_cb);
+ ret = recvfrom_result(ret, &state);
+ }
+ else
+ {
+ ret = -EBUSY;
+ }
+ }
+
+ uip_unlock(save);
+ recvfrom_uninit(&state);
+ return (ssize_t)ret;
+}
+#endif /* CONFIG_NET_TCP */
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_recvfrom
+ *
+ * Description:
+ * recvfrom() receives messages from a socket, and may be used to receive
+ * data on a socket whether or not it is connection-oriented.
+ *
+ * If from is not NULL, and the underlying protocol provides the source
+ * address, this source address is filled in. The argument fromlen
+ * initialized to the size of the buffer associated with from, and modified
+ * on return to indicate the actual size of the address stored there.
+ *
+ * Parameters:
+ * psock A pointer to a NuttX-specific, internal socket structure
+ * buf Buffer to receive data
+ * len Length of buffer
+ * flags Receive flags
+ * from Address of source (may be NULL)
+ * fromlen The length of the address structure
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. If no data is
+ * available to be received and the peer has performed an orderly shutdown,
+ * recv() will return 0. Othwerwise, on errors, -1 is returned, and errno
+ * is set appropriately:
+ *
+ * EAGAIN
+ * The socket is marked non-blocking and the receive operation would block,
+ * or a receive timeout had been set and the timeout expired before data
+ * was received.
+ * EBADF
+ * The argument sockfd is an invalid descriptor.
+ * ECONNREFUSED
+ * A remote host refused to allow the network connection (typically because
+ * it is not running the requested service).
+ * EFAULT
+ * The receive buffer pointer(s) point outside the process's address space.
+ * EINTR
+ * The receive was interrupted by delivery of a signal before any data were
+ * available.
+ * EINVAL
+ * Invalid argument passed.
+ * ENOMEM
+ * Could not allocate memory.
+ * ENOTCONN
+ * The socket is associated with a connection-oriented protocol and has
+ * not been connected.
+ * ENOTSOCK
+ * The argument sockfd does not refer to a socket.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ int flags,FAR struct sockaddr *from,
+ FAR socklen_t *fromlen)
+{
+#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_TCP)
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *infrom = (struct sockaddr_in6 *)from;
+#else
+ FAR struct sockaddr_in *infrom = (struct sockaddr_in *)from;
+#endif
+#endif
+
+ ssize_t ret;
+ int err;
+
+ /* Verify that non-NULL pointers were passed */
+
+#ifdef CONFIG_DEBUG
+ if (!buf)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+#endif
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* If a 'from' address has been provided, verify that it is large
+ * enough to hold this address family.
+ */
+
+ if (from)
+ {
+#ifdef CONFIG_NET_IPv6
+ if (*fromlen < sizeof(struct sockaddr_in6))
+#else
+ if (*fromlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EINVAL;
+ goto errout;
+ }
+ }
+
+ /* Set the socket state to receiving */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_RECV);
+
+ /* Perform the TCP/IP or UDP recv() operation */
+
+#if defined(CONFIG_NET_UDP) && defined(CONFIG_NET_TCP)
+ if (psock->s_type == SOCK_STREAM)
+ {
+ ret = tcp_recvfrom(psock, buf, len, infrom);
+ }
+ else
+ {
+ ret = udp_recvfrom(psock, buf, len, infrom);
+ }
+#elif defined(CONFIG_NET_TCP)
+ ret = tcp_recvfrom(psock, buf, len, infrom);
+#elif defined(CONFIG_NET_UDP)
+ ret = udp_recvfrom(psock, buf, len, infrom);
+#else
+ ret = -ENOSYS;
+#endif
+
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+
+ /* Handle returned errors */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ /* Success return */
+
+ return ret;
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: recvfrom
+ *
+ * Description:
+ * recvfrom() receives messages from a socket, and may be used to receive
+ * data on a socket whether or not it is connection-oriented.
+ *
+ * If from is not NULL, and the underlying protocol provides the source
+ * address, this source address is filled in. The argument fromlen
+ * initialized to the size of the buffer associated with from, and modified
+ * on return to indicate the actual size of the address stored there.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * buf Buffer to receive data
+ * len Length of buffer
+ * flags Receive flags
+ * from Address of source (may be NULL)
+ * fromlen The length of the address structure
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -1 is returned, and errno is set appropriately:
+ *
+ * EAGAIN
+ * The socket is marked non-blocking and the receive operation would block,
+ * or a receive timeout had been set and the timeout expired before data
+ * was received.
+ * EBADF
+ * The argument sockfd is an invalid descriptor.
+ * ECONNREFUSED
+ * A remote host refused to allow the network connection (typically because
+ * it is not running the requested service).
+ * EFAULT
+ * The receive buffer pointer(s) point outside the process's address space.
+ * EINTR
+ * The receive was interrupted by delivery of a signal before any data were
+ * available.
+ * EINVAL
+ * Invalid argument passed.
+ * ENOMEM
+ * Could not allocate memory.
+ * ENOTCONN
+ * The socket is associated with a connection-oriented protocol and has
+ * not been connected.
+ * ENOTSOCK
+ * The argument sockfd does not refer to a socket.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t recvfrom(int sockfd, FAR void *buf, size_t len, int flags,
+ FAR struct sockaddr *from, FAR socklen_t *fromlen)
+{
+ FAR struct socket *psock;
+
+ /* Get the underlying socket structure */
+
+ psock = sockfd_socket(sockfd);
+
+ /* Then let psock_recvfrom() do all of the work */
+
+ return psock_recvfrom(psock, buf, len, flags, from, fromlen);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
new file mode 100644
index 000000000..950b3fc0b
--- /dev/null
+++ b/nuttx/net/send.c
@@ -0,0 +1,596 @@
+/****************************************************************************
+ * net/send.c
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <stdint.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/clock.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#ifdef CONFIG_NET_ARP_IPIN
+# include <nuttx/net/uip/uip-arp.h>
+#endif
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define TCPBUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure holds the state of the send operation until it can be
+ * operated upon from the interrupt level.
+ */
+
+struct send_s
+{
+ FAR struct socket *snd_sock; /* Points to the parent socket structure */
+ FAR struct uip_callback_s *snd_cb; /* Reference to callback instance */
+ sem_t snd_sem; /* Used to wake up the waiting thread */
+ FAR const uint8_t *snd_buffer; /* Points to the buffer of data to send */
+ size_t snd_buflen; /* Number of bytes in the buffer to send */
+ ssize_t snd_sent; /* The number of bytes sent */
+ uint32_t snd_isn; /* Initial sequence number */
+ uint32_t snd_acked; /* The number of bytes acked */
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ uint32_t snd_time; /* last send time for determining timeout */
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: send_timeout
+ *
+ * Description:
+ * Check for send timeout.
+ *
+ * Parameters:
+ * pstate send state structure
+ *
+ * Returned Value:
+ * TRUE:timeout FALSE:no timeout
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+static inline int send_timeout(struct send_s *pstate)
+{
+ FAR struct socket *psock = 0;
+
+ /* Check for a timeout configured via setsockopts(SO_SNDTIMEO).
+ * If none... we well let the send wait forever.
+ */
+
+ psock = pstate->snd_sock;
+ if (psock && psock->s_sndtimeo != 0)
+ {
+ /* Check if the configured timeout has elapsed */
+
+ return net_timeo(pstate->snd_time, psock->s_sndtimeo);
+ }
+
+ /* No timeout */
+
+ return FALSE;
+}
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+
+/****************************************************************************
+ * Function: send_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * send operation when polled by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvpriv, uint16_t flags)
+{
+ struct uip_conn *conn = (struct uip_conn*)pvconn;
+ struct send_s *pstate = (struct send_s *)pvpriv;
+
+ nllvdbg("flags: %04x acked: %d sent: %d\n",
+ flags, pstate->snd_acked, pstate->snd_sent);
+
+ /* If this packet contains an acknowledgement, then update the count of
+ * acknowldged bytes.
+ */
+
+ if ((flags & UIP_ACKDATA) != 0)
+ {
+ /* The current acknowledgement number number is the (relative) offset
+ * of the of the next byte needed by the receiver. The snd_isn is the
+ * offset of the first byte to send to the receiver. The difference
+ * is the number of bytes to be acknowledged.
+ */
+
+ pstate->snd_acked = uip_tcpgetsequence(TCPBUF->ackno) - pstate->snd_isn;
+ nllvdbg("ACK: acked=%d sent=%d buflen=%d\n",
+ pstate->snd_acked, pstate->snd_sent, pstate->snd_buflen);
+
+ /* Have all of the bytes in the buffer been sent and acknowledged? */
+
+ if (pstate->snd_acked >= pstate->snd_buflen)
+ {
+ /* Yes. Then pstate->snd_buflen should hold the number of bytes
+ * actually sent.
+ */
+
+ goto end_wait;
+ }
+
+ /* No.. fall through to send more data if necessary */
+ }
+
+ /* Check if we are being asked to retransmit data */
+
+ else if ((flags & UIP_REXMIT) != 0)
+ {
+ /* Yes.. in this case, reset the number of bytes that have been sent
+ * to the number of bytes that have been ACKed.
+ */
+
+ pstate->snd_sent = pstate->snd_acked;
+
+ /* Fall through to re-send data from the last that was ACKed */
+ }
+
+ /* Check for a loss of connection */
+
+ else if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ /* Report not connected */
+
+ nllvdbg("Lost connection\n");
+ pstate->snd_sent = -ENOTCONN;
+ goto end_wait;
+ }
+
+ /* Check if the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread).
+ */
+
+#if 0 /* We can't really support multiple senders on the same TCP socket */
+ else if (dev->d_sndlen > 0)
+ {
+ /* Another thread has beat us sending data, wait for the next poll */
+
+ return flags;
+ }
+#endif
+
+ /* We get here if (1) not all of the data has been ACKed, (2) we have been
+ * asked to retransmit data, (3) the connection is still healthy, and (4)
+ * the outgoing packet is available for our use. In this case, we are
+ * now free to send more data to receiver -- UNLESS the buffer contains
+ * unprocessing incoming data. In that event, we will have to wait for the
+ * next polling cycle.
+ */
+
+ if ((flags & UIP_NEWDATA) == 0 && pstate->snd_sent < pstate->snd_buflen)
+ {
+ uint32_t seqno;
+
+ /* Get the amount of data that we can send in the next packet */
+
+ uint32_t sndlen = pstate->snd_buflen - pstate->snd_sent;
+ if (sndlen > uip_mss(conn))
+ {
+ sndlen = uip_mss(conn);
+ }
+
+ /* Set the sequence number for this packet. NOTE: uIP updates
+ * sndseq on recept of ACK *before* this function is called. In that
+ * case sndseq will point to the next unacknowledge byte (which might
+ * have already been sent). We will overwrite the value of sndseq
+ * here before the packet is sent.
+ */
+
+ seqno = pstate->snd_sent + pstate->snd_isn;
+ nllvdbg("SEND: sndseq %08x->%08x\n", conn->sndseq, seqno);
+ uip_tcpsetsequence(conn->sndseq, seqno);
+
+ /* Then set-up to send that amount of data. (this won't actually
+ * happen until the polling cycle completes).
+ */
+
+ uip_send(dev, &pstate->snd_buffer[pstate->snd_sent], sndlen);
+
+ /* Check if the destination IP address is in the ARP table. If not,
+ * then the send won't actually make it out... it will be replaced with
+ * an ARP request.
+ *
+ * NOTE 1: This could an expensive check if there are a lot of entries
+ * in the ARP table. Hence, we only check on the first packet -- when
+ * snd_sent is zero.
+ *
+ * NOTE 2: If we are actually harvesting IP addresses on incomming IP
+ * packets, then this check should not be necessary; the MAC mapping
+ * should already be in the ARP table.
+ */
+
+#if defined(CONFIG_NET_ETHERNET) && defined (CONFIG_NET_ARP_IPIN)
+ if (pstate->snd_sent != 0 || uip_arp_find(conn->ripaddr) != NULL)
+#endif
+ {
+ /* Update the amount of data sent (but not necessarily ACKed) */
+
+ pstate->snd_sent += sndlen;
+ nllvdbg("SEND: acked=%d sent=%d buflen=%d\n",
+ pstate->snd_acked, pstate->snd_sent, pstate->snd_buflen);
+
+ /* Update the send time */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ pstate->snd_time = clock_systimer();
+#endif
+ }
+ }
+
+ /* All data has been send and we are just waiting for ACK or re-transmit
+ * indications to complete the send. Check for a timeout.
+ */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ else if (send_timeout(pstate))
+ {
+ /* Yes.. report the timeout */
+
+ nlldbg("SEND timeout\n");
+ pstate->snd_sent = -ETIMEDOUT;
+ goto end_wait;
+ }
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+
+ /* Continue waiting */
+
+ return flags;
+
+end_wait:
+ /* Do not allow any further callbacks */
+
+ pstate->snd_cb->flags = 0;
+ pstate->snd_cb->priv = NULL;
+ pstate->snd_cb->event = NULL;
+
+ /* There are no outstanding, unacknowledged bytes */
+
+ conn->unacked = 0;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->snd_sem);
+ return flags;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_send
+ *
+ * Description:
+ * The send() call may be used only when the socket is in a connected state
+ * (so that the intended recipient is known). The only difference between
+ * send() and write() is the presence of flags. With zero flags parameter,
+ * send() is equivalent to write(). Also, send(sockfd,buf,len,flags) is
+ * equivalent to sendto(sockfd,buf,len,flags,NULL,0).
+ *
+ * Parameters:
+ * psock And instance of the internal socket structure.
+ * buf Data to send
+ * len Length of data to send
+ * flags Send flags
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -1 is returned, and errno is set appropriately:
+ *
+ * EAGAIN or EWOULDBLOCK
+ * The socket is marked non-blocking and the requested operation
+ * would block.
+ * EBADF
+ * An invalid descriptor was specified.
+ * ECONNRESET
+ * Connection reset by peer.
+ * EDESTADDRREQ
+ * The socket is not connection-mode, and no peer address is set.
+ * EFAULT
+ * An invalid user space address was specified for a parameter.
+ * EINTR
+ * A signal occurred before any data was transmitted.
+ * EINVAL
+ * Invalid argument passed.
+ * EISCONN
+ * The connection-mode socket was connected already but a recipient
+ * was specified. (Now either this error is returned, or the recipient
+ * specification is ignored.)
+ * EMSGSIZE
+ * The socket type requires that message be sent atomically, and the
+ * size of the message to be sent made this impossible.
+ * ENOBUFS
+ * The output queue for a network interface was full. This generally
+ * indicates that the interface has stopped sending, but may be
+ * caused by transient congestion.
+ * ENOMEM
+ * No memory available.
+ * ENOTCONN
+ * The socket is not connected, and no target has been given.
+ * ENOTSOCK
+ * The argument s is not a socket.
+ * EOPNOTSUPP
+ * Some bit in the flags argument is inappropriate for the socket
+ * type.
+ * EPIPE
+ * The local end has been shut down on a connection oriented socket.
+ * In this case the process will also receive a SIGPIPE unless
+ * MSG_NOSIGNAL is set.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t psock_send(FAR struct socket *psock, const void *buf, size_t len, int flags)
+{
+ struct send_s state;
+ uip_lock_t save;
+ int err;
+ int ret = OK;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* If this is an un-connected socket, then return ENOTCONN */
+
+ if (psock->s_type != SOCK_STREAM || !_SS_ISCONNECTED(psock->s_flags))
+ {
+ err = ENOTCONN;
+ goto errout;
+ }
+
+ /* Set the socket state to sending */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
+
+ /* Perform the TCP send operation */
+
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ save = uip_lock();
+ memset(&state, 0, sizeof(struct send_s));
+ (void)sem_init(&state. snd_sem, 0, 0); /* Doesn't really fail */
+ state.snd_sock = psock; /* Socket descriptor to use */
+ state.snd_buflen = len; /* Number of bytes to send */
+ state.snd_buffer = buf; /* Buffer to send from */
+
+ if (len > 0)
+ {
+ struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
+
+ /* Allocate resources to receive a callback */
+
+ state.snd_cb = uip_tcpcallbackalloc(conn);
+ if (state.snd_cb)
+ {
+ /* Get the initial sequence number that will be used */
+
+ state.snd_isn = uip_tcpgetsequence(conn->sndseq);
+
+ /* There is no outstanding, unacknowledged data after this
+ * initial sequence number.
+ */
+
+ conn->unacked = 0;
+
+ /* Update the initial time for calculating timeouts */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ state.snd_time = clock_systimer();
+#endif
+ /* Set up the callback in the connection */
+
+ state.snd_cb->flags = UIP_ACKDATA|UIP_REXMIT|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.snd_cb->priv = (void*)&state;
+ state.snd_cb->event = send_interrupt;
+
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&conn->ripaddr);
+
+ /* Wait for the send to complete or an error to occur: NOTES: (1)
+ * uip_lockedwait will also terminate if a signal is received, (2) interrupts
+ * may be disabled! They will be re-enabled while the task sleeps and
+ * automatically re-enabled when the task restarts.
+ */
+
+ ret = uip_lockedwait(&state. snd_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ uip_tcpcallbackfree(conn, state.snd_cb);
+ }
+ }
+
+ sem_destroy(&state. snd_sem);
+ uip_unlock(save);
+
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+
+ /* Check for a errors. Errors are signaled by negative errno values
+ * for the send length
+ */
+
+ if (state.snd_sent < 0)
+ {
+ err = state.snd_sent;
+ goto errout;
+ }
+
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
+ */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ /* Return the number of bytes actually sent */
+
+ return state.snd_sent;
+
+errout:
+ *get_errno_ptr() = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: send
+ *
+ * Description:
+ * The send() call may be used only when the socket is in a connected state
+ * (so that the intended recipient is known). The only difference between
+ * send() and write() is the presence of flags. With zero flags parameter,
+ * send() is equivalent to write(). Also, send(sockfd,buf,len,flags) is
+ * equivalent to sendto(sockfd,buf,len,flags,NULL,0).
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * buf Data to send
+ * len Length of data to send
+ * flags Send flags
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -1 is returned, and errno is set appropriately:
+ *
+ * EAGAIN or EWOULDBLOCK
+ * The socket is marked non-blocking and the requested operation
+ * would block.
+ * EBADF
+ * An invalid descriptor was specified.
+ * ECONNRESET
+ * Connection reset by peer.
+ * EDESTADDRREQ
+ * The socket is not connection-mode, and no peer address is set.
+ * EFAULT
+ * An invalid user space address was specified for a parameter.
+ * EINTR
+ * A signal occurred before any data was transmitted.
+ * EINVAL
+ * Invalid argument passed.
+ * EISCONN
+ * The connection-mode socket was connected already but a recipient
+ * was specified. (Now either this error is returned, or the recipient
+ * specification is ignored.)
+ * EMSGSIZE
+ * The socket type requires that message be sent atomically, and the
+ * size of the message to be sent made this impossible.
+ * ENOBUFS
+ * The output queue for a network interface was full. This generally
+ * indicates that the interface has stopped sending, but may be
+ * caused by transient congestion.
+ * ENOMEM
+ * No memory available.
+ * ENOTCONN
+ * The socket is not connected, and no target has been given.
+ * ENOTSOCK
+ * The argument s is not a socket.
+ * EOPNOTSUPP
+ * Some bit in the flags argument is inappropriate for the socket
+ * type.
+ * EPIPE
+ * The local end has been shut down on a connection oriented socket.
+ * In this case the process will also receive a SIGPIPE unless
+ * MSG_NOSIGNAL is set.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t send(int sockfd, const void *buf, size_t len, int flags)
+{
+ return psock_send(sockfd_socket(sockfd), buf, len, flags);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
new file mode 100644
index 000000000..320eacc19
--- /dev/null
+++ b/nuttx/net/sendto.c
@@ -0,0 +1,440 @@
+/****************************************************************************
+ * net/sendto.c
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <stdint.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+#include <arch/irq.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "net_internal.h"
+#include "uip/uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct sendto_s
+{
+ FAR struct uip_callback_s *st_cb; /* Reference to callback instance */
+ sem_t st_sem; /* Semaphore signals sendto completion */
+ uint16_t st_buflen; /* Length of send buffer (error if <0) */
+ const char *st_buffer; /* Pointer to send buffer */
+ int st_sndlen; /* Result of the send (length sent or negated errno) */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: sendto_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * send operation when polled by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn An instance of the UDP connection structure cast to void *
+ * pvpriv An instance of struct sendto_s cast to void*
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * Modified value of the input flags
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+static uint16_t sendto_interrupt(struct uip_driver_s *dev, void *conn,
+ void *pvpriv, uint16_t flags)
+{
+ struct sendto_s *pstate = (struct sendto_s *)pvpriv;
+
+ nllvdbg("flags: %04x\n", flags);
+ if (pstate)
+ {
+ /* Check if the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread -OR- if the output
+ * buffer currently contains unprocessed incoming data. In these cases
+ * we will just have to wait for the next polling cycle.
+ */
+
+ if (dev->d_sndlen > 0 || (flags & UIP_NEWDATA) != 0)
+ {
+ /* Another thread has beat us sending data or the buffer is busy,
+ * wait for the next polling cycle
+ */
+
+ return flags;
+ }
+
+ /* It looks like we are good to send the data */
+
+ else
+ {
+ /* Copy the user data into d_snddata and send it */
+
+ uip_send(dev, pstate->st_buffer, pstate->st_buflen);
+ pstate->st_sndlen = pstate->st_buflen;
+ }
+
+ /* Don't allow any further call backs. */
+
+ pstate->st_cb->flags = 0;
+ pstate->st_cb->priv = NULL;
+ pstate->st_cb->event = NULL;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->st_sem);
+ }
+
+ return flags;
+}
+#endif
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_sendto
+ *
+ * Description:
+ * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
+ * socket, the parameters to and 'tolen' are ignored (and the error EISCONN
+ * may be returned when they are not NULL and 0), and the error ENOTCONN is
+ * returned when the socket was not actually connected.
+ *
+ * Parameters:
+ * psock A pointer to a NuttX-specific, internal socket structure
+ * buf Data to send
+ * len Length of data to send
+ * flags Send flags
+ * to Address of recipient
+ * tolen The length of the address structure
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -1 is returned, and errno is set appropriately:
+ *
+ * EAGAIN or EWOULDBLOCK
+ * The socket is marked non-blocking and the requested operation
+ * would block.
+ * EBADF
+ * An invalid descriptor was specified.
+ * ECONNRESET
+ * Connection reset by peer.
+ * EDESTADDRREQ
+ * The socket is not connection-mode, and no peer address is set.
+ * EFAULT
+ * An invalid user space address was specified for a parameter.
+ * EINTR
+ * A signal occurred before any data was transmitted.
+ * EINVAL
+ * Invalid argument passed.
+ * EISCONN
+ * The connection-mode socket was connected already but a recipient
+ * was specified. (Now either this error is returned, or the recipient
+ * specification is ignored.)
+ * EMSGSIZE
+ * The socket type requires that message be sent atomically, and the
+ * size of the message to be sent made this impossible.
+ * ENOBUFS
+ * The output queue for a network interface was full. This generally
+ * indicates that the interface has stopped sending, but may be
+ * caused by transient congestion.
+ * ENOMEM
+ * No memory available.
+ * ENOTCONN
+ * The socket is not connected, and no target has been given.
+ * ENOTSOCK
+ * The argument s is not a socket.
+ * EOPNOTSUPP
+ * Some bit in the flags argument is inappropriate for the socket
+ * type.
+ * EPIPE
+ * The local end has been shut down on a connection oriented socket.
+ * In this case the process will also receive a SIGPIPE unless
+ * MSG_NOSIGNAL is set.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
+ size_t len, int flags, FAR const struct sockaddr *to,
+ socklen_t tolen)
+{
+#ifdef CONFIG_NET_UDP
+ FAR struct uip_udp_conn *conn;
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *into = (const struct sockaddr_in6 *)to;
+#else
+ FAR const struct sockaddr_in *into = (const struct sockaddr_in *)to;
+#endif
+ struct sendto_s state;
+ uip_lock_t save;
+ int ret;
+#endif
+ int err;
+
+ /* If to is NULL or tolen is zero, then this function is same as send (for
+ * connected socket types)
+ */
+
+ if (!to || !tolen)
+ {
+#ifdef CONFIG_NET_TCP
+ return psock_send(psock, buf, len, flags);
+#else
+ err = EINVAL;
+ goto errout;
+#endif
+ }
+
+ /* Verify that a valid address has been provided */
+
+#ifdef CONFIG_NET_IPv6
+ if (to->sa_family != AF_INET6 || tolen < sizeof(struct sockaddr_in6))
+#else
+ if (to->sa_family != AF_INET || tolen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Verify that the psock corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* If this is a connected socket, then return EISCONN */
+
+ if (psock->s_type != SOCK_DGRAM)
+ {
+ err = EISCONN;
+ goto errout;
+ }
+
+ /* Perform the UDP sendto operation */
+
+#ifdef CONFIG_NET_UDP
+ /* Set the socket state to sending */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_SEND);
+
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ save = uip_lock();
+ memset(&state, 0, sizeof(struct sendto_s));
+ sem_init(&state.st_sem, 0, 0);
+ state.st_buflen = len;
+ state.st_buffer = buf;
+
+ /* Setup the UDP socket */
+
+ conn = (struct uip_udp_conn *)psock->s_conn;
+ ret = uip_udpconnect(conn, into);
+ if (ret < 0)
+ {
+ uip_unlock(save);
+ err = -ret;
+ goto errout;
+ }
+
+ /* Set up the callback in the connection */
+
+ state.st_cb = uip_udpcallbackalloc(conn);
+ if (state.st_cb)
+ {
+ state.st_cb->flags = UIP_POLL;
+ state.st_cb->priv = (void*)&state;
+ state.st_cb->event = sendto_interrupt;
+
+ /* Enable the UDP socket */
+
+ uip_udpenable(conn);
+
+ /* Notify the device driver of the availabilty of TX data */
+
+ netdev_txnotify(&conn->ripaddr);
+
+ /* Wait for either the receive to complete or for an error/timeout to occur.
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
+ * interrupts may be disabled! They will be re-enabled while the task sleeps
+ * and automatically re-enabled when the task restarts.
+ */
+
+ uip_lockedwait(&state.st_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ uip_udpdisable(conn);
+ uip_udpcallbackfree(conn, state.st_cb);
+ }
+ uip_unlock(save);
+
+ sem_destroy(&state.st_sem);
+
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+
+ /* Check for errors */
+
+ if (state.st_sndlen < 0)
+ {
+ err = -state.st_sndlen;
+ goto errout;
+ }
+
+ /* Sucess */
+
+ return state.st_sndlen;
+#else
+ err = ENOSYS;
+#endif
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: sendto
+ *
+ * Description:
+ * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET)
+ * socket, the parameters to and 'tolen' are ignored (and the error EISCONN
+ * may be returned when they are not NULL and 0), and the error ENOTCONN is
+ * returned when the socket was not actually connected.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * buf Data to send
+ * len Length of data to send
+ * flags Send flags
+ * to Address of recipient
+ * tolen The length of the address structure
+ *
+ * Returned Value:
+ * On success, returns the number of characters sent. On error,
+ * -1 is returned, and errno is set appropriately:
+ *
+ * EAGAIN or EWOULDBLOCK
+ * The socket is marked non-blocking and the requested operation
+ * would block.
+ * EBADF
+ * An invalid descriptor was specified.
+ * ECONNRESET
+ * Connection reset by peer.
+ * EDESTADDRREQ
+ * The socket is not connection-mode, and no peer address is set.
+ * EFAULT
+ * An invalid user space address was specified for a parameter.
+ * EINTR
+ * A signal occurred before any data was transmitted.
+ * EINVAL
+ * Invalid argument passed.
+ * EISCONN
+ * The connection-mode socket was connected already but a recipient
+ * was specified. (Now either this error is returned, or the recipient
+ * specification is ignored.)
+ * EMSGSIZE
+ * The socket type requires that message be sent atomically, and the
+ * size of the message to be sent made this impossible.
+ * ENOBUFS
+ * The output queue for a network interface was full. This generally
+ * indicates that the interface has stopped sending, but may be
+ * caused by transient congestion.
+ * ENOMEM
+ * No memory available.
+ * ENOTCONN
+ * The socket is not connected, and no target has been given.
+ * ENOTSOCK
+ * The argument s is not a socket.
+ * EOPNOTSUPP
+ * Some bit in the flags argument is inappropriate for the socket
+ * type.
+ * EPIPE
+ * The local end has been shut down on a connection oriented socket.
+ * In this case the process will also receive a SIGPIPE unless
+ * MSG_NOSIGNAL is set.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+ssize_t sendto(int sockfd, FAR const void *buf, size_t len, int flags,
+ FAR const struct sockaddr *to, socklen_t tolen)
+{
+ FAR struct socket *psock;
+
+ /* Get the underlying socket structure */
+
+ psock = sockfd_socket(sockfd);
+
+ /* And let psock_sendto do all of the work */
+
+ return psock_sendto(psock, buf, len, flags, to, tolen);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/setsockopt.c b/nuttx/net/setsockopt.c
new file mode 100644
index 000000000..ad52ff53d
--- /dev/null
+++ b/nuttx/net/setsockopt.c
@@ -0,0 +1,304 @@
+/****************************************************************************
+ * net/setsockopt.c
+ *
+ * Copyright (C) 2007, 2008, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+#include <arch/irq.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_setsockopt
+ *
+ * Description:
+ * psock_setsockopt() sets the option specified by the 'option' argument,
+ * at the protocol level specified by the 'level' argument, to the value
+ * pointed to by the 'value' argument for the socket on the 'psock' argument.
+ *
+ * The 'level' argument specifies the protocol level of the option. To set
+ * options at the socket level, specify the level argument as SOL_SOCKET.
+ *
+ * See <sys/socket.h> a complete list of values for the 'option' argument.
+ *
+ * Parameters:
+ * psock Socket structure of socket to operate on
+ * level Protocol level to set the option
+ * option identifies the option to set
+ * value Points to the argument value
+ * value_len The length of the argument value
+ *
+ * Returned Value:
+ * 0 on success; -1 on failure
+ *
+ * EDOM
+ * The send and receive timeout values are too big to fit into the
+ * timeout fields in the socket structure.
+ * EINVAL
+ * The specified option is invalid at the specified socket 'level' or the
+ * socket has been shut down.
+ * EISCONN
+ * The socket is already connected, and a specified option cannot be set
+ * while the socket is connected.
+ * ENOPROTOOPT
+ * The 'option' is not supported by the protocol.
+ * ENOTSOCK
+ * The 'sockfd' argument does not refer to a socket.
+ * ENOMEM
+ * There was insufficient memory available for the operation to complete.
+ * ENOBUFS
+ * Insufficient resources are available in the system to complete the
+ * call.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_setsockopt(FAR struct socket *psock, int level, int option,
+ FAR const void *value, socklen_t value_len)
+{
+ uip_lock_t flags;
+ int err;
+
+ /* Verify that the socket option if valid (but might not be supported ) */
+
+ if (!_SO_SETVALID(option) || !value)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Process the option */
+ switch (option)
+ {
+ /* The following options take a point to an integer boolean value.
+ * We will blindly set the bit here although the implementation
+ * is outside of the scope of setsockopt.
+ */
+
+ case SO_DEBUG: /* Enables recording of debugging information */
+ case SO_BROADCAST: /* Permits sending of broadcast messages */
+ case SO_REUSEADDR: /* Allow reuse of local addresses */
+ case SO_KEEPALIVE: /* Keeps connections active by enabling the
+ * periodic transmission */
+ case SO_OOBINLINE: /* Leaves received out-of-band data inline */
+ case SO_DONTROUTE: /* Requests outgoing messages bypass standard routing */
+ {
+ int setting;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (value_len != sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the value. Is the option being set or cleared? */
+
+ setting = *(int*)value;
+
+ /* Disable interrupts so that there is no conflict with interrupt
+ * level access to options.
+ */
+
+ flags = uip_lock();
+
+ /* Set or clear the option bit */
+
+ if (setting)
+ {
+ _SO_SETOPT(psock->s_options, option);
+ }
+ else
+ {
+ _SO_CLROPT(psock->s_options, option);
+ }
+ uip_unlock(flags);
+ }
+ break;
+
+ /* The following are valid only if the OS CLOCK feature is enabled */
+
+ case SO_RCVTIMEO:
+ case SO_SNDTIMEO:
+#ifndef CONFIG_DISABLE_CLOCK
+ {
+ socktimeo_t timeo;
+
+ /* Verify that option is the size of an 'struct timeval'. */
+
+ if (value_len != sizeof(struct timeval))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the timeout value */
+
+ timeo = net_timeval2dsec((struct timeval *)value);
+
+ /* Save the timeout value */
+
+ if (option == SO_RCVTIMEO)
+ {
+ psock->s_rcvtimeo = timeo;
+ }
+ else
+ {
+ psock->s_sndtimeo = timeo;
+ }
+
+ /* Set/clear the corresponding enable/disable bit */
+
+ if (timeo)
+ {
+ _SO_CLROPT(psock->s_options, option);
+ }
+ else
+ {
+ _SO_SETOPT(psock->s_options, option);
+ }
+ }
+ break;
+#endif
+
+ /* The following are not yet implemented */
+
+ case SO_LINGER:
+ case SO_SNDBUF: /* Sets send buffer size */
+ case SO_RCVBUF: /* Sets receive buffer size */
+ case SO_RCVLOWAT: /* Sets the minimum number of bytes to input */
+ case SO_SNDLOWAT: /* Sets the minimum number of bytes to output */
+
+ /* There options are only valid when used with getopt */
+
+ case SO_ACCEPTCONN: /* Reports whether socket listening is enabled */
+ case SO_ERROR: /* Reports and clears error status. */
+ case SO_TYPE: /* Reports the socket type */
+
+ default:
+ err = ENOPROTOOPT;
+ goto errout;
+ }
+ return OK;
+
+errout:
+ set_errno(err);
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: setsockopt
+ *
+ * Description:
+ * setsockopt() sets the option specified by the 'option' argument,
+ * at the protocol level specified by the 'level' argument, to the value
+ * pointed to by the 'value' argument for the socket associated with the
+ * file descriptor specified by the 'sockfd' argument.
+ *
+ * The 'level' argument specifies the protocol level of the option. To set
+ * options at the socket level, specify the level argument as SOL_SOCKET.
+ *
+ * See <sys/socket.h> a complete list of values for the 'option' argument.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket
+ * level Protocol level to set the option
+ * option identifies the option to set
+ * value Points to the argument value
+ * value_len The length of the argument value
+ *
+ * Returned Value:
+ * 0 on success; -1 on failure
+ *
+ * EBADF
+ * The 'sockfd' argument is not a valid socket descriptor.
+ * EDOM
+ * The send and receive timeout values are too big to fit into the
+ * timeout fields in the socket structure.
+ * EINVAL
+ * The specified option is invalid at the specified socket 'level' or the
+ * socket has been shut down.
+ * EISCONN
+ * The socket is already connected, and a specified option cannot be set
+ * while the socket is connected.
+ * ENOPROTOOPT
+ * The 'option' is not supported by the protocol.
+ * ENOTSOCK
+ * The 'sockfd' argument does not refer to a socket.
+ * ENOMEM
+ * There was insufficient memory available for the operation to complete.
+ * ENOBUFS
+ * Insufficient resources are available in the system to complete the
+ * call.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int setsockopt(int sockfd, int level, int option, const void *value, socklen_t value_len)
+{
+ FAR struct socket *psock;
+
+ /* Get the underlying socket structure */
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ set_errno(EBADF);
+ return ERROR;
+ }
+
+ /* Then let psock_setockopt() do all of the work */
+
+ return psock_setsockopt(psock, level, option, value, value_len);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS */
diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c
new file mode 100644
index 000000000..a6befc5d7
--- /dev/null
+++ b/nuttx/net/socket.c
@@ -0,0 +1,286 @@
+/****************************************************************************
+ * net/socket.c
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <sys/socket.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: psock_socket
+ *
+ * Description:
+ * socket() creates an endpoint for communication and returns a socket
+ * structure.
+ *
+ * Parameters:
+ * domain (see sys/socket.h)
+ * type (see sys/socket.h)
+ * protocol (see sys/socket.h)
+ * psock A pointer to a user allocated socket structure to be initialized.
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES
+ * Permission to create a socket of the specified type and/or protocol
+ * is denied.
+ * EAFNOSUPPORT
+ * The implementation does not support the specified address family.
+ * EINVAL
+ * Unknown protocol, or protocol family not available.
+ * EMFILE
+ * Process file table overflow.
+ * ENFILE
+ * The system limit on the total number of open files has been reached.
+ * ENOBUFS or ENOMEM
+ * Insufficient memory is available. The socket cannot be created until
+ * sufficient resources are freed.
+ * EPROTONOSUPPORT
+ * The protocol type or the specified protocol is not supported within
+ * this domain.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
+{
+ int err = ENFILE;
+
+ /* Only PF_INET or PF_INET6 domains supported */
+
+#ifdef CONFIG_NET_IPv6
+ if ( domain != PF_INET6)
+#else
+ if ( domain != PF_INET)
+#endif
+ {
+ err = EAFNOSUPPORT;
+ goto errout;
+ }
+
+ /* Only SOCK_STREAM and possible SOCK_DRAM are supported */
+
+#if defined(CONFIG_NET_TCP) && defined(CONFIG_NET_UDP)
+ if ((type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
+ (type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
+ (type != SOCK_STREAM && type != SOCK_DGRAM))
+#elif defined(CONFIG_NET_TCP)
+ if ((type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
+ (type != SOCK_STREAM))
+#elif defined(CONFIG_NET_UDP)
+ if ((type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
+ (type != SOCK_DGRAM))
+#endif
+ {
+ err = EPROTONOSUPPORT;
+ goto errout;
+ }
+
+ /* Everything looks good. Initialize the socket structure */
+ /* Save the protocol type */
+
+ psock->s_type = type;
+ psock->s_conn = NULL;
+
+ /* Allocate the appropriate connection structure. This reserves the
+ * the connection structure is is unallocated at this point. It will
+ * not actually be initialized until the socket is connected.
+ */
+
+ err = ENOMEM; /* Assume failure to allocate connection instance */
+ switch (type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ /* Allocate the TCP connection structure and save in the new
+ * socket instance.
+ */
+
+ struct uip_conn *conn = uip_tcpalloc();
+ if (conn)
+ {
+ /* Set the reference count on the connection structure. This
+ * reference count will be increment only if the socket is
+ * dup'ed
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+ psock->s_conn = conn;
+ conn->crefs = 1;
+ }
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ /* Allocate the UDP connection structure and save in the new
+ * socket instance.
+ */
+
+ struct uip_udp_conn *conn = uip_udpalloc();
+ if (conn)
+ {
+ /* Set the reference count on the connection structure. This
+ * reference count will be increment only if the socket is
+ * dup'ed
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+ psock->s_conn = conn;
+ conn->crefs = 1;
+ }
+ }
+ break;
+#endif
+
+ default:
+ break;
+ }
+
+ /* Did we succesfully allocate some kind of connection structure? */
+
+ if (!psock->s_conn)
+ {
+ /* Failed to reserve a connection structure */
+
+ goto errout; /* With err == ENFILE or ENOMEM */
+ }
+
+ return OK;
+
+errout:
+ errno = err;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Function: socket
+ *
+ * Description:
+ * socket() creates an endpoint for communication and returns a descriptor.
+ *
+ * Parameters:
+ * domain (see sys/socket.h)
+ * type (see sys/socket.h)
+ * protocol (see sys/socket.h)
+ *
+ * Returned Value:
+ * A non-negative socket descriptor on success; -1 on error with errno set
+ * appropriately.
+ *
+ * EACCES
+ * Permission to create a socket of the specified type and/or protocol
+ * is denied.
+ * EAFNOSUPPORT
+ * The implementation does not support the specified address family.
+ * EINVAL
+ * Unknown protocol, or protocol family not available.
+ * EMFILE
+ * Process file table overflow.
+ * ENFILE
+ * The system limit on the total number of open files has been reached.
+ * ENOBUFS or ENOMEM
+ * Insufficient memory is available. The socket cannot be created until
+ * sufficient resources are freed.
+ * EPROTONOSUPPORT
+ * The protocol type or the specified protocol is not supported within
+ * this domain.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int socket(int domain, int type, int protocol)
+{
+ FAR struct socket *psock;
+ int sockfd;
+ int ret;
+
+ /* Allocate a socket descriptor */
+
+ sockfd = sockfd_allocate(0);
+ if (sockfd < 0)
+ {
+ set_errno(ENFILE);
+ return ERROR;
+ }
+
+ /* Get the underlying socket structure */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock)
+ {
+ set_errno(ENOSYS); /* should not happen */
+ goto errout;
+ }
+
+ /* Initialize the socket structure */
+
+ ret = psock_socket(domain, type, protocol, psock);
+ if (ret < 0)
+ {
+ /* Error already set by psock_socket() */
+
+ goto errout;
+ }
+
+ return sockfd;
+
+errout:
+ sockfd_release(sockfd);
+ return ERROR;
+}
+
+#endif /* CONFIG_NET */
+
+
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
new file mode 100644
index 000000000..8bd8d1839
--- /dev/null
+++ b/nuttx/net/uip/Make.defs
@@ -0,0 +1,106 @@
+############################################################################
+# Make.defs
+#
+# Copyright (C) 2007, 2009-20010 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+UIP_ASRCS =
+UIP_CSRCS =
+
+ifeq ($(CONFIG_NET),y)
+
+# Common IP source files
+
+UIP_CSRCS += uip_initialize.c uip_setipid.c uip_input.c uip_send.c \
+ uip_poll.c uip_chksum.c uip_callback.c
+
+# Non-interrupt level support required?
+
+ifeq ($(CONFIG_NET_NOINTS),y)
+UIP_CSRCS += uip_lock.c
+endif
+
+# ARP supported is not provided for SLIP (Ethernet only)
+
+ifneq ($(CONFIG_NET_SLIP),y)
+UIP_CSRCS += uip_arp.c uip_arptab.c
+endif
+
+# IPv6-specific logic
+
+ifeq ($(CONFIG_NET_IPv6),y)
+UIP_CSRCS += uip_neighbor.c
+endif
+
+# TCP/IP source files
+
+ifeq ($(CONFIG_NET_TCP),y)
+
+UIP_CSRCS += uip_tcpconn.c uip_tcpseqno.c uip_tcppoll.c uip_tcptimer.c uip_tcpsend.c \
+ uip_tcpinput.c uip_tcpappsend.c uip_listen.c uip_tcpcallback.c \
+ uip_tcpreadahead.c uip_tcpbacklog.c
+
+endif
+
+# UDP source files
+
+ifeq ($(CONFIG_NET_UDP),y)
+
+UIP_CSRCS += uip_udpconn.c uip_udppoll.c uip_udpsend.c uip_udpinput.c \
+ uip_udpcallback.c
+
+endif
+
+# ICMP source files
+
+ifeq ($(CONFIG_NET_ICMP),y)
+
+UIP_CSRCS += uip_icmpinput.c uip_igmppoll.c
+
+ifeq ($(CONFIG_NET_ICMP_PING),y)
+ifneq ($(CONFIG_DISABLE_CLOCK),y)
+UIP_CSRCS += uip_icmpping.c uip_icmppoll.c uip_icmpsend.c
+endif
+endif
+
+# IGMP source files
+
+ifeq ($(CONFIG_NET_IGMP),y)
+UIP_CSRCS += uip_igmpgroup.c uip_igmpinit.c uip_igmpinput.c uip_igmpjoin.c \
+ uip_igmpleave.c uip_igmpmsg.c uip_igmpsend.c uip_igmptimer.c \
+ uip_mcastmac.c
+endif
+
+endif
+endif
+
+
diff --git a/nuttx/net/uip/uip_arp.c b/nuttx/net/uip/uip_arp.c
new file mode 100644
index 000000000..c731ff0de
--- /dev/null
+++ b/nuttx/net/uip/uip_arp.c
@@ -0,0 +1,431 @@
+/****************************************************************************
+ * net/uip/uip_arp.c
+ * Implementation of the ARP Address Resolution Protocol.
+ *
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Based on uIP which also has a BSD style license:
+ *
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/* The Address Resolution Protocol ARP is used for mapping between IP
+ * addresses and link level addresses such as the Ethernet MAC
+ * addresses. ARP uses broadcast queries to ask for the link level
+ * address of a known IP address and the host which is configured with
+ * the IP address for which the query was meant, will respond with its
+ * link level address.
+ *
+ * Note: This ARP implementation only supports Ethernet.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <netinet/in.h>
+
+#include <net/ethernet.h>
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip-arch.h>
+#include <nuttx/net/uip/uip-arp.h>
+
+#ifdef CONFIG_NET_ARP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define ARP_REQUEST 1
+#define ARP_REPLY 2
+
+#define ARP_HWTYPE_ETH 1
+
+#define RASIZE 4 /* Size of ROUTER ALERT */
+
+#define ETHBUF ((struct uip_eth_hdr *)&dev->d_buf[0])
+#define ARPBUF ((struct arp_hdr_s *)&dev->d_buf[UIP_LLH_LEN])
+#define IPBUF ((struct arp_iphdr_s *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* ARP header -- Size 28 bytes */
+
+struct arp_hdr_s
+{
+ uint16_t ah_hwtype; /* 16-bit Hardware type (Ethernet=0x001) */
+ uint16_t ah_protocol; /* 16-bit Protocol type (IP=0x0800) */
+ uint8_t ah_hwlen; /* 8-bit Hardware address size (6) */
+ uint8_t ah_protolen; /* 8-bit Procotol address size (4) */
+ uint16_t ah_opcode; /* 16-bit Operation */
+ uint8_t ah_shwaddr[6]; /* 48-bit Sender hardware address */
+ uint16_t ah_sipaddr[2]; /* 32-bit Sender IP adress */
+ uint8_t ah_dhwaddr[6]; /* 48-bit Target hardware address */
+ uint16_t ah_dipaddr[2]; /* 32-bit Target IP address */
+};
+
+/* IP header -- Size 20 or 24 bytes */
+
+struct arp_iphdr_s
+{
+ uint8_t eh_vhl; /* 8-bit Version (4) and header length (5 or 6) */
+ uint8_t eh_tos; /* 8-bit Type of service (e.g., 6=TCP) */
+ uint8_t eh_len[2]; /* 16-bit Total length */
+ uint8_t eh_ipid[2]; /* 16-bit Identification */
+ uint8_t eh_ipoffset[2]; /* 16-bit IP flags + fragment offset */
+ uint8_t eh_ttl; /* 8-bit Time to Live */
+ uint8_t eh_proto; /* 8-bit Protocol */
+ uint16_t eh_ipchksum; /* 16-bit Header checksum */
+ uint16_t eh_srcipaddr[2]; /* 32-bit Source IP address */
+ uint16_t eh_destipaddr[2]; /* 32-bit Destination IP address */
+ uint16_t eh_ipoption[2]; /* (optional) */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* Support for broadcast address */
+
+static const struct ether_addr g_broadcast_ethaddr =
+ {{0xff, 0xff, 0xff, 0xff, 0xff, 0xff}};
+static const uint16_t g_broadcast_ipaddr[2] = {0xffff, 0xffff};
+
+/* Support for IGMP multicast addresses.
+ *
+ * Well-known ethernet multicast address:
+ *
+ * ADDRESS TYPE USAGE
+ * 01-00-0c-cc-cc-cc 0x0802 CDP (Cisco Discovery Protocol), VTP (Virtual Trunking Protocol)
+ * 01-00-0c-cc-cc-cd 0x0802 Cisco Shared Spanning Tree Protocol Address
+ * 01-80-c2-00-00-00 0x0802 Spanning Tree Protocol (for bridges) IEEE 802.1D
+ * 01-80-c2-00-00-02 0x0809 Ethernet OAM Protocol IEEE 802.3ah
+ * 01-00-5e-xx-xx-xx 0x0800 IPv4 IGMP Multicast Address
+ * 33-33-00-00-00-00 0x86DD IPv6 Neighbor Discovery
+ * 33-33-xx-xx-xx-xx 0x86DD IPv6 Multicast Address (RFC3307)
+ *
+ * The following is the first three octects of the IGMP address:
+ */
+
+#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
+static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_DUMPARP) && defined(CONFIG_DEBUG)
+static void uip_arp_dump(struct arp_hdr_s *arp)
+{
+ nlldbg(" HW type: %04x Protocol: %04x\n",
+ arp->ah_hwtype, arp->ah_protocol);\
+ nlldbg(" HW len: %02x Proto len: %02x Operation: %04x\n",
+ arp->ah_hwlen, arp->ah_protolen, arp->ah_opcode);
+ nlldbg(" Sender MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
+ arp->ah_shwaddr[0], arp->ah_shwaddr[1], arp->ah_shwaddr[2],
+ arp->ah_shwaddr[3], arp->ah_shwaddr[4], arp->ah_shwaddr[5],
+ arp->ah_sipaddr[0] & 0xff, arp->ah_sipaddr[0] >> 8,
+ arp->ah_sipaddr[1] & 0xff, arp->ah_sipaddr[1] >> 8);
+ nlldbg(" Dest MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
+ arp->ah_dhwaddr[0], arp->ah_dhwaddr[1], arp->ah_dhwaddr[2],
+ arp->ah_dhwaddr[3], arp->ah_dhwaddr[4], arp->ah_dhwaddr[5],
+ arp->ah_dipaddr[0] & 0xff, arp->ah_dipaddr[0] >> 8,
+ arp->ah_dipaddr[1] & 0xff, arp->ah_dipaddr[1] >> 8);
+}
+#else
+# define uip_arp_dump(arp)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/* ARP processing for incoming IP packets
+ *
+ * This function should be called by the device driver when an IP packet has
+ * been received. The function will check if the address is in the ARP cache,
+ * and if so the ARP cache entry will be refreshed. If no ARP cache entry was
+ * found, a new one is created.
+ *
+ * This function expects an IP packet with a prepended Ethernet header in the
+ * d_buf[] buffer, and the length of the packet in the variable d_len.
+ */
+
+#ifdef CONFIG_NET_ARP_IPIN
+void uip_arp_ipin(struct uip_driver_s *dev)
+{
+ in_addr_t srcipaddr;
+
+ /* Only insert/update an entry if the source IP address of the incoming IP
+ * packet comes from a host on the local network.
+ */
+
+ srcipaddr = uip_ip4addr_conv(IPBUF->eh_srcipaddr);
+ if (!uip_ipaddr_maskcmp(srcipaddr, dev->d_ipaddr, dev->d_netmask))
+ {
+ uip_arp_update(IPBUF->eh_srcipaddr, ETHBUF->src);
+ }
+}
+#endif /* CONFIG_NET_ARP_IPIN */
+
+/* ARP processing for incoming ARP packets.
+ *
+ * This function should be called by the device driver when an ARP
+ * packet has been received. The function will act differently
+ * depending on the ARP packet type: if it is a reply for a request
+ * that we previously sent out, the ARP cache will be filled in with
+ * the values from the ARP reply. If the incoming ARP packet is an ARP
+ * request for our IP address, an ARP reply packet is created and put
+ * into the d_buf[] buffer.
+ *
+ * When the function returns, the value of the field d_len
+ * indicates whether the device driver should send out a packet or
+ * not. If d_len is zero, no packet should be sent. If d_len is
+ * non-zero, it contains the length of the outbound packet that is
+ * present in the d_buf[] buffer.
+ *
+ * This function expects an ARP packet with a prepended Ethernet
+ * header in the d_buf[] buffer, and the length of the packet in the
+ * variable d_len.
+ */
+
+void uip_arp_arpin(struct uip_driver_s *dev)
+{
+ struct arp_hdr_s *parp = ARPBUF;
+ in_addr_t ipaddr;
+
+ if (dev->d_len < (sizeof(struct arp_hdr_s) + UIP_LLH_LEN))
+ {
+ nlldbg("Too small\n");
+ dev->d_len = 0;
+ return;
+ }
+ dev->d_len = 0;
+
+ ipaddr = uip_ip4addr_conv(parp->ah_dipaddr);
+ switch(parp->ah_opcode)
+ {
+ case HTONS(ARP_REQUEST):
+ nllvdbg("ARP request for IP %04lx\n", (long)ipaddr);
+
+ /* ARP request. If it asked for our address, we send out a reply. */
+
+ if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr))
+ {
+ struct uip_eth_hdr *peth = ETHBUF;
+
+ /* First, we register the one who made the request in our ARP
+ * table, since it is likely that we will do more communication
+ * with this host in the future.
+ */
+
+ uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
+
+ parp->ah_opcode = HTONS(ARP_REPLY);
+ memcpy(parp->ah_dhwaddr, parp->ah_shwaddr, ETHER_ADDR_LEN);
+ memcpy(parp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
+ memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
+ memcpy(peth->dest, parp->ah_dhwaddr, ETHER_ADDR_LEN);
+
+ parp->ah_dipaddr[0] = parp->ah_sipaddr[0];
+ parp->ah_dipaddr[1] = parp->ah_sipaddr[1];
+ uiphdr_ipaddr_copy(parp->ah_sipaddr, &dev->d_ipaddr);
+ uip_arp_dump(parp);
+
+ peth->type = HTONS(UIP_ETHTYPE_ARP);
+ dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
+ }
+ break;
+
+ case HTONS(ARP_REPLY):
+ nllvdbg("ARP reply for IP %04lx\n", (long)ipaddr);
+
+ /* ARP reply. We insert or update the ARP table if it was meant
+ * for us.
+ */
+
+ if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr))
+ {
+ uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
+ }
+ break;
+ }
+}
+
+/* Prepend Ethernet header to an outbound IP packet and see if we need
+ * to send out an ARP request.
+ *
+ * This function should be called before sending out an IP packet. The
+ * function checks the destination IP address of the IP packet to see
+ * what Ethernet MAC address that should be used as a destination MAC
+ * address on the Ethernet.
+ *
+ * If the destination IP address is in the local network (determined
+ * by logical ANDing of netmask and our IP address), the function
+ * checks the ARP cache to see if an entry for the destination IP
+ * address is found. If so, an Ethernet header is prepended and the
+ * function returns. If no ARP cache entry is found for the
+ * destination IP address, the packet in the d_buf[] is replaced by
+ * an ARP request packet for the IP address. The IP packet is dropped
+ * and it is assumed that they higher level protocols (e.g., TCP)
+ * eventually will retransmit the dropped packet.
+ *
+ * If the destination IP address is not on the local network, the IP
+ * address of the default router is used instead.
+ *
+ * When the function returns, a packet is present in the d_buf[]
+ * buffer, and the length of the packet is in the field d_len.
+ */
+
+void uip_arp_out(struct uip_driver_s *dev)
+{
+ const struct arp_entry *tabptr = NULL;
+ struct arp_hdr_s *parp = ARPBUF;
+ struct uip_eth_hdr *peth = ETHBUF;
+ struct arp_iphdr_s *pip = IPBUF;
+ in_addr_t ipaddr;
+ in_addr_t destipaddr;
+
+ /* Find the destination IP address in the ARP table and construct
+ * the Ethernet header. If the destination IP addres isn't on the
+ * local network, we use the default router's IP address instead.
+ *
+ * If not ARP table entry is found, we overwrite the original IP
+ * packet with an ARP request for the IP address.
+ */
+
+ /* First check if destination is a local broadcast. */
+
+ if (uiphdr_ipaddr_cmp(pip->eh_destipaddr, g_broadcast_ipaddr))
+ {
+ memcpy(peth->dest, g_broadcast_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
+ }
+#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
+ /* Check if the destination address is a multicast address
+ *
+ * - IPv4: multicast addresses lie in the class D group -- The address range
+ * 224.0.0.0 to 239.255.255.255 (224.0.0.0/4)
+ *
+ * - IPv6 multicast addresses are have the high-order octet of the
+ * addresses=0xff (ff00::/8.)
+ */
+
+ else if (NTOHS(pip->eh_destipaddr[0]) >= 0xe000 &&
+ NTOHS(pip->eh_destipaddr[0]) <= 0xefff)
+ {
+ /* Build the well-known IPv4 IGMP ethernet address. The first
+ * three bytes are fixed; the final three variable come from the
+ * last three bytes of the IP address.
+ */
+
+ const uint8_t *ip = ((uint8_t*)pip->eh_destipaddr) + 1;
+ memcpy(peth->dest, g_multicast_ethaddr, 3);
+ memcpy(&peth->dest[3], ip, 3);
+ }
+#endif
+ else
+ {
+ /* Check if the destination address is on the local network. */
+
+ destipaddr = uip_ip4addr_conv(pip->eh_destipaddr);
+ if (!uip_ipaddr_maskcmp(destipaddr, dev->d_ipaddr, dev->d_netmask))
+ {
+ /* Destination address was not on the local network, so we need to
+ * use the default router's IP address instead of the destination
+ * address when determining the MAC address.
+ */
+
+ uip_ipaddr_copy(ipaddr, dev->d_draddr);
+ }
+ else
+ {
+ /* Else, we use the destination IP address. */
+
+ uip_ipaddr_copy(ipaddr, destipaddr);
+ }
+
+ /* Check if we already have this destination address in the ARP table */
+
+ tabptr = uip_arp_find(ipaddr);
+ if (!tabptr)
+ {
+ nllvdbg("ARP request for IP %04lx\n", (long)ipaddr);
+
+ /* The destination address was not in our ARP table, so we
+ * overwrite the IP packet with an ARP request.
+ */
+
+ memset(peth->dest, 0xff, ETHER_ADDR_LEN);
+ memset(parp->ah_dhwaddr, 0x00, ETHER_ADDR_LEN);
+ memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
+ memcpy(parp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
+
+ uiphdr_ipaddr_copy(parp->ah_dipaddr, &ipaddr);
+ uiphdr_ipaddr_copy(parp->ah_sipaddr, &dev->d_ipaddr);
+
+ parp->ah_opcode = HTONS(ARP_REQUEST);
+ parp->ah_hwtype = HTONS(ARP_HWTYPE_ETH);
+ parp->ah_protocol = HTONS(UIP_ETHTYPE_IP);
+ parp->ah_hwlen = ETHER_ADDR_LEN;
+ parp->ah_protolen = 4;
+ uip_arp_dump(parp);
+
+ peth->type = HTONS(UIP_ETHTYPE_ARP);
+ dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
+ return;
+ }
+
+ /* Build an ethernet header. */
+
+ memcpy(peth->dest, tabptr->at_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
+ }
+
+ /* Finish populating the ethernet header */
+
+ memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
+ peth->type = HTONS(UIP_ETHTYPE_IP);
+ dev->d_len += UIP_LLH_LEN;
+}
+
+#endif /* CONFIG_NET_ARP */
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_arptab.c b/nuttx/net/uip/uip_arptab.c
new file mode 100644
index 000000000..1a29f25df
--- /dev/null
+++ b/nuttx/net/uip/uip_arptab.c
@@ -0,0 +1,257 @@
+/****************************************************************************
+ * net/uip/uip_arptab.c
+ * Implementation of the ARP Address Resolution Protocol.
+ *
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based originally on uIP which also has a BSD style license:
+ *
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#ifdef CONFIG_NET
+
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <netinet/in.h>
+
+#include <net/ethernet.h>
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip-arch.h>
+#include <nuttx/net/uip/uip-arp.h>
+
+#ifdef CONFIG_NET_ARP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The table of known address mappings */
+
+static struct arp_entry g_arptable[CONFIG_NET_ARPTAB_SIZE];
+static uint8_t g_arptime;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_arp_init
+ *
+ * Description:
+ * Initialize the ARP module. This function must be called before any of
+ * the other ARP functions.
+ *
+ ****************************************************************************/
+
+void uip_arp_init(void)
+{
+ int i;
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ memset(&g_arptable[i].at_ipaddr, 0, sizeof(in_addr_t));
+ }
+}
+
+/****************************************************************************
+ * Name: uip_arp_timer
+ *
+ * Description:
+ * This function performs periodic timer processing in the ARP module
+ * and should be called at regular intervals. The recommended interval
+ * is 10 seconds between the calls. It is responsible for flushing old
+ * entries in the ARP table.
+ *
+ ****************************************************************************/
+
+void uip_arp_timer(void)
+{
+ struct arp_entry *tabptr;
+ int i;
+
+ ++g_arptime;
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &g_arptable[i];
+ if (tabptr->at_ipaddr != 0 && g_arptime - tabptr->at_time >= UIP_ARP_MAXAGE)
+ {
+ tabptr->at_ipaddr = 0;
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: uip_arp_update
+ *
+ * Description:
+ * Add the IP/HW address mapping to the ARP table -OR- change the IP
+ * address of an existing association.
+ *
+ * Input parameters:
+ * pipaddr - Refers to an IP address uint16_t[2]
+ * ethaddr - Refers to a HW address uint8_t[IFHWADDRLEN]
+ *
+ * Assumptions
+ * Interrupts are disabled
+ *
+ ****************************************************************************/
+
+void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
+{
+ struct arp_entry *tabptr = NULL;
+ in_addr_t ipaddr = uip_ip4addr_conv(pipaddr);
+ int i;
+
+ /* Walk through the ARP mapping table and try to find an entry to
+ * update. If none is found, the IP -> MAC address mapping is
+ * inserted in the ARP table.
+ */
+
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &g_arptable[i];
+
+ /* Only check those entries that are actually in use. */
+
+ if (tabptr->at_ipaddr != 0)
+ {
+ /* Check if the source IP address of the incoming packet matches
+ * the IP address in this ARP table entry.
+ */
+
+ if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
+ {
+ /* An old entry found, update this and return. */
+
+ memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN);
+ tabptr->at_time = g_arptime;
+ return;
+ }
+ }
+ }
+
+ /* If we get here, no existing ARP table entry was found, so we create one. */
+
+ /* First, we try to find an unused entry in the ARP table. */
+
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &g_arptable[i];
+ if (tabptr->at_ipaddr == 0)
+ {
+ break;
+ }
+ }
+
+ /* If no unused entry is found, we try to find the oldest entry and
+ * throw it away.
+ */
+
+ if (i == CONFIG_NET_ARPTAB_SIZE)
+ {
+ uint8_t tmpage = 0;
+ int j = 0;
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &g_arptable[i];
+ if (g_arptime - tabptr->at_time > tmpage)
+ {
+ tmpage = g_arptime - tabptr->at_time;
+ j = i;
+ }
+ }
+ i = j;
+ tabptr = &g_arptable[i];
+ }
+
+ /* Now, i is the ARP table entry which we will fill with the new
+ * information.
+ */
+
+ tabptr->at_ipaddr = ipaddr;
+ memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN);
+ tabptr->at_time = g_arptime;
+}
+
+/****************************************************************************
+ * Name: uip_arp_find
+ *
+ * Description:
+ * Find the ARP entry corresponding to this IP address.
+ *
+ * Input parameters:
+ * ipaddr - Refers to an IP addressin network order
+ *
+ * Assumptions
+ * Interrupts are disabled; Returned value will become unstable when
+ * interrupts are re-enabled or if any other uIP APIs are called.
+ *
+ ****************************************************************************/
+
+struct arp_entry *uip_arp_find(in_addr_t ipaddr)
+{
+ struct arp_entry *tabptr;
+ int i;
+
+ for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &g_arptable[i];
+ if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
+ {
+ return tabptr;
+ }
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NET_ARP */
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_callback.c b/nuttx/net/uip/uip_callback.c
new file mode 100644
index 000000000..730aa7758
--- /dev/null
+++ b/nuttx/net/uip/uip_callback.c
@@ -0,0 +1,251 @@
+/****************************************************************************
+ * net/uip/uip_callback.c
+ *
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET)
+
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct uip_callback_s g_cbprealloc[CONFIG_NET_NACTIVESOCKETS];
+static FAR struct uip_callback_s *g_cbfreelist = NULL;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_callbackinit
+ *
+ * Description:
+ * Configure the pre-allocated callaback structures into a free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_callbackinit(void)
+{
+ int i;
+ for (i = 0; i < CONFIG_NET_NACTIVESOCKETS; i++)
+ {
+ g_cbprealloc[i].flink = g_cbfreelist;
+ g_cbfreelist = &g_cbprealloc[i];
+ }
+}
+
+/****************************************************************************
+ * Function: uip_callbackalloc
+ *
+ * Description:
+ * Allocate a callback container from the free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+FAR struct uip_callback_s *uip_callbackalloc(FAR struct uip_callback_s **list)
+{
+ struct uip_callback_s *ret;
+ uip_lock_t save;
+
+ /* Check the head of the free list */
+
+ save = uip_lock();
+ ret = g_cbfreelist;
+ if (ret)
+ {
+ /* Remove the next instance from the head of the free list */
+
+ g_cbfreelist = ret->flink;
+ memset(ret, 0, sizeof(struct uip_callback_s));
+
+ /* Add the newly allocated instance to the head of the specified list */
+
+ if (list)
+ {
+ ret->flink = *list;
+ *list = ret;
+ }
+ else
+ {
+ ret->flink = NULL;
+ }
+ }
+#ifdef CONFIG_DEBUG
+ else
+ {
+ nlldbg("Failed to allocate callback\n");
+ }
+#endif
+
+ uip_unlock(save);
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_callbackfree
+ *
+ * Description:
+ * Return a callback container to the free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_callbackfree(FAR struct uip_callback_s *cb, FAR struct uip_callback_s **list)
+{
+ FAR struct uip_callback_s *prev;
+ FAR struct uip_callback_s *curr;
+ uip_lock_t save;
+
+ if (cb)
+ {
+ /* Find the callback structure in the connection's list */
+
+ save = uip_lock();
+ if (list)
+ {
+ for (prev = NULL, curr = *list;
+ curr && curr != cb;
+ prev = curr, curr = curr->flink);
+
+ /* Remove the structure from the connection's list */
+
+ if (curr)
+ {
+ if (prev)
+ {
+ prev->flink = cb->flink;
+ }
+ else
+ {
+ *list = cb->flink;
+ }
+ }
+ }
+
+ /* Put the structure into the free list */
+
+ cb->flink = g_cbfreelist;
+ g_cbfreelist = cb;
+ uip_unlock(save);
+ }
+}
+
+/****************************************************************************
+ * Function: uip_callbackexecute
+ *
+ * Description:
+ * Execute a list of callbacks.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
+ uint16_t flags, FAR struct uip_callback_s *list)
+{
+ FAR struct uip_callback_s *next;
+ uip_lock_t save;
+
+ /* Loop for each callback in the list and while there are still events
+ * set in the flags set.
+ */
+
+ save = uip_lock();
+ while (list && flags)
+ {
+ /* Save the pointer to the next callback in the lists. This is done
+ * because the callback action might delete the entry pointed to by
+ * list.
+ */
+
+ next = list->flink;
+
+ /* Check if this callback handles any of the events in the flag set */
+
+ if (list->event && (flags & list->flags) != 0)
+ {
+ /* Yes.. perform the callback. Actions perform by the callback
+ * may delete the current list entry or add a new list entry to
+ * beginning of the list (which will be ignored on this pass)
+ */
+
+ nllvdbg("Call event=%p with flags=%04x\n", list->event, flags);
+ flags = list->event(dev, pvconn, list->priv, flags);
+ }
+
+ /* Set up for the next time through the loop */
+
+ list = next;
+ }
+
+ uip_unlock(save);
+ return flags;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_chksum.c b/nuttx/net/uip/uip_chksum.c
new file mode 100644
index 000000000..7a4eee790
--- /dev/null
+++ b/nuttx/net/uip/uip_chksum.c
@@ -0,0 +1,230 @@
+/****************************************************************************
+ * net/uip/uip_chksum.c
+ *
+ * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define BUF ((struct uip_ip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+#if !UIP_ARCH_CHKSUM
+static uint16_t chksum(uint16_t sum, const uint8_t *data, uint16_t len)
+{
+ uint16_t t;
+ const uint8_t *dataptr;
+ const uint8_t *last_byte;
+
+ dataptr = data;
+ last_byte = data + len - 1;
+
+ while(dataptr < last_byte)
+ {
+ /* At least two more bytes */
+
+ t = (dataptr[0] << 8) + dataptr[1];
+ sum += t;
+ if (sum < t)
+ {
+ sum++; /* carry */
+ }
+ dataptr += 2;
+ }
+
+ if (dataptr == last_byte)
+ {
+ t = (dataptr[0] << 8) + 0;
+ sum += t;
+ if (sum < t)
+ {
+ sum++; /* carry */
+ }
+ }
+
+ /* Return sum in host byte order. */
+
+ return sum;
+}
+
+static uint16_t upper_layer_chksum(struct uip_driver_s *dev, uint8_t proto)
+{
+ struct uip_ip_hdr *pbuf = BUF;
+ uint16_t upper_layer_len;
+ uint16_t sum;
+
+#ifdef CONFIG_NET_IPv6
+ upper_layer_len = (((uint16_t)(pbuf->len[0]) << 8) + pbuf->len[1]);
+#else /* CONFIG_NET_IPv6 */
+ upper_layer_len = (((uint16_t)(pbuf->len[0]) << 8) + pbuf->len[1]) - UIP_IPH_LEN;
+#endif /* CONFIG_NET_IPv6 */
+
+ /* First sum pseudoheader. */
+
+ /* IP protocol and length fields. This addition cannot carry. */
+
+ sum = upper_layer_len + proto;
+
+ /* Sum IP source and destination addresses. */
+
+ sum = chksum(sum, (uint8_t *)&pbuf->srcipaddr, 2 * sizeof(uip_ipaddr_t));
+
+ /* Sum TCP header and data. */
+
+ sum = chksum(sum, &dev->d_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len);
+
+ return (sum == 0) ? 0xffff : htons(sum);
+}
+
+#ifdef CONFIG_NET_IPv6
+static uint16_t uip_icmp6chksum(struct uip_driver_s *dev)
+{
+ return upper_layer_chksum(dev, UIP_PROTO_ICMP6);
+}
+#endif /* CONFIG_NET_IPv6 */
+
+#endif /* UIP_ARCH_CHKSUM */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/* Calculate the Internet checksum over a buffer. */
+
+#if !UIP_ARCH_ADD32
+static inline void uip_carry32(uint8_t *sum, uint16_t op16)
+{
+ if (sum[2] < (op16 >> 8))
+ {
+ ++sum[1];
+ if (sum[1] == 0)
+ {
+ ++sum[0];
+ }
+ }
+
+ if (sum[3] < (op16 & 0xff))
+ {
+ ++sum[2];
+ if (sum[2] == 0)
+ {
+ ++sum[1];
+ if (sum[1] == 0)
+ {
+ ++sum[0];
+ }
+ }
+ }
+}
+
+void uip_incr32(uint8_t *op32, uint16_t op16)
+{
+ op32[3] += (op16 & 0xff);
+ op32[2] += (op16 >> 8);
+ uip_carry32(op32, op16);
+}
+
+#endif /* UIP_ARCH_ADD32 */
+
+#if !UIP_ARCH_CHKSUM
+uint16_t uip_chksum(uint16_t *data, uint16_t len)
+{
+ return htons(chksum(0, (uint8_t *)data, len));
+}
+
+/* Calculate the IP header checksum of the packet header in d_buf. */
+
+#ifndef UIP_ARCH_IPCHKSUM
+uint16_t uip_ipchksum(struct uip_driver_s *dev)
+{
+ uint16_t sum;
+
+ sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN);
+ return (sum == 0) ? 0xffff : htons(sum);
+}
+#endif
+
+/* Calculate the TCP checksum of the packet in d_buf and d_appdata. */
+
+uint16_t uip_tcpchksum(struct uip_driver_s *dev)
+{
+ return upper_layer_chksum(dev, UIP_PROTO_TCP);
+}
+
+/* Calculate the UDP checksum of the packet in d_buf and d_appdata. */
+
+#ifdef CONFIG_NET_UDP_CHECKSUMS
+uint16_t uip_udpchksum(struct uip_driver_s *dev)
+{
+ return upper_layer_chksum(dev, UIP_PROTO_UDP);
+}
+#endif
+
+/* Calculate the checksum of the ICMP message */
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+uint16_t uip_icmpchksum(struct uip_driver_s *dev, int len)
+{
+ struct uip_icmpip_hdr *picmp = ICMPBUF;
+ return uip_chksum((uint16_t*)&picmp->type, len);
+}
+#endif
+
+#endif /* UIP_ARCH_CHKSUM */
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_icmpinput.c b/nuttx/net/uip/uip_icmpinput.c
new file mode 100644
index 000000000..cea2ae4fc
--- /dev/null
+++ b/nuttx/net/uip/uip_icmpinput.c
@@ -0,0 +1,317 @@
+/****************************************************************************
+ * net/uip/uip_icmpinput.c
+ * Handling incoming ICMP/ICMP6 input
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_ICMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_ICMP_PING
+struct uip_callback_s *g_echocallback = NULL;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_icmpinput
+ *
+ * Description:
+ * Handle incoming ICMP/ICMP6 input
+ *
+ * Parameters:
+ * dev - The device driver structure containing the received ICMP/ICMP6
+ * packet
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_icmpinput(struct uip_driver_s *dev)
+{
+ struct uip_icmpip_hdr *picmp = ICMPBUF;
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.recv++;
+#endif
+
+#ifndef CONFIG_NET_IPv6
+ /* ICMPv4 processing code follows. */
+
+ /* ICMP echo (i.e., ping) processing. This is simple, we only change the
+ * ICMP type from ECHO to ECHO_REPLY and adjust the ICMP checksum before
+ * we return the packet.
+ */
+
+ if (picmp->type == ICMP_ECHO_REQUEST)
+ {
+ /* If we are configured to use ping IP address assignment, we use
+ * the destination IP address of this ping packet and assign it to
+ * ourself.
+ */
+
+#ifdef CONFIG_NET_PINGADDRCONF
+ if (dev->d_ipaddr == 0)
+ {
+ dev->d_ipaddr = picmp->destipaddr;
+ }
+#endif
+
+ /* Change the ICMP type */
+
+ picmp->type = ICMP_ECHO_REPLY;
+
+ /* Swap IP addresses. */
+
+ uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
+ uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
+
+ /* Recalculate the ICMP checksum */
+
+#if 0
+ /* The slow way... sum over the ICMP message */
+
+ picmp->icmpchksum = 0;
+ picmp->icmpchksum = ~uip_icmpchksum(dev, (((uint16_t)picmp->len[0] << 8) | (uint16_t)picmp->len[1]) - UIP_IPH_LEN);
+ if (picmp->icmpchksum == 0)
+ {
+ picmp->icmpchksum = 0xffff;
+ }
+#else
+ /* The quick way -- Since only the type has changed, just adjust the
+ * checksum for the change of type
+ */
+
+ if( picmp->icmpchksum >= HTONS(0xffff - (ICMP_ECHO_REQUEST << 8)))
+ {
+ picmp->icmpchksum += HTONS(ICMP_ECHO_REQUEST << 8) + 1;
+ }
+ else
+ {
+ picmp->icmpchksum += HTONS(ICMP_ECHO_REQUEST << 8);
+ }
+#endif
+
+ nllvdbg("Outgoing ICMP packet length: %d (%d)\n",
+ dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.sent++;
+ uip_stat.ip.sent++;
+#endif
+ }
+
+ /* If an ICMP echo reply is received then there should also be
+ * a thread waiting to received the echo response.
+ */
+
+#ifdef CONFIG_NET_ICMP_PING
+ else if (picmp->type == ICMP_ECHO_REPLY && g_echocallback)
+ {
+ (void)uip_callbackexecute(dev, picmp, UIP_ECHOREPLY, g_echocallback);
+ }
+#endif
+
+ /* Otherwise the ICMP input was not processed */
+
+ else
+ {
+ nlldbg("Unknown ICMP cmd: %d\n", picmp->type);
+ goto typeerr;
+ }
+
+ return;
+
+typeerr:
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.typeerr++;
+ uip_stat.icmp.drop++;
+#endif
+ dev->d_len = 0;
+
+#else /* !CONFIG_NET_IPv6 */
+
+ /* If we get a neighbor solicitation for our address we should send
+ * a neighbor advertisement message back.
+ */
+
+ if (picmp->type == ICMP6_NEIGHBOR_SOLICITATION)
+ {
+ if (uip_ipaddr_cmp(picmp->icmp6data, dev->d_ipaddr))
+ {
+ if (picmp->options[0] == ICMP6_OPTION_SOURCE_LINK_ADDRESS)
+ {
+ /* Save the sender's address in our neighbor list. */
+
+ uiphdr_neighbor_add(picmp->srcipaddr, &(picmp->options[2]));
+ }
+
+ /* We should now send a neighbor advertisement back to where the
+ * neighbor solicication came from.
+ */
+
+ picmp->type = ICMP6_NEIGHBOR_ADVERTISEMENT;
+ picmp->flags = ICMP6_FLAG_S; /* Solicited flag. */
+
+ picmp->reserved1 = picmp->reserved2 = picmp->reserved3 = 0;
+
+ uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
+ uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
+ picmp->options[0] = ICMP6_OPTION_TARGET_LINK_ADDRESS;
+ picmp->options[1] = 1; /* Options length, 1 = 8 bytes. */
+ memcpy(&(picmp->options[2]), &dev->d_mac, IFHWADDRLEN);
+ picmp->icmpchksum = 0;
+ picmp->icmpchksum = ~uip_icmp6chksum(dev);
+ }
+ else
+ {
+ goto drop;
+ }
+ }
+ else if (picmp->type == ICMP6_ECHO_REQUEST)
+ {
+ /* ICMP echo (i.e., ping) processing. This is simple, we only
+ * change the ICMP type from ECHO to ECHO_REPLY and update the
+ * ICMP checksum before we return the packet.
+ */
+
+ picmp->type = ICMP6_ECHO_REPLY;
+
+ uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
+ uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
+ picmp->icmpchksum = 0;
+ picmp->icmpchksum = ~uip_icmp6chksum(dev);
+ }
+
+ /* If an ICMP echo reply is received then there should also be
+ * a thread waiting to received the echo response.
+ */
+
+#ifdef CONFIG_NET_ICMP_PING
+ else if (picmp->type == ICMP6_ECHO_REPLY && g_echocallback)
+ {
+ uint16_t flags = UIP_ECHOREPLY;
+
+ if (g_echocallback)
+ {
+ /* Dispatch the ECHO reply to the waiting thread */
+
+ flags = uip_callbackexecute(dev, picmp, flags, g_echocallback);
+ }
+
+ /* If the ECHO reply was not handled, then drop the packet */
+
+ if (flags == UIP_ECHOREPLY)
+ {
+ /* The ECHO reply was not handled */
+
+ goto drop;
+ }
+ }
+#endif
+
+ else
+ {
+ nlldbg("Unknown ICMP6 cmd: %d\n", picmp->type);
+ goto typeerr;
+ }
+
+ nllvdbg("Outgoing ICMP6 packet length: %d (%d)\n",
+ dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.sent++;
+ uip_stat.ip.sent++;
+#endif
+ return;
+
+typeerr:
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.typeerr++;
+#endif
+
+drop:
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.drop++;
+#endif
+ dev->d_len = 0;
+
+#endif /* !CONFIG_NET_IPv6 */
+}
+
+#endif /* CONFIG_NET_ICMP */
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c
new file mode 100644
index 000000000..356187d09
--- /dev/null
+++ b/nuttx/net/uip/uip_icmpping.c
@@ -0,0 +1,379 @@
+/****************************************************************************
+ * net/uip/uip_icmpping.c
+ *
+ * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && \
+ defined(CONFIG_NET_ICMP_PING) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <nuttx/clock.h>
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+#include "../net_internal.h" /* Should not include this! */
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define ICMPDAT (&dev->d_buf[UIP_LLH_LEN + sizeof(struct uip_icmpip_hdr)])
+
+/* Allocate a new ICMP data callback */
+
+#define uip_icmpcallbackalloc() uip_callbackalloc(&g_echocallback)
+#define uip_icmpcallbackfree(cb) uip_callbackfree(cb, &g_echocallback)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct icmp_ping_s
+{
+ FAR struct uip_callback_s *png_cb; /* Reference to callback instance */
+
+ sem_t png_sem; /* Use to manage the wait for the response */
+ uint32_t png_time; /* Start time for determining timeouts */
+ uint32_t png_ticks; /* System clock ticks to wait */
+ int png_result; /* 0: success; <0:negated errno on fail */
+ uip_ipaddr_t png_addr; /* The peer to be ping'ed */
+ uint16_t png_id; /* Used to match requests with replies */
+ uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
+ uint16_t png_datlen; /* The length of data to send in the ECHO request */
+ bool png_sent; /* true... the PING request has been sent */
+};
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: ping_timeout
+ *
+ * Description:
+ * Check for send timeout.
+ *
+ * Parameters:
+ * pstate - Ping state structure
+ *
+ * Returned Value:
+ * TRUE:timeout FALSE:no timeout
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static inline int ping_timeout(struct icmp_ping_s *pstate)
+{
+ uint32_t elapsed = clock_systimer() - pstate->png_time;
+ if (elapsed >= pstate->png_ticks)
+ {
+ return TRUE;
+ }
+ return FALSE;
+}
+
+/****************************************************************************
+ * Function: ping_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * ECHO request and/or ECHO reply actions when polled by the uIP layer.
+ *
+ * Parameters:
+ * dev The structure of the network driver that caused the interrupt
+ * conn The received packet, cast to void *
+ * pvpriv An instance of struct icmp_ping_s cast to void*
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * Modified value of the input flags
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static uint16_t ping_interrupt(struct uip_driver_s *dev, void *conn,
+ void *pvpriv, uint16_t flags)
+{
+ struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvpriv;
+ uint8_t *ptr;
+ int failcode = -ETIMEDOUT;
+ int i;
+
+ nllvdbg("flags: %04x\n", flags);
+ if (pstate)
+ {
+ /* Check if this device is on the same network as the destination device. */
+
+ if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
+ {
+ /* Destination address was not on the local network served by this
+ * device. If a timeout occurs, then the most likely reason is
+ * that the destination address is not reachable.
+ */
+
+ nllvdbg("Not reachable\n");
+ failcode = -ENETUNREACH;
+ }
+ else
+ {
+ /* Check if this is a ICMP ECHO reply. If so, return the sequence
+ * number to the caller. NOTE: We may not even have sent the
+ * requested ECHO request; this could have been the delayed ECHO
+ * response from a previous ping.
+ */
+
+ if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL)
+ {
+ struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn;
+ nlldbg("ECHO reply: id=%d seqno=%d\n", ntohs(icmp->id), ntohs(icmp->seqno));
+
+ if (ntohs(icmp->id) == pstate->png_id)
+ {
+ /* Consume the ECHOREPLY */
+
+ flags &= ~UIP_ECHOREPLY;
+ dev->d_len = 0;
+
+ /* Return the result to the caller */
+
+ pstate->png_result = OK;
+ pstate->png_seqno = ntohs(icmp->seqno);
+ goto end_wait;
+ }
+ }
+
+ /* Check:
+ * If the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread
+ * -OR-
+ * If the output buffer currently contains unprocessed incoming
+ * data.
+ * -OR-
+ * If we have alread sent the ECHO request
+ *
+ * In the first two cases, we will just have to wait for the next
+ * polling cycle.
+ */
+
+ if (dev->d_sndlen <= 0 && /* Packet available */
+ (flags & UIP_NEWDATA) == 0 && /* No incoming data */
+ !pstate->png_sent) /* Request not sent */
+ {
+ struct uip_icmpip_hdr *picmp = ICMPBUF;
+
+ /* We can send the ECHO request now.
+ *
+ * Format the ICMP ECHO request packet
+ */
+
+ picmp->type = ICMP_ECHO_REQUEST;
+ picmp->icode = 0;
+#ifndef CONFIG_NET_IPv6
+ picmp->id = htons(pstate->png_id);
+ picmp->seqno = htons(pstate->png_seqno);
+#else
+# error "IPv6 ECHO Request not implemented"
+#endif
+ /* Add some easily verifiable data */
+
+ for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++)
+ {
+ *ptr++ = i;
+ }
+
+ /* Send the ICMP echo request. Note that d_sndlen is set to
+ * the size of the ICMP payload and does not include the size
+ * of the ICMP header.
+ */
+
+ nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
+
+ dev->d_sndlen = pstate->png_datlen + 4;
+ uip_icmpsend(dev, &pstate->png_addr);
+ pstate->png_sent = true;
+ return flags;
+ }
+ }
+
+ /* Check if the selected timeout has elapsed */
+
+ if (ping_timeout(pstate))
+ {
+ /* Yes.. report the timeout */
+
+ nlldbg("Ping timeout\n");
+ pstate->png_result = failcode;
+ goto end_wait;
+ }
+
+ /* Continue waiting */
+ }
+ return flags;
+
+end_wait:
+ nllvdbg("Resuming\n");
+
+ /* Do not allow any further callbacks */
+
+ pstate->png_cb->flags = 0;
+ pstate->png_cb->priv = NULL;
+ pstate->png_cb->event = NULL;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->png_sem);
+ return flags;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_ping
+ *
+ * Description:
+ * Send a ECHO request and wait for the ECHO response
+ *
+ * Parameters:
+ * addr - The IP address of the peer to send the ICMP ECHO request to
+ * in network order.
+ * id - The ID to use in the ICMP ECHO request. This number should be
+ * unique; only ECHO responses with this matching ID will be
+ * processed (host order)
+ * seqno - The sequence number used in the ICMP ECHO request. NOT used
+ * to match responses (host order)
+ * dsecs - Wait up to this many deci-seconds for the ECHO response to be
+ * returned (host order).
+ *
+ * Return:
+ * seqno of received ICMP ECHO with matching ID (may be different
+ * from the seqno argument (may be a delayed response from an earlier
+ * ping with the same ID). Or a negated errno on any failure.
+ *
+ * Assumptions:
+ * Called from the user level with interrupts enabled.
+ *
+ ****************************************************************************/
+
+int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
+ uint16_t datalen, int dsecs)
+{
+ struct icmp_ping_s state;
+ uip_lock_t save;
+
+ /* Initialize the state structure */
+
+ sem_init(&state.png_sem, 0, 0);
+ state.png_ticks = DSEC2TICK(dsecs); /* System ticks to wait */
+ state.png_result = -ENOMEM; /* Assume allocation failure */
+ state.png_addr = addr; /* Address of the peer to be ping'ed */
+ state.png_id = id; /* The ID to use in the ECHO request */
+ state.png_seqno = seqno; /* The seqno to use int the ECHO request */
+ state.png_datlen = datalen; /* The length of data to send in the ECHO request */
+ state.png_sent = false; /* ECHO request not yet sent */
+
+ save = uip_lock();
+ state.png_time = clock_systimer();
+
+ /* Set up the callback */
+
+ state.png_cb = uip_icmpcallbackalloc();
+ if (state.png_cb)
+ {
+ state.png_cb->flags = UIP_POLL|UIP_ECHOREPLY;
+ state.png_cb->priv = (void*)&state;
+ state.png_cb->event = ping_interrupt;
+ state.png_result = -EINTR; /* Assume sem-wait interrupted by signal */
+
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&state.png_addr);
+
+ /* Wait for either the full round trip transfer to complete or
+ * for timeout to occur. (1) uip_lockedwait will also terminate if a
+ * signal is received, (2) interrupts may be disabled! They will
+ * be re-enabled while the task sleeps and automatically
+ * re-enabled when the task restarts.
+ */
+
+ nlldbg("Start time: 0x%08x seqno: %d\n", state.png_time, seqno);
+ uip_lockedwait(&state.png_sem);
+
+ uip_icmpcallbackfree(state.png_cb);
+ }
+ uip_unlock(save);
+
+ /* Return the negated error number in the event of a failure, or the
+ * sequence number of the ECHO reply on success.
+ */
+
+ if (!state.png_result)
+ {
+ nlldbg("Return seqno=%d\n", state.png_seqno);
+ return (int)state.png_seqno;
+ }
+ else
+ {
+ nlldbg("Return error=%d\n", -state.png_result);
+ return state.png_result;
+ }
+}
+
+#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING ... */
diff --git a/nuttx/net/uip/uip_icmppoll.c b/nuttx/net/uip/uip_icmppoll.c
new file mode 100644
index 000000000..ca1d684c0
--- /dev/null
+++ b/nuttx/net/uip/uip_icmppoll.c
@@ -0,0 +1,103 @@
+/****************************************************************************
+ * net/uip/uip_icmppoll.c
+ *
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_icmppoll
+ *
+ * Description:
+ * Poll a UDP "connection" structure for availability of TX data
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_icmppoll(struct uip_driver_s *dev)
+{
+ /* Setup for the application callback */
+
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPICMPH_LEN];
+ dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPICMPH_LEN];
+
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+
+ /* Perform the application callback */
+
+ (void)uip_callbackexecute(dev, NULL, UIP_POLL, g_echocallback);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
diff --git a/nuttx/net/uip/uip_icmpsend.c b/nuttx/net/uip/uip_icmpsend.c
new file mode 100644
index 000000000..00c5bb9de
--- /dev/null
+++ b/nuttx/net/uip/uip_icmpsend.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * net/uip/uip_icmpsend.c
+ *
+ * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_icmpsend
+ *
+ * Description:
+ * Setup to send an ICMP packet
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_icmpsend(struct uip_driver_s *dev, uip_ipaddr_t *destaddr)
+{
+ struct uip_icmpip_hdr *picmp = ICMPBUF;
+
+ if (dev->d_sndlen > 0)
+ {
+ /* The total length to send is the size of the application data plus
+ * the IP and ICMP headers (and, eventually, the ethernet header)
+ */
+
+ dev->d_len = dev->d_sndlen + UIP_IPICMPH_LEN;
+
+ /* The total size of the data (for ICMP checksum calculation) includes
+ * the size of the ICMP header
+ */
+
+ dev->d_sndlen += UIP_ICMPH_LEN;
+
+ /* Initialize the IP header. Note that for IPv6, the IP length field
+ * does not include the IPv6 IP header length.
+ */
+
+#ifdef CONFIG_NET_IPv6
+
+ picmp->vtc = 0x60;
+ picmp->tcf = 0x00;
+ picmp->flow = 0x00;
+ picmp->len[0] = (dev->d_sndlen >> 8);
+ picmp->len[1] = (dev->d_sndlen & 0xff);
+ picmp->nexthdr = UIP_PROTO_ICMP;
+ picmp->hoplimit = UIP_TTL;
+
+ uip_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
+ uip_ipaddr_copy(picmp->destipaddr, destaddr);
+
+#else /* CONFIG_NET_IPv6 */
+
+ picmp->vhl = 0x45;
+ picmp->tos = 0;
+ picmp->len[0] = (dev->d_len >> 8);
+ picmp->len[1] = (dev->d_len & 0xff);
+ ++g_ipid;
+ picmp->ipid[0] = g_ipid >> 8;
+ picmp->ipid[1] = g_ipid & 0xff;
+ picmp->ipoffset[0] = UIP_TCPFLAG_DONTFRAG >> 8;
+ picmp->ipoffset[1] = UIP_TCPFLAG_DONTFRAG & 0xff;
+ picmp->ttl = UIP_TTL;
+ picmp->proto = UIP_PROTO_ICMP;
+
+ uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(picmp->destipaddr, destaddr);
+
+ /* Calculate IP checksum. */
+
+ picmp->ipchksum = 0;
+ picmp->ipchksum = ~(uip_ipchksum(dev));
+
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Calculate the ICMP checksum. */
+
+ picmp->icmpchksum = 0;
+ picmp->icmpchksum = ~(uip_icmpchksum(dev, dev->d_sndlen));
+ if (picmp->icmpchksum == 0)
+ {
+ picmp->icmpchksum = 0xffff;
+ }
+
+ nllvdbg("Outgoing ICMP packet length: %d (%d)\n",
+ dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.icmp.sent++;
+ uip_stat.ip.sent++;
+#endif
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
diff --git a/nuttx/net/uip/uip_igmpgroup.c b/nuttx/net/uip/uip_igmpgroup.c
new file mode 100755
index 000000000..220de047e
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpgroup.c
@@ -0,0 +1,391 @@
+/****************************************************************************
+ * net/uip/uip_igmpgroup.c
+ * IGMP group data structure management logic
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/compiler.h>
+
+#include <stdlib.h>
+#include <string.h>
+#include <wdog.h>
+#include <queue.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+# error "IGMP for IPv6 not supported"
+#endif
+
+#ifndef CONFIG_PREALLOC_IGMPGROUPS
+# define CONFIG_PREALLOC_IGMPGROUPS 4
+#endif
+
+/* Debug ********************************************************************/
+
+#undef IGMP_GRPDEBUG /* Define to enable detailed IGMP group debug */
+
+#ifndef CONFIG_NET_IGMP
+# undef IGMP_GRPDEBUG
+#endif
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef IGMP_GRPDEBUG
+# define grpdbg(format, arg...) ndbg(format, ##arg)
+# define grplldbg(format, arg...) nlldbg(format, ##arg)
+# define grpvdbg(format, arg...) nvdbg(format, ##arg)
+# define grpllvdbg(format, arg...) nllvdbg(format, ##arg)
+# else
+# define grpdbg(x...)
+# define grplldbg(x...)
+# define grpvdbg(x...)
+# define grpllvdbg(x...)
+# endif
+#else
+# ifdef IGMP_GRPDEBUG
+# define grpdbg ndbg
+# define grplldbg nlldbg
+# define grpvdbg nvdbg
+# define grpllvdbg nllvdbg
+# else
+# define grpdbg (void)
+# define grplldbg (void)
+# define grpvdbg (void)
+# define grpllvdbg (void)
+# endif
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* malloc() cannot be called from an interrupt handler. To work around this,
+ * a small number of IGMP groups are preallocated just for use in interrupt
+ * handling logic.
+ */
+
+#if CONFIG_PREALLOC_IGMPGROUPS > 0
+static struct igmp_group_s g_preallocgrps[CONFIG_PREALLOC_IGMPGROUPS];
+static FAR sq_queue_t g_freelist;
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_grpalloc
+ *
+ * Description:
+ * Allocate a new group from heap memory.
+ *
+ * Assumptions:
+ * Calls malloc and so cannot be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static inline FAR struct igmp_group_s *uip_grpheapalloc(void)
+{
+ return (FAR struct igmp_group_s *)zalloc(sizeof(struct igmp_group_s));
+}
+
+/****************************************************************************
+ * Name: uip_grpprealloc
+ *
+ * Description:
+ * Allocate a new group from the pre-allocated groups.
+ *
+ * Assumptions:
+ * This function should only be called from an interrupt handler (or with
+ * interrupts disabled).
+ *
+ ****************************************************************************/
+
+#if CONFIG_PREALLOC_IGMPGROUPS > 0
+static inline FAR struct igmp_group_s *uip_grpprealloc(void)
+{
+ FAR struct igmp_group_s *group = (FAR struct igmp_group_s *)sq_remfirst(&g_freelist);
+ if (group)
+ {
+ memset(group, 0, sizeof(struct igmp_group_s));
+ group->flags = IGMP_PREALLOCATED;
+ }
+ return group;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_grpinit
+ *
+ * Description:
+ * One-time initialization of group data.
+ *
+ * Assumptions:
+ * Called only during early boot phases (pre-multitasking).
+ *
+ ****************************************************************************/
+
+void uip_grpinit(void)
+{
+ FAR struct igmp_group_s *group;
+ int i;
+
+ grplldbg("Initializing\n");
+
+#if CONFIG_PREALLOC_IGMPGROUPS > 0
+ for (i = 0; i < CONFIG_PREALLOC_IGMPGROUPS; i++)
+ {
+ group = &g_preallocgrps[i];
+ sq_addfirst((FAR sq_entry_t *)group, &g_freelist);
+ }
+#endif
+}
+
+/****************************************************************************
+ * Name: uip_grpalloc
+ *
+ * Description:
+ * Allocate a new group from heap memory.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
+FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
+{
+ FAR struct igmp_group_s *group;
+ uip_lock_t flags;
+
+ nllvdbg("addr: %08x dev: %p\n", *addr, dev);
+ if (up_interrupt_context())
+ {
+#if CONFIG_PREALLOC_IGMPGROUPS > 0
+ grplldbg("Use a pre-allocated group entry\n");
+ group = uip_grpprealloc();
+#else
+ grplldbg("Cannot allocate from interrupt handler\n");
+ group = NULL;
+#endif
+ }
+ else
+ {
+ grplldbg("Allocate from the heap\n");
+ group = uip_grpheapalloc();
+ }
+ grplldbg("group: %p\n", group);
+
+ /* Check if we succesfully allocated a group structure */
+
+ if (group)
+ {
+ /* Initialize the non-zero elements of the group structure */
+
+ uip_ipaddr_copy(group->grpaddr, *addr);
+ sem_init(&group->sem, 0, 0);
+
+ /* Initialize the group timer (but don't start it yet) */
+
+ group->wdog = wd_create();
+ DEBUGASSERT(group->wdog);
+
+ /* Interrupts must be disabled in order to modify the group list */
+
+ flags = uip_lock();
+
+ /* Add the group structure to the list in the device structure */
+
+ sq_addfirst((FAR sq_entry_t*)group, &dev->grplist);
+ uip_unlock(flags);
+ }
+ return group;
+}
+
+/****************************************************************************
+ * Name: uip_grpfind
+ *
+ * Description:
+ * Find an existing group.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
+FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
+{
+ FAR struct igmp_group_s *group;
+ uip_lock_t flags;
+
+ grplldbg("Searching for addr %08x\n", (int)*addr);
+
+ /* We must disable interrupts because we don't which context we were
+ * called from.
+ */
+
+ flags = uip_lock();
+ for (group = (FAR struct igmp_group_s *)dev->grplist.head;
+ group;
+ group = group->next)
+ {
+ grplldbg("Compare: %08x vs. %08x\n", group->grpaddr, *addr);
+ if (uip_ipaddr_cmp(group->grpaddr, *addr))
+ {
+ grplldbg("Match!\n");
+ break;
+ }
+ }
+ uip_unlock(flags);
+ return group;
+}
+
+/****************************************************************************
+ * Name: uip_grpallocfind
+ *
+ * Description:
+ * Find an existing group. If not found, create a new group for the
+ * address.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
+FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
+{
+ FAR struct igmp_group_s *group = uip_grpfind(dev, addr);
+
+ grplldbg("group: %p addr: %08x\n", group, (int)*addr);
+ if (!group)
+ {
+ group = uip_grpalloc(dev, addr);
+ }
+ grplldbg("group: %p\n", group);
+ return group;
+}
+
+/****************************************************************************
+ * Name: uip_grpfree
+ *
+ * Description:
+ * Release a previously allocated group.
+ *
+ * Assumptions:
+ * May be called from either user or interrupt level processing.
+ *
+ ****************************************************************************/
+
+void uip_grpfree(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
+{
+ uip_lock_t flags;
+
+ grplldbg("Free: %p flags: %02x\n", group, group->flags);
+
+ /* Cancel the wdog */
+
+ flags = uip_lock();
+ wd_cancel(group->wdog);
+
+ /* Remove the group structure from the group list in the device structure */
+
+ sq_rem((FAR sq_entry_t*)group, &dev->grplist);
+
+ /* Destroy the wait semapore */
+
+ (void)sem_destroy(&group->sem);
+
+ /* Destroy the wdog */
+
+ wd_delete(group->wdog);
+
+ /* Then release the group structure resources. Check first if this is one
+ * of the pre-allocated group structures that we will retain in a free list.
+ */
+
+#if CONFIG_PREALLOC_IGMPGROUPS > 0
+ if (IS_PREALLOCATED(group->flags))
+ {
+ grplldbg("Put back on free list\n");
+ sq_addlast((FAR sq_entry_t*)group, &g_freelist);
+ uip_unlock(flags);
+ }
+ else
+#endif
+ {
+ /* No.. deallocate the group structure. Use sched_free() just in case
+ * this function is executing within an interrupt handler.
+ */
+
+ uip_unlock(flags);
+ grplldbg("Call sched_free()\n");
+ sched_free(group);
+ }
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpinit.c b/nuttx/net/uip/uip_igmpinit.c
new file mode 100755
index 000000000..7954e7b3e
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpinit.c
@@ -0,0 +1,122 @@
+/****************************************************************************
+ * net/uip/uip_igmpinit.c
+ * IGMP initialization logic
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+# error "IGMP for IPv6 not supported"
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+uip_ipaddr_t g_allsystems;
+uip_ipaddr_t g_allrouters;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmpinit
+ *
+ * Description:
+ * Perform one-time IGMP initialization.
+ *
+ ****************************************************************************/
+
+void uip_igmpinit(void)
+{
+ nvdbg("IGMP initializing\n");
+
+ uip_ipaddr(g_allrouters, 224, 0, 0, 2);
+ uip_ipaddr(g_allsystems, 224, 0, 0, 1);
+
+ /* Initialize the group allocation logic */
+
+ uip_grpinit();
+}
+
+/****************************************************************************
+ * Name: uip_igmpdevinit
+ *
+ * Description:
+ * Called when a new network device is registered to configure that device
+ * for IGMP support.
+ *
+ ****************************************************************************/
+
+void uip_igmpdevinit(struct uip_driver_s *dev)
+{
+ struct igmp_group_s *group;
+
+ nvdbg("IGMP initializing dev %p\n", dev);
+ DEBUGASSERT(dev->grplist.head == NULL);
+
+ /* Add the all systems address to the group */
+
+ group = uip_grpalloc(dev, &g_allsystems);
+
+ /* Allow the IGMP messages at the MAC level */
+
+ uip_addmcastmac(dev, &g_allrouters);
+ uip_addmcastmac(dev, &g_allsystems);
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpinput.c b/nuttx/net/uip/uip_igmpinput.c
new file mode 100755
index 000000000..5b4fbefa4
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpinput.c
@@ -0,0 +1,280 @@
+/****************************************************************************
+ * net/uip/uip_igminput.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <wdog.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define IGMPBUF ((struct uip_igmphdr_s *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmpinput
+ *
+ * Description:
+ * An IGMP packet has been received.
+ *
+ * ________________
+ * | |
+ * | |
+ * | |
+ * | |
+ * +--------->| Non-Member |<---------+
+ * | | | |
+ * | | | |
+ * | | | |
+ * | |________________| |
+ * | | |
+ * | leave group | join group | leave group
+ * | (stop timer, |(send report, | (send leave
+ * | send leave if | set flag, | if flag set)
+ * | flag set) | start timer) |
+ * ________|________ | ________|________
+ * | |<---------+ | |
+ * | | | |
+ * | |<-------------------| |
+ * | | query received | |
+ * | Delaying Member | (start timer) | Idle Member |
+ * +---->| |------------------->| |
+ * | | | report received | |
+ * | | | (stop timer, | |
+ * | | | clear flag) | |
+ * | |_________________|------------------->|_________________|
+ * | query received | timer expired
+ * | (reset timer if | (send report,
+ * | Max Resp Time | set flag)
+ * | < current timer) |
+ * +-------------------+
+ *
+ * NOTE: This is most likely executing from an interrupt handler.
+ *
+ ****************************************************************************/
+
+void uip_igmpinput(struct uip_driver_s *dev)
+{
+ FAR struct igmp_group_s *group;
+ uip_ipaddr_t destipaddr;
+ uip_ipaddr_t grpaddr;
+ unsigned int ticks;
+
+ nllvdbg("IGMP message: %04x%04x\n", IGMPBUF->destipaddr[1], IGMPBUF->destipaddr[0]);
+
+ /* Verify the message length */
+
+ if (dev->d_len < UIP_LLH_LEN+UIP_IPIGMPH_LEN)
+ {
+ IGMP_STATINCR(uip_stat.igmp.length_errors);
+ nlldbg("Length error\n");
+ return;
+ }
+
+ /* Calculate and check the IGMP checksum */
+
+ if (uip_chksum((uint16_t*)&IGMPBUF->type, UIP_IGMPH_LEN) != 0)
+ {
+ IGMP_STATINCR(uip_stat.igmp.chksum_errors);
+ nlldbg("Checksum error\n");
+ return;
+ }
+
+ /* Find the group (or create a new one) using the incoming IP address*/
+
+ destipaddr = uip_ip4addr_conv(IGMPBUF->destipaddr);
+ group = uip_grpallocfind(dev, &destipaddr);
+ if (!group)
+ {
+ nlldbg("Failed to allocate/find group: %08x\n", destipaddr);
+ return;
+ }
+
+ /* Now handle the message based on the IGMP message type */
+
+ switch (IGMPBUF->type)
+ {
+ case IGMP_MEMBERSHIP_QUERY:
+ /* RFC 2236, 2.2. ax Response Time
+ * "The Max Response Time field is meaningful only in Membership Query
+ * messages, and specifies the maximum allowed time before sending a
+ * responding report in units of 1/10 second. In all other messages, it
+ * is set to zero by the sender and ignored by receivers.
+ */
+
+ /* Check if the query was sent to all systems */
+
+ if (uip_ipaddr_cmp(destipaddr, g_allsystems))
+ {
+ /* Yes... Now check the if this this is a general or a group
+ * specific query.
+ *
+ * RFC 2236, 2.1. Type
+ * There are two sub-types of Membership Query messages:
+ * - General Query, used to learn which groups have members on an
+ * attached network.
+ * - Group-Specific Query, used to learn if a particular group
+ * has any members on an attached network.
+ *
+ * RFC 2236, 2.4. Group Address
+ * "In a Membership Query message, the group address field is
+ * set to zero when sending a General Query, and set to the
+ * group address being queried when sending a Group-Specific
+ * Query."
+ */
+
+ if (IGMPBUF->grpaddr == 0)
+ {
+ FAR struct igmp_group_s *member;
+
+ /* This is the general query */
+
+ nllvdbg("General multicast query\n");
+ if (IGMPBUF->maxresp == 0)
+ {
+ IGMP_STATINCR(uip_stat.igmp.v1_received);
+ IGMPBUF->maxresp = 10;
+
+ nlldbg("V1 not implemented\n");
+ }
+
+ IGMP_STATINCR(uip_stat.igmp.query_received);
+ for (member = (FAR struct igmp_group_s *)dev->grplist.head;
+ member;
+ member = member->next)
+ {
+ /* Skip over the all systems group entry */
+
+ if (!uip_ipaddr_cmp(member->grpaddr, g_allsystems))
+ {
+ ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
+ if (IS_IDLEMEMBER(member->flags) ||
+ uip_igmpcmptimer(member, ticks))
+ {
+ uip_igmpstartticks(member, ticks);
+ CLR_IDLEMEMBER(member->flags);
+ }
+ }
+ }
+ }
+ else /* if (IGMPBUF->grpaddr != 0) */
+ {
+ nllvdbg("Group-specific multicast queury\n");
+
+ /* We first need to re-lookup the group since we used dest last time.
+ * Use the incoming IPaddress!
+ */
+
+ IGMP_STATINCR(uip_stat.igmp.ucast_query);
+ grpaddr = uip_ip4addr_conv(IGMPBUF->grpaddr);
+ group = uip_grpallocfind(dev, &grpaddr);
+ ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
+ if (IS_IDLEMEMBER(group->flags) || uip_igmpcmptimer(group, ticks))
+ {
+ uip_igmpstartticks(group, ticks);
+ CLR_IDLEMEMBER(group->flags);
+ }
+ }
+ }
+
+ /* Not sent to all systems -- Unicast query */
+
+ else if (group->grpaddr != 0)
+ {
+ nllvdbg("Unitcast queury\n");
+ IGMP_STATINCR(uip_stat.igmp.ucast_query);
+
+ nlldbg("Query to a specific group with the group address as destination\n");
+
+ ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
+ if (IS_IDLEMEMBER(group->flags) || uip_igmpcmptimer(group, ticks))
+ {
+ uip_igmpstartticks(group, ticks);
+ CLR_IDLEMEMBER(group->flags);
+ }
+ }
+ break;
+
+ case IGMPv2_MEMBERSHIP_REPORT:
+ {
+ nllvdbg("Membership report\n");
+
+ IGMP_STATINCR(uip_stat.igmp.report_received);
+ if (!IS_IDLEMEMBER(group->flags))
+ {
+ /* This is on a specific group we have already looked up */
+
+ wd_cancel(group->wdog);
+ SET_IDLEMEMBER(group->flags);
+ CLR_LASTREPORT(group->flags);
+ }
+ }
+ break;
+
+ default:
+ {
+ nlldbg("Unexpected msg %02x\n", IGMPBUF->type);
+ }
+ break;
+ }
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpjoin.c b/nuttx/net/uip/uip_igmpjoin.c
new file mode 100755
index 000000000..eb6e88837
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpjoin.c
@@ -0,0 +1,160 @@
+/****************************************************************************
+ * net/uip/uip_igmpjoin.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: igmp_joingroup
+ *
+ * Description:
+ * Add the specified group address to the group.
+ *
+ * RFC 2236, 3. Protocol Description:
+ *
+ * "When a host joins a multicast group, it should immediately transmit
+ * an unsolicited Version 2 Membership Report for that group, in case it
+ * is the first member of that group on the network. To cover the
+ * possibility of the initial Membership Report being lost or damaged,
+ * it is recommended that it be repeated once or twice after short
+ * delays [Unsolicited Report Interval]. (A simple way to accomplish
+ * this is to send the initial Version 2 Membership Report and then act
+ * as if a Group-Specific Query was received for that group, and set a
+ * timer appropriately)."
+ * ________________
+ * | |
+ * | |
+ * | |
+ * | |
+ * +--------->| Non-Member |<---------+
+ * | | | |
+ * | | | |
+ * | | | |
+ * | |________________| |
+ * | | |
+ * | leave group | join group | leave group
+ * | (stop timer, |(send report, | (send leave
+ * | send leave if | set flag, | if flag set)
+ * | flag set) | start timer) |
+ * ________|________ | ________|________
+ * | |<---------+ | |
+ * | | | |
+ * | |<-------------------| |
+ * | | query received | |
+ * | Delaying Member | (start timer) | Idle Member |
+ * +---->| |------------------->| |
+ * | | | report received | |
+ * | | | (stop timer, | |
+ * | | | clear flag) | |
+ * | |_________________|------------------->|_________________|
+ * | query received | timer expired
+ * | (reset timer if | (send report,
+ * | Max Resp Time | set flag)
+ * | < current timer) |
+ * +-------------------+
+ *
+ * Assumptions:
+ * This function cannot be called from interrupt handling logic!
+ *
+ ****************************************************************************/
+
+int igmp_joingroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
+{
+ struct igmp_group_s *group;
+
+ DEBUGASSERT(dev && grpaddr);
+
+ /* Check if a this address is already in the group */
+
+ group = uip_grpfind(dev, &grpaddr->s_addr);
+ if (!group)
+ {
+ /* No... allocate a new entry */
+
+ nvdbg("Join to new group: %08x\n", grpaddr->s_addr);
+ group = uip_grpalloc(dev, &grpaddr->s_addr);
+ IGMP_STATINCR(uip_stat.igmp.joins);
+
+ /* Send the Membership Report */
+
+ IGMP_STATINCR(uip_stat.igmp.report_sched);
+ uip_igmpwaitmsg(group, IGMPv2_MEMBERSHIP_REPORT);
+
+ /* And start the timer at 10*100 msec */
+
+ uip_igmpstarttimer(group, 10);
+
+ /* Add the group (MAC) address to the ether drivers MAC filter list */
+
+ uip_addmcastmac(dev, (FAR uip_ipaddr_t *)&grpaddr->s_addr);
+ return OK;
+ }
+
+ /* Return EEXIST if the address is already a member of the group */
+
+ return -EEXIST;
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpleave.c b/nuttx/net/uip/uip_igmpleave.c
new file mode 100755
index 000000000..7e2a31a19
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpleave.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * net/uip/uip_igmpleave.c
+ *
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <wdog.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: igmp_leavegroup
+ *
+ * Description:
+ * Remove the specified group address to the group.
+ *
+ * RFC 2236, 3. Protocol Description:
+ *
+ * "When a host leaves a multicast group, if it was the last host to
+ * reply to a Query with a Membership Report for that group, it SHOULD
+ * send a Leave Group message to the all-routers multicast group
+ * (224.0.0.2). If it was not the last host to reply to a Query, it MAY
+ * send nothing as there must be another member on the subnet. This is
+ * an optimization to reduce traffic; a host without sufficient storage
+ * to remember whether or not it was the last host to reply MAY always
+ * send a Leave Group message when it leaves a group. Routers SHOULD
+ * accept a Leave Group message addressed to the group being left, in
+ * order to accommodate implementations of an earlier version of this
+ * standard. Leave Group messages are addressed to the all-routers
+ * group because other group members have no need to know that a host
+ * has left the group, but it does no harm to address the message to the
+ * group."
+ *
+ * ________________
+ * | |
+ * | |
+ * | |
+ * | |
+ * +--------->| Non-Member |<---------+
+ * | | | |
+ * | | | |
+ * | | | |
+ * | |________________| |
+ * | | |
+ * | leave group | join group | leave group
+ * | (stop timer, |(send report, | (send leave
+ * | send leave if | set flag, | if flag set)
+ * | flag set) | start timer) |
+ * ________|________ | ________|________
+ * | |<---------+ | |
+ * | | | |
+ * | |<-------------------| |
+ * | | query received | |
+ * | Delaying Member | (start timer) | Idle Member |
+ * +---->| |------------------->| |
+ * | | | report received | |
+ * | | | (stop timer, | |
+ * | | | clear flag) | |
+ * | |_________________|------------------->|_________________|
+ * | query received | timer expired
+ * | (reset timer if | (send report,
+ * | Max Resp Time | set flag)
+ * | < current timer) |
+ * +-------------------+
+ *
+ * Assumptions:
+ * This function cannot be called from interrupt handling logic!
+ *
+ ****************************************************************************/
+
+int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
+{
+ struct igmp_group_s *group;
+ uip_lock_t flags;
+
+ DEBUGASSERT(dev && grpaddr);
+
+ /* Find the entry corresponding to the address leaving the group */
+
+ group = uip_grpfind(dev, &grpaddr->s_addr);
+ ndbg("Leaving group: %p\n", group);
+ if (group)
+ {
+ /* Cancel the timer and discard any queued Membership Reports. Canceling
+ * the timer will prevent any new Membership Reports from being sent;
+ * clearing the flags will discard any pending Membership Reports that
+ * could interfere with the Leave Group.
+ */
+
+ flags = uip_lock();
+ wd_cancel(group->wdog);
+ CLR_SCHEDMSG(group->flags);
+ CLR_WAITMSG(group->flags);
+ uip_unlock(flags);
+
+ IGMP_STATINCR(uip_stat.igmp.leaves);
+
+ /* Send a leave if the flag is set according to the state diagram */
+
+ if (IS_LASTREPORT(group->flags))
+ {
+ ndbg("Schedule Leave Group message\n");
+ IGMP_STATINCR(uip_stat.igmp.leave_sched);
+ uip_igmpwaitmsg(group, IGMP_LEAVE_GROUP);
+ }
+
+ /* Free the group structure (state is now Non-Member */
+
+ uip_grpfree(dev, group);
+
+ /* And remove the group address from the ethernet drivers MAC filter set */
+
+ uip_removemcastmac(dev, (FAR uip_ipaddr_t *)&grpaddr->s_addr);
+ return OK;
+ }
+
+ /* Return ENOENT if the address is not a member of the group */
+
+ nvdbg("Return -ENOENT\n");
+ return -ENOENT;
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpmsg.c b/nuttx/net/uip/uip_igmpmsg.c
new file mode 100755
index 000000000..9ea3daa4e
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpmsg.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * net/uip/uip_igmpmgs.c
+ *
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmpschedmsg
+ *
+ * Description:
+ * Schedule a message to be send at the next driver polling interval.
+ *
+ * Assumptions:
+ * This function may be called in most any context.
+ *
+ ****************************************************************************/
+
+void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid)
+{
+ uip_lock_t flags;
+
+ /* The following should be atomic */
+
+ flags = uip_lock();
+ DEBUGASSERT(!IS_SCHEDMSG(group->flags));
+ group->msgid = msgid;
+ SET_SCHEDMSG(group->flags);
+ uip_unlock(flags);
+}
+
+/****************************************************************************
+ * Name: uip_igmpwaitmsg
+ *
+ * Description:
+ * Schedule a message to be send at the next driver polling interval and
+ * block, waiting for the message to be sent.
+ *
+ * Assumptions:
+ * This function cannot be called from an interrupt handler (if you try it,
+ * uip_lockedwait will assert).
+ *
+ ****************************************************************************/
+
+void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid)
+{
+ uip_lock_t flags;
+
+ /* Schedule to send the message */
+
+ flags = uip_lock();
+ DEBUGASSERT(!IS_WAITMSG(group->flags));
+ SET_WAITMSG(group->flags);
+ uip_igmpschedmsg(group, msgid);
+
+ /* Then wait for the message to be sent */
+
+ while (IS_SCHEDMSG(group->flags))
+ {
+ /* Wait for the semaphore to be posted */
+
+ while (uip_lockedwait(&group->sem) != 0)
+ {
+ /* The only error that should occur from uip_lockedwait() is if
+ * the wait is awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+ }
+
+ /* The message has been sent and we are no longer waiting */
+
+ CLR_WAITMSG(group->flags);
+ uip_unlock(flags);
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmppoll.c b/nuttx/net/uip/uip_igmppoll.c
new file mode 100755
index 000000000..cec2a5e1b
--- /dev/null
+++ b/nuttx/net/uip/uip_igmppoll.c
@@ -0,0 +1,176 @@
+/****************************************************************************
+ * net/uip/uip_igmppoll.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_schedsend
+ *
+ * Description:
+ * Construct the .
+ *
+ * Returned Value:
+ * Returns a non-zero value if a IGP message is sent.
+ *
+ * Assumptions:
+ * This function is called from the driver polling logic... probably within
+ * an interrupt handler.
+ *
+ ****************************************************************************/
+
+static inline void uip_schedsend(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
+{
+ uip_ipaddr_t *dest;
+
+ /* Check what kind of messsage we need to send. There are only two
+ * possibilities:
+ */
+
+ if (group->msgid == IGMPv2_MEMBERSHIP_REPORT)
+ {
+ dest = &group->grpaddr;
+ nllvdbg("Send IGMPv2_MEMBERSHIP_REPORT, dest=%08x flags=%02x\n",
+ *dest, group->flags);
+ IGMP_STATINCR(uip_stat.igmp.report_sched);
+ SET_LASTREPORT(group->flags); /* Remember we were the last to report */
+ }
+ else
+ {
+ DEBUGASSERT(group->msgid == IGMP_LEAVE_GROUP);
+ dest = &g_allrouters;
+ nllvdbg("Send IGMP_LEAVE_GROUP, dest=%08x flags=%02x\n",
+ *dest, group->flags);
+ IGMP_STATINCR(uip_stat.igmp.leave_sched);
+ }
+
+ /* Send the message */
+
+ uip_igmpsend(dev, group, dest);
+
+ /* Indicate that the message has been sent */
+
+ CLR_SCHEDMSG(group->flags);
+ group->msgid = 0;
+
+ /* If there is a thread waiting fore the message to be sent, wake it up */
+
+ if (IS_WAITMSG(group->flags))
+ {
+ nllvdbg("Awakening waiter\n");
+ sem_post(&group->sem);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmppoll
+ *
+ * Description:
+ * Poll the groups associated with the device to see if any IGMP messages
+ * are pending transfer.
+ *
+ * Returned Value:
+ * Returns a non-zero value if a IGP message is sent.
+ *
+ * Assumptions:
+ * This function is called from the driver polling logic... probably within
+ * an interrupt handler.
+ *
+ ****************************************************************************/
+
+void uip_igmppoll(FAR struct uip_driver_s *dev)
+{
+ FAR struct igmp_group_s *group;
+
+ nllvdbg("Entry\n");
+
+ /* Setup the poll operation */
+
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPIGMPH_LEN];
+ dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPIGMPH_LEN];
+
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+
+ /* Check each member of the group */
+
+ for (group = (FAR struct igmp_group_s *)dev->grplist.head; group; group = group->next)
+ {
+ /* Does this member have a pending outgoing message? */
+
+ if (IS_SCHEDMSG(group->flags))
+ {
+ /* Yes, create the IGMP message in the driver buffer */
+
+ uip_schedsend(dev, group);
+
+ /* Mark the message as sent and break out */
+
+ CLR_SCHEDMSG(group->flags);
+ break;
+ }
+ }
+}
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpsend.c b/nuttx/net/uip/uip_igmpsend.c
new file mode 100755
index 000000000..21fc2beb0
--- /dev/null
+++ b/nuttx/net/uip/uip_igmpsend.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * net/uip/uip_igmpsend.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+#include <arpa/inet.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+#include <nuttx/net/uip/uip-ipopt.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Debug */
+
+#undef IGMP_DUMPPKT /* Define to enable packet dump */
+
+#ifndef CONFIG_DEBUG_NET
+# undef IGMP_DUMPPKT
+#endif
+
+#ifdef IGMP_DUMPPKT
+# define igmp_dumppkt(b,n) lib_dumpbuffer("IGMP", (FAR const uint8_t*)(b), (n))
+#else
+# define igmp_dumppkt(b,n)
+#endif
+
+/* Buffer layout */
+
+#define RASIZE (4)
+#define IGMPBUF ((struct uip_igmphdr_s *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static uint16_t uip_igmpchksum(FAR uint8_t *buffer, int buflen)
+{
+ uint16_t sum = uip_chksum((FAR uint16_t*)buffer, buflen);
+ return sum ? sum : 0xffff;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmpsend
+ *
+ * Description:
+ * Sends an IGMP IP packet on a network interface. This function constructs
+ * the IP header and calculates the IP header checksum.
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation.
+ * group - Describes the multicast group member and identifies the message
+ * to be sent.
+ * destipaddr - The IP address of the recipient of the message
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_igmpsend(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group,
+ FAR uip_ipaddr_t *destipaddr)
+{
+ nllvdbg("msgid: %02x destipaddr: %08x\n", group->msgid, (int)*destipaddr);
+
+ /* The total length to send is the size of the IP and IGMP headers and 4
+ * bytes for the ROUTER ALERT (and, eventually, the ethernet header)
+ */
+
+ dev->d_len = UIP_IPIGMPH_LEN;
+
+ /* The total size of the data is the size of the IGMP header */
+
+ dev->d_sndlen = UIP_IGMPH_LEN;
+
+ /* Add the router alert option */
+
+ IGMPBUF->ra[0] = HTONS(IPOPT_RA >> 16);
+ IGMPBUF->ra[1] = HTONS(IPOPT_RA & 0xffff);
+
+ /* Initialize the IPv4 header */
+
+ IGMPBUF->vhl = 0x46; /* 4->IP; 6->24 bytes */
+ IGMPBUF->tos = 0;
+ IGMPBUF->len[0] = (dev->d_len >> 8);
+ IGMPBUF->len[1] = (dev->d_len & 0xff);
+ ++g_ipid;
+ IGMPBUF->ipid[0] = g_ipid >> 8;
+ IGMPBUF->ipid[1] = g_ipid & 0xff;
+ IGMPBUF->ipoffset[0] = UIP_TCPFLAG_DONTFRAG >> 8;
+ IGMPBUF->ipoffset[1] = UIP_TCPFLAG_DONTFRAG & 0xff;
+ IGMPBUF->ttl = IGMP_TTL;
+ IGMPBUF->proto = UIP_PROTO_IGMP;
+
+ uiphdr_ipaddr_copy(IGMPBUF->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(IGMPBUF->destipaddr, destipaddr);
+
+ /* Calculate IP checksum. */
+
+ IGMPBUF->ipchksum = 0;
+ IGMPBUF->ipchksum = ~uip_igmpchksum((FAR uint8_t *)IGMPBUF, UIP_IPH_LEN + RASIZE);
+
+ /* Set up the IGMP message */
+
+ IGMPBUF->type = group->msgid;
+ IGMPBUF->maxresp = 0;
+ uiphdr_ipaddr_copy(IGMPBUF->grpaddr, &group->grpaddr);
+
+ /* Calculate the IGMP checksum. */
+
+ IGMPBUF->chksum = 0;
+ IGMPBUF->chksum = ~uip_igmpchksum(&IGMPBUF->type, UIP_IPIGMPH_LEN);
+
+ IGMP_STATINCR(uip_stat.igmp.poll_send);
+ IGMP_STATINCR(uip_stat.ip.sent);
+
+ nllvdbg("Outgoing IGMP packet length: %d (%d)\n",
+ dev->d_len, (IGMPBUF->len[0] << 8) | IGMPBUF->len[1]);
+ igmp_dumppkt(RA, UIP_IPIGMPH_LEN + RASIZE);
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmptimer.c b/nuttx/net/uip/uip_igmptimer.c
new file mode 100755
index 000000000..27e2f9ff0
--- /dev/null
+++ b/nuttx/net/uip/uip_igmptimer.c
@@ -0,0 +1,257 @@
+/****************************************************************************
+ * net/uip/uip_igmptimer.c
+ *
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/compiler.h>
+
+#include <wdog.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-igmp.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Debug ********************************************************************/
+
+#undef IGMP_GTMRDEBUG /* Define to enable detailed IGMP group debug */
+
+#ifndef CONFIG_NET_IGMP
+# undef IGMP_GTMRDEBUG
+#endif
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef IGMP_GTMRDEBUG
+# define gtmrdbg(format, arg...) ndbg(format, ##arg)
+# define gtmrlldbg(format, arg...) nlldbg(format, ##arg)
+# define gtmrvdbg(format, arg...) nvdbg(format, ##arg)
+# define gtmrllvdbg(format, arg...) nllvdbg(format, ##arg)
+# else
+# define gtmrdbg(x...)
+# define gtmrlldbg(x...)
+# define gtmrvdbg(x...)
+# define gtmrllvdbg(x...)
+# endif
+#else
+# ifdef IGMP_GTMRDEBUG
+# define gtmrdbg ndbg
+# define gtmrlldbg nlldbg
+# define gtmrvdbg nvdbg
+# define gtmrllvdbg nllvdbg
+# else
+# define gtmrdbg (void)
+# define gtmrlldbg (void)
+# define gtmrvdbg (void)
+# define gtmrllvdbg (void)
+# endif
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmptimeout
+ *
+ * Description:
+ * Timeout watchdog handler.
+ *
+ * Assumptions:
+ * This function is called from the wdog timer handler which runs in the
+ * context of the timer interrupt handler.
+ *
+ ****************************************************************************/
+
+static void uip_igmptimeout(int argc, uint32_t arg, ...)
+{
+ FAR struct igmp_group_s *group;
+
+ /* If the state is DELAYING_MEMBER then we send a report for this group */
+
+ nllvdbg("Timeout!\n");
+ group = (FAR struct igmp_group_s *)arg;
+ DEBUGASSERT(argc == 1 && group);
+
+ /* If the group exists and is no an IDLE MEMBER, then it must be a DELAYING
+ * member. Race conditions are avoided because (1) the timer is not started
+ * until after the first IGMPv2_MEMBERSHIP_REPORT during the join, and (2)
+ * the timer is canceled before sending the IGMP_LEAVE_GROUP during a leave.
+ */
+
+ if (!IS_IDLEMEMBER(group->flags))
+ {
+ /* Schedule (and forget) the Membership Report. NOTE:
+ * Since we are executing from a timer interrupt, we cannot wait
+ * for the message to be sent.
+ */
+
+ IGMP_STATINCR(uip_stat.igmp.report_sched);
+ uip_igmpschedmsg(group, IGMPv2_MEMBERSHIP_REPORT);
+
+ /* Also note: The Membership Report is sent at most two times becasue
+ * the timer is not reset here. Hmm.. does this mean that the group
+ * is stranded if both reports were lost? This is consistent with the
+ * RFC that states: "To cover the possibility of the initial Membership
+ * Report being lost or damaged, it is recommended that it be repeated
+ * once or twice after shortdelays [Unsolicited Report Interval]..."
+ */
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_igmpstarttimer
+ *
+ * Description:
+ * Start the IGMP timer.
+ *
+ * Assumptions:
+ * This function may be called from most any context.
+ *
+ ****************************************************************************/
+
+int uip_decisec2tick(int decisecs)
+{
+ /* Convert the deci-second comparison value to clock ticks. The CLK_TCK
+ * value is the number of clock ticks per second; decisecs argument is the
+ * maximum delay in 100's of milliseconds. CLK_TCK/10 is then the number
+ * of clock ticks in 100 milliseconds.
+ */
+
+ return CLK_TCK * decisecs / 10;
+}
+
+/****************************************************************************
+ * Name: uip_igmpstartticks and uip_igmpstarttimer
+ *
+ * Description:
+ * Start the IGMP timer with differing time units (ticks or deciseconds).
+ *
+ * Assumptions:
+ * This function may be called from most any context.
+ *
+ ****************************************************************************/
+
+void uip_igmpstartticks(FAR struct igmp_group_s *group, int ticks)
+{
+ int ret;
+
+ /* Start the timer */
+
+ gtmrlldbg("ticks: %d\n", ticks);
+ ret = wd_start(group->wdog, ticks, uip_igmptimeout, 1, (uint32_t)group);
+ DEBUGASSERT(ret == OK);
+}
+
+void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs)
+{
+ /* Convert the decisec value to system clock ticks and start the timer.
+ * Important!! this should be a random timer from 0 to decisecs
+ */
+
+ gtmrdbg("decisecs: %d\n", decisecs);
+ uip_igmpstartticks(group, uip_decisec2tick(decisecs));
+}
+
+/****************************************************************************
+ * Name: uip_igmpcmptimer
+ *
+ * Description:
+ * Compare the timer remaining on the watching timer to the deci-second
+ * value. If maxticks > ticks-remaining, then (1) cancel the timer (to
+ * avoid race conditions) and return true.
+ *
+ * Assumptions:
+ * This function may be called from most any context. If true is retuend
+ * then the caller must call uip_igmpstartticks() to restart the timer
+ *
+ ****************************************************************************/
+
+bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks)
+{
+ uip_lock_t flags;
+ int remaining;
+
+ /* Disable interrupts so that there is no race condition with the actual
+ * timer expiration.
+ */
+
+ flags = uip_lock();
+
+ /* Get the timer remaining on the watchdog. A time of <= zero means that
+ * the watchdog was never started.
+ */
+
+ remaining = wd_gettime(group->wdog);
+
+ /* A remaining time of zero means that the watchdog was never started
+ * or has already expired. That case should be covered in the following
+ * test as well.
+ */
+
+ gtmrdbg("maxticks: %d remaining: %d\n", maxticks, remaining);
+ if (maxticks > remaining)
+ {
+ /* Cancel the watchdog timer and return true */
+
+ wd_cancel(group->wdog);
+ uip_unlock(flags);
+ return true;
+ }
+
+ uip_unlock(flags);
+ return false;
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_initialize.c b/nuttx/net/uip/uip_initialize.c
new file mode 100644
index 000000000..8839836c4
--- /dev/null
+++ b/nuttx/net/uip/uip_initialize.c
@@ -0,0 +1,155 @@
+/****************************************************************************
+ * net/uip/uip_initialize.c
+ *
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <nuttx/net/uip/uip.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/* IP/TCP/UDP/ICMP statistics for all network interfaces */
+
+#ifdef CONFIG_NET_STATISTICS
+struct uip_stats uip_stat;
+#endif
+
+/* Increasing number used for the IP ID field. */
+
+uint16_t g_ipid;
+
+const uip_ipaddr_t g_alloneaddr =
+#ifdef CONFIG_NET_IPv6
+ {0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff};
+#else
+ 0xffffffff;
+#endif
+
+const uip_ipaddr_t g_allzeroaddr =
+#ifdef CONFIG_NET_IPv6
+ {0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000};
+#else
+ 0x00000000;
+#endif
+
+/* Reassembly timer (units: deci-seconds) */
+
+#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
+uint8_t uip_reasstmr;
+#endif
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_initialize
+ *
+ * Description:
+ * Perform initialization of the uIP layer
+ *
+ * Parameters:
+ * None
+ *
+ * Return:
+ * None
+ *
+ ****************************************************************************/
+
+void uip_initialize(void)
+{
+ /* Initialize the locking facility */
+
+ uip_lockinit();
+
+ /* Initialize callback support */
+
+ uip_callbackinit();
+
+ /* Initialize the listening port structures */
+
+#ifdef CONFIG_NET_TCP
+ uip_listeninit();
+
+ /* Initialize the TCP/IP connection structures */
+
+ uip_tcpinit();
+
+ /* Initialize the TCP/IP read-ahead buffering */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ uip_tcpreadaheadinit();
+#endif
+#endif /* CONFIG_NET_TCP */
+
+ /* Initialize the UDP connection structures */
+
+#ifdef CONFIG_NET_UDP
+ uip_udpinit();
+#endif
+
+ /* Initialize IGMP support */
+
+#ifdef CONFIG_NET_IGMP
+ uip_igmpinit();
+#endif
+}
+#endif /* CONFIG_NET */
+
diff --git a/nuttx/net/uip/uip_input.c b/nuttx/net/uip/uip_input.c
new file mode 100644
index 000000000..878b351a7
--- /dev/null
+++ b/nuttx/net/uip/uip_input.c
@@ -0,0 +1,545 @@
+/****************************************************************************
+ * netuip/uip_input.c
+ * The uIP TCP/IP stack code.
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * uIP is an implementation of the TCP/IP protocol stack intended for
+ * small 8-bit and 16-bit microcontrollers.
+ *
+ * uIP provides the necessary protocols for Internet communication,
+ * with a very small code footprint and RAM requirements - the uIP
+ * code size is on the order of a few kilobytes and RAM usage is on
+ * the order of a few hundred bytes.
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * uIP is a small implementation of the IP, UDP and TCP protocols (as
+ * well as some basic ICMP stuff). The implementation couples the IP,
+ * UDP, TCP and the application layers very tightly. To keep the size
+ * of the compiled code down, this code frequently uses the goto
+ * statement. While it would be possible to break the uip_input()
+ * function into many smaller functions, this would increase the code
+ * size because of the overhead of parameter passing and the fact that
+ * the optimier would not be as efficient.
+ *
+ * The principle is that we have a small buffer, called the d_buf,
+ * in which the device driver puts an incoming packet. The TCP/IP
+ * stack parses the headers in the packet, and calls the
+ * application. If the remote host has sent data to the application,
+ * this data is present in the d_buf and the application read the
+ * data from there. It is up to the application to put this data into
+ * a byte stream if needed. The application will not be fed with data
+ * that is out of sequence.
+ *
+ * If the application whishes to send data to the peer, it should put
+ * its data into the d_buf. The d_appdata pointer points to the
+ * first available byte. The TCP/IP stack will calculate the
+ * checksums, and fill in the necessary header fields and finally send
+ * the packet back to the peer.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <debug.h>
+#include <string.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#ifdef CONFIG_NET_IPv6
+# include "uip_neighbor.h"
+#endif /* CONFIG_NET_IPv6 */
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Macros. */
+
+#define BUF ((struct uip_ip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define FBUF ((struct uip_ip_hdr *)&uip_reassbuf[0])
+
+/* IP fragment re-assembly */
+
+#define IP_MF 0x20
+#define UIP_REASS_BUFSIZE (CONFIG_NET_BUFSIZE - UIP_LLH_LEN)
+#define UIP_REASS_FLAG_LASTFRAG 0x01
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
+static uint8_t uip_reassbuf[UIP_REASS_BUFSIZE];
+static uint8_t uip_reassbitmap[UIP_REASS_BUFSIZE / (8 * 8)];
+static const uint8_t bitmap_bits[8] = {0xff, 0x7f, 0x3f, 0x1f, 0x0f, 0x07, 0x03, 0x01};
+static uint16_t uip_reasslen;
+static uint8_t uip_reassflags;
+#endif /* UIP_REASSEMBLY */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_reass
+ *
+ * Description:
+ * IP fragment reassembly: not well-tested.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
+static uint8_t uip_reass(void)
+{
+ struct uip_ip_hdr *pbuf = BUF;
+ struct uip_ip_hdr *pfbuf = FBUF;
+ uint16_t offset;
+ uint16_t len;
+ uint16_t i;
+
+ /* If uip_reasstmr is zero, no packet is present in the buffer, so we
+ * write the IP header of the fragment into the reassembly
+ * buffer. The timer is updated with the maximum age.
+ */
+
+ if (!uip_reasstmr)
+ {
+ memcpy(uip_reassbuf, &pbuf->vhl, UIP_IPH_LEN);
+ uip_reasstmr = UIP_REASS_MAXAGE;
+ uip_reassflags = 0;
+
+ /* Clear the bitmap. */
+
+ memset(uip_reassbitmap, 0, sizeof(uip_reassbitmap));
+ }
+
+ /* Check if the incoming fragment matches the one currently present
+ * in the reasembly buffer. If so, we proceed with copying the
+ * fragment into the buffer.
+ */
+
+ if (uiphdr_addr_cmp(pbuf->srcipaddr, pfbuf->srcipaddr) &&
+ uiphdr_addr_cmp(pbuf->destipaddr == pfbuf->destipaddr) &&
+ pbuf->g_ipid[0] == pfbuf->g_ipid[0] && pbuf->g_ipid[1] == pfbuf->g_ipid[1])
+ {
+ len = (pbuf->len[0] << 8) + pbuf->len[1] - (pbuf->vhl & 0x0f) * 4;
+ offset = (((pbuf->ipoffset[0] & 0x3f) << 8) + pbuf->ipoffset[1]) * 8;
+
+ /* If the offset or the offset + fragment length overflows the
+ * reassembly buffer, we discard the entire packet.
+ */
+
+ if (offset > UIP_REASS_BUFSIZE || offset + len > UIP_REASS_BUFSIZE)
+ {
+ uip_reasstmr = 0;
+ goto nullreturn;
+ }
+
+ /* Copy the fragment into the reassembly buffer, at the right offset. */
+
+ memcpy(&uip_reassbuf[UIP_IPH_LEN + offset], (char *)pbuf + (int)((pbuf->vhl & 0x0f) * 4), len);
+
+ /* Update the bitmap. */
+
+ if (offset / (8 * 8) == (offset + len) / (8 * 8))
+ {
+ /* If the two endpoints are in the same byte, we only update that byte. */
+
+ uip_reassbitmap[offset / (8 * 8)] |=
+ bitmap_bits[(offset / 8 ) & 7] & ~bitmap_bits[((offset + len) / 8 ) & 7];
+
+ }
+ else
+ {
+ /* If the two endpoints are in different bytes, we update the bytes
+ * in the endpoints and fill the stuff inbetween with 0xff.
+ */
+
+ uip_reassbitmap[offset / (8 * 8)] |= bitmap_bits[(offset / 8 ) & 7];
+ for (i = 1 + offset / (8 * 8); i < (offset + len) / (8 * 8); ++i)
+ {
+ uip_reassbitmap[i] = 0xff;
+ }
+ uip_reassbitmap[(offset + len) / (8 * 8)] |= ~bitmap_bits[((offset + len) / 8 ) & 7];
+ }
+
+ /* If this fragment has the More Fragments flag set to zero, we know that
+ * this is the last fragment, so we can calculate the size of the entire
+ * packet. We also set the IP_REASS_FLAG_LASTFRAG flag to indicate that
+ * we have received the final fragment.
+ */
+
+ if ((pbuf->ipoffset[0] & IP_MF) == 0)
+ {
+ uip_reassflags |= UIP_REASS_FLAG_LASTFRAG;
+ uip_reasslen = offset + len;
+ }
+
+ /* Finally, we check if we have a full packet in the buffer. We do this
+ * by checking if we have the last fragment and if all bits in the bitmap
+ * are set.
+ */
+
+ if (uip_reassflags & UIP_REASS_FLAG_LASTFRAG)
+ {
+ /* Check all bytes up to and including all but the last byte in
+ * the bitmap.
+ */
+
+ for (i = 0; i < uip_reasslen / (8 * 8) - 1; ++i)
+ {
+ if (uip_reassbitmap[i] != 0xff)
+ {
+ goto nullreturn;
+ }
+ }
+
+ /* Check the last byte in the bitmap. It should contain just the
+ * right amount of bits.
+ */
+
+ if (uip_reassbitmap[uip_reasslen / (8 * 8)] != (uint8_t)~bitmap_bits[uip_reasslen / 8 & 7])
+ {
+ goto nullreturn;
+ }
+
+ /* If we have come this far, we have a full packet in the buffer,
+ * so we allocate a pbuf and copy the packet into it. We also reset
+ * the timer.
+ */
+
+ uip_reasstmr = 0;
+ memcpy(pbuf, pfbuf, uip_reasslen);
+
+ /* Pretend to be a "normal" (i.e., not fragmented) IP packet from
+ * now on.
+ */
+
+ pbuf->ipoffset[0] = pbuf->ipoffset[1] = 0;
+ pbuf->len[0] = uip_reasslen >> 8;
+ pbuf->len[1] = uip_reasslen & 0xff;
+ pbuf->ipchksum = 0;
+ pbuf->ipchksum = ~(uip_ipchksum(dev));
+
+ return uip_reasslen;
+ }
+ }
+
+nullreturn:
+ return 0;
+}
+#endif /* UIP_REASSEMBLY */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_input
+ *
+ * Description:
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void uip_input(struct uip_driver_s *dev)
+{
+ struct uip_ip_hdr *pbuf = BUF;
+ uint16_t iplen;
+
+ /* This is where the input processing starts. */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.recv++;
+#endif
+
+ /* Start of IP input header processing code. */
+
+#ifdef CONFIG_NET_IPv6
+ /* Check validity of the IP header. */
+
+ if ((pbuf->vtc & 0xf0) != 0x60)
+ {
+ /* IP version and header length. */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+ uip_stat.ip.vhlerr++;
+#endif
+ nlldbg("Invalid IPv6 version: %d\n", pbuf->vtc >> 4);
+ goto drop;
+ }
+#else /* CONFIG_NET_IPv6 */
+ /* Check validity of the IP header. */
+
+ if (pbuf->vhl != 0x45)
+ {
+ /* IP version and header length. */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+ uip_stat.ip.vhlerr++;
+#endif
+ nlldbg("Invalid IP version or header length: %02x\n", pbuf->vhl);
+ goto drop;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Check the size of the packet. If the size reported to us in d_len is
+ * smaller the size reported in the IP header, we assume that the packet
+ * has been corrupted in transit. If the size of d_len is larger than the
+ * size reported in the IP packet header, the packet has been padded and
+ * we set d_len to the correct value.
+ */
+
+#ifdef CONFIG_NET_IPv6
+ /* The length reported in the IPv6 header is the length of the payload
+ * that follows the header. However, uIP uses the d_len variable for
+ * holding the size of the entire packet, including the IP header. For
+ * IPv4 this is not a problem as the length field in the IPv4 header
+ * contains the length of the entire packet. But for IPv6 we need to add
+ * the size of the IPv6 header (40 bytes).
+ */
+
+ iplen = (pbuf->len[0] << 8) + pbuf->len[1] + UIP_IPH_LEN;
+#else
+ iplen = (pbuf->len[0] << 8) + pbuf->len[1];
+#endif /* CONFIG_NET_IPv6 */
+
+ if (iplen <= dev->d_len)
+ {
+ dev->d_len = iplen;
+ }
+ else
+ {
+ nlldbg("IP packet shorter than length in IP header\n");
+ goto drop;
+ }
+
+#ifndef CONFIG_NET_IPv6
+ /* Check the fragment flag. */
+
+ if ((pbuf->ipoffset[0] & 0x3f) != 0 || pbuf->ipoffset[1] != 0)
+ {
+#if UIP_REASSEMBLY
+ dev->d_len = uip_reass();
+ if (dev->d_len == 0)
+ {
+ goto drop;
+ }
+#else /* UIP_REASSEMBLY */
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+ uip_stat.ip.fragerr++;
+#endif
+ nlldbg("IP fragment dropped\n");
+ goto drop;
+#endif /* UIP_REASSEMBLY */
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+ /* If IP broadcast support is configured, we check for a broadcast
+ * UDP packet, which may be destined to us (even if there is no IP
+ * address yet assigned to the device as is the case when we are
+ * negotiating over DHCP for an address).
+ */
+
+#if defined(CONFIG_NET_BROADCAST) && defined(CONFIG_NET_UDP)
+ if (pbuf->proto == UIP_PROTO_UDP &&
+#ifndef CONFIG_NET_IPv6
+ uip_ipaddr_cmp(uip_ip4addr_conv(pbuf->destipaddr), g_alloneaddr))
+#else
+ uip_ipaddr_cmp(pbuf->destipaddr, g_alloneaddr))
+#endif
+ {
+ uip_udpinput(dev);
+ return;
+ }
+
+ /* In most other cases, the device must be assigned a non-zero IP
+ * address. Another exception is when CONFIG_NET_PINGADDRCONF is
+ * enabled...
+ */
+
+ else
+#endif
+#ifdef CONFIG_NET_ICMP
+ if (uip_ipaddr_cmp(dev->d_ipaddr, g_allzeroaddr))
+ {
+ /* If we are configured to use ping IP address configuration and
+ * hasn't been assigned an IP address yet, we accept all ICMP
+ * packets.
+ */
+
+#if defined(CONFIG_NET_PINGADDRCONF) && !defined(CONFIG_NET_IPv6)
+ if (pbuf->proto == UIP_PROTO_ICMP)
+ {
+ nlldbg("Possible ping config packet received\n");
+ uip_icmpinput(dev);
+ goto done;
+ }
+ else
+#endif
+ {
+ nlldbg("No IP address assigned\n");
+ goto drop;
+ }
+ }
+
+ /* Check if the packet is destined for out IP address */
+ else
+#endif
+ {
+ /* Check if the packet is destined for our IP address. */
+#ifndef CONFIG_NET_IPv6
+ if (!uip_ipaddr_cmp(uip_ip4addr_conv(pbuf->destipaddr), dev->d_ipaddr))
+ {
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+#endif
+ goto drop;
+ }
+#else /* CONFIG_NET_IPv6 */
+ /* For IPv6, packet reception is a little trickier as we need to
+ * make sure that we listen to certain multicast addresses (all
+ * hosts multicast address, and the solicited-node multicast
+ * address) as well. However, we will cheat here and accept all
+ * multicast packets that are sent to the ff02::/16 addresses.
+ */
+
+ if (!uip_ipaddr_cmp(pbuf->destipaddr, dev->d_ipaddr) &&
+ pbuf->destipaddr[0] != 0xff02)
+ {
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+#endif
+ goto drop;
+ }
+#endif /* CONFIG_NET_IPv6 */
+ }
+
+#ifndef CONFIG_NET_IPv6
+ if (uip_ipchksum(dev) != 0xffff)
+ {
+ /* Compute and check the IP header checksum. */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+ uip_stat.ip.chkerr++;
+#endif
+ nlldbg("Bad IP checksum\n");
+ goto drop;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Everything looks good so far. Now process the incoming packet
+ * according to the protocol.
+ */
+
+ switch (pbuf->proto)
+ {
+#ifdef CONFIG_NET_TCP
+ case UIP_PROTO_TCP: /* TCP input */
+ uip_tcpinput(dev);
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case UIP_PROTO_UDP: /* UDP input */
+ uip_udpinput(dev);
+ break;
+#endif
+
+ /* Check for ICMP input */
+
+#ifdef CONFIG_NET_ICMP
+#ifndef CONFIG_NET_IPv6
+ case UIP_PROTO_ICMP: /* ICMP input */
+#else
+ case UIP_PROTO_ICMP6: /* ICMP6 input */
+#endif
+ uip_icmpinput(dev);
+ break;
+#endif
+
+ /* Check for ICMP input */
+
+#ifdef CONFIG_NET_IGMP
+#ifndef CONFIG_NET_IPv6
+ case UIP_PROTO_IGMP: /* IGMP input */
+ uip_igmpinput(dev);
+ break;
+#endif
+#endif
+
+ default: /* Unrecognized/unsupported protocol */
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.ip.drop++;
+ uip_stat.ip.protoerr++;
+#endif
+
+ nlldbg("Unrecognized IP protocol\n");
+ goto drop;
+ }
+
+ /* Return and let the caller do any actual transmission. */
+
+ return;
+
+drop:
+ dev->d_len = 0;
+}
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_internal.h b/nuttx/net/uip/uip_internal.h
new file mode 100644
index 000000000..eee99a222
--- /dev/null
+++ b/nuttx/net/uip/uip_internal.h
@@ -0,0 +1,272 @@
+/****************************************************************************
+ * net/uip/uip_internal.h
+ *
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This logic was leveraged from uIP which also has a BSD-style license:
+ *
+ * Author Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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 __UIP_INTERNAL_H
+#define __UIP_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <errno.h>
+#include <arch/irq.h>
+#include <nuttx/net/uip/uip.h>
+
+/****************************************************************************
+ * Public Macro Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+extern const uip_ipaddr_t g_alloneaddr;
+extern const uip_ipaddr_t g_allzeroaddr;
+
+/* Increasing number used for the IP ID field. */
+
+extern uint16_t g_ipid;
+
+/* Reassembly timer (units: deci-seconds) */
+
+#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
+extern uint8_t uip_reasstmr;
+#endif
+
+/* List of applications waiting for ICMP ECHO REPLY */
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+extern struct uip_callback_s *g_echocallback;
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Defined in uip_callback.c ************************************************/
+
+EXTERN void uip_callbackinit(void);
+EXTERN FAR struct uip_callback_s *uip_callbackalloc(struct uip_callback_s **list);
+EXTERN void uip_callbackfree(FAR struct uip_callback_s *cb, struct uip_callback_s **list);
+EXTERN uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
+ uint16_t flags, FAR struct uip_callback_s *list);
+
+#ifdef CONFIG_NET_TCP
+/* Defined in uip_tcpconn.c *************************************************/
+
+EXTERN void uip_tcpinit(void);
+EXTERN struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf);
+EXTERN struct uip_conn *uip_nexttcpconn(struct uip_conn *conn);
+EXTERN struct uip_conn *uip_tcplistener(uint16_t portno);
+EXTERN struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf);
+
+/* Defined in uip_tcpseqno.c ************************************************/
+
+EXTERN void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value);
+EXTERN uint32_t uip_tcpgetsequence(FAR uint8_t *seqno);
+EXTERN uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len);
+EXTERN void uip_tcpinitsequence(FAR uint8_t *seqno);
+EXTERN void uip_tcpnextsequence(void);
+
+/* Defined in uip_tcppoll.c *************************************************/
+
+EXTERN void uip_tcppoll(struct uip_driver_s *dev, struct uip_conn *conn);
+
+/* Defined in uip_udptimer.c ************************************************/
+
+EXTERN void uip_tcptimer(struct uip_driver_s *dev, struct uip_conn *conn, int hsec);
+
+/* Defined in uip_listen.c **************************************************/
+
+EXTERN void uip_listeninit(void);
+EXTERN bool uip_islistener(uint16_t port);
+EXTERN int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn, uint16_t portno);
+
+/* Defined in uip_tcpsend.c *************************************************/
+
+EXTERN void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t flags, uint16_t len);
+EXTERN void uip_tcpreset(struct uip_driver_s *dev);
+EXTERN void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint8_t ack);
+
+/* Defined in uip_tcpappsend.c **********************************************/
+
+EXTERN void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t result);
+EXTERN void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t result);
+
+/* Defined in uip_tcpinput.c ************************************************/
+
+EXTERN void uip_tcpinput(struct uip_driver_s *dev);
+
+/* Defined in uip_tcpcallback.c *********************************************/
+
+EXTERN uint16_t uip_tcpcallback(FAR struct uip_driver_s *dev,
+ FAR struct uip_conn *conn, uint16_t flags);
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+EXTERN uint16_t uip_datahandler(FAR struct uip_conn *conn,
+ FAR uint8_t *buffer, uint16_t nbytes);
+#endif
+
+/* Defined in uip_tcpreadahead.c ********************************************/
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+EXTERN void uip_tcpreadaheadinit(void);
+EXTERN struct uip_readahead_s *uip_tcpreadaheadalloc(void);
+EXTERN void uip_tcpreadaheadrelease(struct uip_readahead_s *buf);
+#endif /* CONFIG_NET_NTCP_READAHEAD_BUFFERS */
+
+#endif /* CONFIG_NET_TCP */
+
+#ifdef CONFIG_NET_UDP
+/* Defined in uip_udpconn.c *************************************************/
+
+EXTERN void uip_udpinit(void);
+EXTERN struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf);
+EXTERN struct uip_udp_conn *uip_nextudpconn(struct uip_udp_conn *conn);
+
+/* Defined in uip_udppoll.c *************************************************/
+
+EXTERN void uip_udppoll(struct uip_driver_s *dev, struct uip_udp_conn *conn);
+
+/* Defined in uip_udpsend.c *************************************************/
+
+EXTERN void uip_udpsend(struct uip_driver_s *dev, struct uip_udp_conn *conn);
+
+/* Defined in uip_udpinput.c ************************************************/
+
+EXTERN void uip_udpinput(struct uip_driver_s *dev);
+
+/* Defined in uip_udpcallback.c *********************************************/
+
+EXTERN void uip_udpcallback(struct uip_driver_s *dev,
+ struct uip_udp_conn *conn, uint16_t flags);
+#endif /* CONFIG_NET_UDP */
+
+#ifdef CONFIG_NET_ICMP
+/* Defined in uip_icmpinput.c ***********************************************/
+
+EXTERN void uip_icmpinput(struct uip_driver_s *dev);
+
+#ifdef CONFIG_NET_ICMP_PING
+/* Defined in uip_icmpoll.c *************************************************/
+
+EXTERN void uip_icmppoll(struct uip_driver_s *dev);
+
+/* Defined in uip_icmsend.c *************************************************/
+
+EXTERN void uip_icmpsend(struct uip_driver_s *dev, uip_ipaddr_t *destaddr);
+
+#endif /* CONFIG_NET_ICMP_PING */
+#endif /* CONFIG_NET_ICMP */
+
+#ifdef CONFIG_NET_IGMP
+/* Defined in uip_igmpinit.c ************************************************/
+
+EXTERN void uip_igmpinit(void);
+
+/* Defined in uip_igmpinput.c ***********************************************/
+
+EXTERN void uip_igmpinput(struct uip_driver_s *dev);
+
+/* Defined in uip_igmpgroup.c ***********************************************/
+
+EXTERN void uip_grpinit(void);
+EXTERN FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr);
+EXTERN FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr);
+EXTERN FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr);
+EXTERN void uip_grpfree(FAR struct uip_driver_s *dev,
+ FAR struct igmp_group_s *group);
+
+/* Defined in uip_igmpmsg.c **************************************************/
+
+EXTERN void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid);
+EXTERN void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid);
+
+/* Defined in uip_igmppoll.c *************************************************/
+
+EXTERN void uip_igmppoll(FAR struct uip_driver_s *dev);
+
+/* Defined in up_igmpsend.c **************************************************/
+
+EXTERN void uip_igmpsend(FAR struct uip_driver_s *dev,
+ FAR struct igmp_group_s *group,
+ FAR uip_ipaddr_t *dest);
+
+/* Defined in uip_igmptimer.c ************************************************/
+
+EXTERN int uip_decisec2tick(int decisecs);
+EXTERN void uip_igmpstartticks(FAR struct igmp_group_s *group, int ticks);
+EXTERN void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs);
+EXTERN bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks);
+
+/* Defined in uip_mcastmac ***************************************************/
+
+EXTERN void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
+EXTERN void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
+
+#endif /* CONFIG_NET_IGMP */
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_NET */
+#endif /* __UIP_INTERNAL_H */
diff --git a/nuttx/net/uip/uip_listen.c b/nuttx/net/uip/uip_listen.c
new file mode 100644
index 000000000..5f867fef2
--- /dev/null
+++ b/nuttx/net/uip/uip_listen.c
@@ -0,0 +1,288 @@
+/****************************************************************************
+ * net/uip/uip_listen.c
+ *
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * A direct leverage of logic from uIP which also has b BSD style license
+ *
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The uip_listenports list all currently listening ports. */
+
+static struct uip_conn *uip_listenports[CONFIG_NET_MAX_LISTENPORTS];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_findlistener
+ *
+ * Description:
+ * Return the connection listener for connections on this port (if any)
+ *
+ * Assumptions:
+ * Called at interrupt level
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_findlistener(uint16_t portno)
+{
+ int ndx;
+
+ /* Examine each connection structure in each slot of the listener list */
+
+ for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
+ {
+ /* Is this slot assigned? If so, does the connection have the same
+ * local port number?
+ */
+
+ struct uip_conn *conn = uip_listenports[ndx];
+ if (conn && conn->lport == portno)
+ {
+ /* Yes.. we found a listener on this port */
+
+ return conn;
+ }
+ }
+
+ /* No listener for this port */
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_listeninit
+ *
+ * Description:
+ * Setup the listening data structures
+ *
+ * Assumptions:
+ * Called early in the inialization phase while the system is still
+ * single-threaded.
+ *
+ ****************************************************************************/
+
+void uip_listeninit(void)
+{
+ int ndx;
+ for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
+ {
+ uip_listenports[ndx] = NULL;
+ }
+}
+
+/****************************************************************************
+ * Function: uip_unlisten
+ *
+ * Description:
+ * Stop listening to the port bound to the specified TCP connection
+ *
+ * Assumptions:
+ * Called from normal user code.
+ *
+ ****************************************************************************/
+
+int uip_unlisten(struct uip_conn *conn)
+{
+ uip_lock_t flags;
+ int ndx;
+ int ret = -EINVAL;
+
+ flags = uip_lock();
+ for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
+ {
+ if (uip_listenports[ndx] == conn)
+ {
+ uip_listenports[ndx] = NULL;
+ ret = OK;
+ break;
+ }
+ }
+
+ uip_unlock(flags);
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_listen
+ *
+ * Description:
+ * Start listening to the port bound to the specified TCP connection
+ *
+ * Assumptions:
+ * Called from normal user code.
+ *
+ ****************************************************************************/
+
+int uip_listen(struct uip_conn *conn)
+{
+ uip_lock_t flags;
+ int ndx;
+ int ret;
+
+ /* This must be done with interrupts disabled because the listener table
+ * is accessed from interrupt level as well.
+ */
+
+ flags = uip_lock();
+
+ /* First, check if there is already a socket listening on this port */
+
+ if (uip_islistener(conn->lport))
+ {
+ /* Yes, then we must refuse this request */
+
+ ret = -EADDRINUSE;
+ }
+ else
+ {
+ /* Otherwise, save a reference to the connection structure in the
+ * "listener" list.
+ */
+
+ ret = -ENOBUFS; /* Assume failure */
+
+ /* Search all slots until an available slot is found */
+
+ for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
+ {
+ /* Is the next slot available? */
+
+ if (!uip_listenports[ndx])
+ {
+ /* Yes.. we found it */
+
+ uip_listenports[ndx] = conn;
+ ret = OK;
+ break;
+ }
+ }
+ }
+
+ uip_unlock(flags);
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_islistener
+ *
+ * Description:
+ * Return true is there is a listener for the specified port
+ *
+ * Assumptions:
+ * Called at interrupt level
+ *
+ ****************************************************************************/
+
+bool uip_islistener(uint16_t portno)
+{
+ return uip_findlistener(portno) != NULL;
+}
+
+/****************************************************************************
+ * Function: uip_accept
+ *
+ * Description:
+ * Accept the new connection for the specified listening port.
+ *
+ * Assumptions:
+ * Called at interrupt level
+ *
+ ****************************************************************************/
+
+int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t portno)
+{
+ struct uip_conn *listener;
+ int ret = ERROR;
+
+ /* The interrupt logic has already allocated and initialized a TCP
+ * connection -- now check there if is an application in place to accept the
+ * connection.
+ */
+
+ listener = uip_findlistener(portno);
+ if (listener)
+ {
+ /* Yes, there is a listener. Is it accepting connections now? */
+
+ if (listener->accept)
+ {
+ /* Yes.. accept the connection */
+
+ ret = listener->accept(listener, conn);
+ }
+#ifdef CONFIG_NET_TCPBACKLOG
+ else
+ {
+ /* Add the connection to the backlog and notify any threads that
+ * may be waiting on poll()/select() that the connection is available.
+ */
+
+ ret = uip_backlogadd(listener, conn);
+ if (ret == OK)
+ {
+ (void)uip_tcpcallback(dev, listener, UIP_BACKLOG);
+ }
+ }
+#endif
+ }
+ return ret;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_lock.c b/nuttx/net/uip/uip_lock.c
new file mode 100644
index 000000000..0e770cef7
--- /dev/null
+++ b/nuttx/net/uip/uip_lock.c
@@ -0,0 +1,218 @@
+/****************************************************************************
+ * net/uip/uip_lock.c
+ *
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/net/uip/uip.h>
+
+#if defined(CONFIG_NET) && defined(CONFIG_NET_NOINTS)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define NO_HOLDER (pid_t)-1
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static sem_t g_uipsem;
+static pid_t g_holder = NO_HOLDER;
+static unsigned int g_count = 0;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_takesem
+ *
+ * Description:
+ * Take the semaphore
+ *
+ ****************************************************************************/
+
+static void uip_takesem(void)
+{
+ while (sem_wait(&g_uipsem) != 0)
+ {
+ /* The only case that an error should occur here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_lockinit
+ *
+ * Description:
+ * Initialize the locking facility
+ *
+ ****************************************************************************/
+
+void uip_lockinit(void)
+{
+ sem_init(&g_uipsem, 0, 1);
+}
+
+/****************************************************************************
+ * Function: uip_lock
+ *
+ * Description:
+ * Take the lock
+ *
+ ****************************************************************************/
+
+uip_lock_t uip_lock(void)
+{
+ pid_t me = getpid();
+
+ /* Does this thread already hold the semaphore? */
+
+ if (g_holder == me)
+ {
+ /* Yes.. just increment the reference count */
+
+ g_count++;
+ }
+ else
+ {
+ /* No.. take the semaphore (perhaps waiting) */
+
+ uip_takesem();
+
+ /* Now this thread holds the semaphore */
+
+ g_holder = me;
+ g_count = 1;
+ }
+
+ return 0;
+}
+
+/****************************************************************************
+ * Function: uip_unlock
+ *
+ * Description:
+ * Release the lock.
+ *
+ ****************************************************************************/
+
+void uip_unlock(uip_lock_t flags)
+{
+ DEBUGASSERT(g_holder == getpid() && g_count > 0);
+
+ /* If the count would go to zero, then release the semaphore */
+
+ if (g_count == 1)
+ {
+ /* We no longer hold the semaphore */
+
+ g_holder = NO_HOLDER;
+ g_count = 0;
+ sem_post(&g_uipsem);
+ }
+ else
+ {
+ /* We still hold the semaphore. Just decrement the count */
+
+ g_count--;
+ }
+}
+
+/****************************************************************************
+ * Function: uip_lockedwait
+ *
+ * Description:
+ * Atomically wait for sem while temporarily releasing g_uipsem.
+ *
+ ****************************************************************************/
+
+int uip_lockedwait(sem_t *sem)
+{
+ pid_t me = getpid();
+ unsigned int count;
+ irqstate_t flags;
+ int ret;
+
+ flags = irqsave(); /* No interrupts */
+ sched_lock(); /* No context switches */
+ if (g_holder == me)
+ {
+ /* Release the uIP semaphore, remembering the count */
+
+ count = g_count;
+ g_holder = NO_HOLDER;
+ g_count = 0;
+ sem_post(&g_uipsem);
+
+ /* Now take the semaphore */
+
+ ret = sem_wait(sem);
+
+ /* Recover the uIP semaphore at the proper count */
+
+ uip_takesem();
+ g_holder = me;
+ g_count = count;
+ }
+ else
+ {
+ ret = sem_wait(sem);
+ }
+
+ sched_unlock();
+ irqrestore(flags);
+ return ret;
+ }
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_mcastmac.c b/nuttx/net/uip/uip_mcastmac.c
new file mode 100755
index 000000000..7795becab
--- /dev/null
+++ b/nuttx/net/uip/uip_mcastmac.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * net/uip/uip_mcastmac.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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 of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_mcastmac
+ *
+ * Description:
+ * Given an IP address (in network order), create a IGMP multicast MAC
+ * address.
+ *
+ ****************************************************************************/
+
+static void uip_mcastmac(uip_ipaddr_t *ip, FAR uint8_t *mac)
+{
+ /* This mapping is from the IETF IN RFC 1700 */
+
+ mac[0] = 0x01;
+ mac[1] = 0x00;
+ mac[2] = 0x5e;
+ mac[3] = ip4_addr2(*ip) & 0x7f;
+ mac[4] = ip4_addr3(*ip);
+ mac[5] = ip4_addr4(*ip);
+
+ nvdbg("IP: %08x -> MAC: %02x%02x%02x%02x%02x%02x\n",
+ *ip, mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_addmcastmac
+ *
+ * Description:
+ * Add an IGMP MAC address to the device's MAC filter table.
+ *
+ ****************************************************************************/
+
+void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
+{
+ uint8_t mcastmac[6];
+
+ nvdbg("Adding: IP %08x\n", *ip);
+ if (dev->d_addmac)
+ {
+ uip_mcastmac(ip, mcastmac);
+ dev->d_addmac(dev, mcastmac);
+ }
+}
+
+/****************************************************************************
+ * Name: uip_removemcastmac
+ *
+ * Description:
+ * Remove an IGMP MAC address from the device's MAC filter table.
+ *
+ ****************************************************************************/
+
+void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
+{
+ uint8_t mcastmac[6];
+
+ nvdbg("Removing: IP %08x\n", *ip);
+ if (dev->d_rmmac)
+ {
+ uip_mcastmac(ip, mcastmac);
+ dev->d_rmmac(dev, mcastmac);
+ }
+}
+
+#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_neighbor.c b/nuttx/net/uip/uip_neighbor.c
new file mode 100644
index 000000000..82fb9a845
--- /dev/null
+++ b/nuttx/net/uip/uip_neighbor.c
@@ -0,0 +1,162 @@
+/*
+ * uip_neighbor.c
+ * Database of link-local neighbors, used by IPv6 code and to be used by
+ * a future ARP code rewrite.
+ *
+ * Author: Adam Dunkels <adam@sics.se>
+ * Copyright (c) 2006, Swedish Institute of Computer Science.
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 <string.h>
+#include <debug.h>
+
+#include "uip_neighbor.h"
+
+#define MAX_TIME 128
+
+#ifdef UIP_NEIGHBOR_CONF_ENTRIES
+#define ENTRIES UIP_NEIGHBOR_CONF_ENTRIES
+#else /* UIP_NEIGHBOR_CONF_ENTRIES */
+#define ENTRIES 8
+#endif /* UIP_NEIGHBOR_CONF_ENTRIES */
+
+struct neighbor_entry
+{
+ uip_ipaddr_t ipaddr;
+ struct uip_neighbor_addr addr;
+ uint8_t time;
+};
+static struct neighbor_entry entries[ENTRIES];
+
+void uip_neighbor_init(void)
+{
+ int i;
+
+ for(i = 0; i < ENTRIES; ++i)
+ {
+ entries[i].time = MAX_TIME;
+ }
+}
+
+void uip_neighbor_periodic(void)
+{
+ int i;
+
+ for(i = 0; i < ENTRIES; ++i)
+ {
+ if (entries[i].time < MAX_TIME)
+ {
+ entries[i].time++;
+ }
+ }
+}
+
+void uip_neighbor_add(uip_ipaddr_t ipaddr, struct uip_neighbor_addr *addr)
+{
+ uint8_t oldest_time;
+ int oldest;
+ int i;
+
+ nlldbg("Add neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ addr->addr.ether_addr_octet[0], addr->addr.ether_addr_octet[1],
+ addr->addr.ether_addr_octet[2], addr->addr.ether_addr_octet[3],
+ addr->addr.ether_addr_octet[4], addr->addr.ether_addr_octet[5]);
+
+ /* Find the first unused entry or the oldest used entry. */
+
+ oldest_time = 0;
+ oldest = 0;
+ for (i = 0; i < ENTRIES; ++i)
+ {
+ if (entries[i].time == MAX_TIME)
+ {
+ oldest = i;
+ break;
+ }
+ if (uip_ipaddr_cmp(entries[i].ipaddr, addr))
+ {
+ oldest = i;
+ break;
+ }
+ if (entries[i].time > oldest_time)
+ {
+ oldest = i;
+ oldest_time = entries[i].time;
+ }
+ }
+
+ /* Use the oldest or first free entry (either pointed to by the
+ * "oldest" variable).
+ */
+
+ entries[oldest].time = 0;
+ uip_ipaddr_copy(entries[oldest].ipaddr, ipaddr);
+ memcpy(&entries[oldest].addr, addr, sizeof(struct uip_neighbor_addr));
+}
+
+static struct neighbor_entry *find_entry(uip_ipaddr_t ipaddr)
+{
+ int i;
+
+ for(i = 0; i < ENTRIES; ++i)
+ {
+ if (uip_ipaddr_cmp(entries[i].ipaddr, ipaddr))
+ {
+ return &entries[i];
+ }
+ }
+ return NULL;
+}
+
+void uip_neighbor_update(uip_ipaddr_t ipaddr)
+{
+ struct neighbor_entry *e;
+
+ e = find_entry(ipaddr);
+ if (e != NULL)
+ {
+ e->time = 0;
+ }
+}
+
+struct uip_neighbor_addr *uip_neighbor_lookup(uip_ipaddr_t ipaddr)
+{
+ struct neighbor_entry *e;
+
+ e = find_entry(ipaddr);
+ if (e != NULL)
+ {
+ nlldbg("Lookup neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ e->addr.addr.ether_addr_octet[0], e->addr.addr.ether_addr_octet[1],
+ e->addr.addr.ether_addr_octet[2], e->addr.addr.ether_addr_octet[3],
+ e->addr.addr.ether_addr_octet[4], e->addr.addr.ether_addr_octet[5]);
+
+ return &e->addr;
+ }
+ return NULL;
+}
diff --git a/nuttx/net/uip/uip_neighbor.h b/nuttx/net/uip/uip_neighbor.h
new file mode 100644
index 000000000..eac08f938
--- /dev/null
+++ b/nuttx/net/uip/uip_neighbor.h
@@ -0,0 +1,61 @@
+/* net/uip/uip_neighbor.h
+ * Header file for database of link-local neighbors, used by IPv6 code and
+ * to be used by future ARP code.
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * A direct leverage of logic from uIP which also has b BSD style license
+ *
+ * Author: Adam Dunkels <adam@sics.se>
+ * Copyright (c) 2006, Swedish Institute of Computer Science.
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 __UIP_NEIGHBOR_H__
+#define __UIP_NEIGHBOR_H__
+
+#include <stdint.h>
+#include <nuttx/net/uip/uip.h>
+#include <net/ethernet.h>
+
+struct uip_neighbor_addr
+{
+#if UIP_NEIGHBOR_CONF_ADDRTYPE
+ UIP_NEIGHBOR_CONF_ADDRTYPE addr;
+#else
+ struct ether_addr addr;
+#endif
+};
+
+void uip_neighbor_init(void);
+void uip_neighbor_add(uip_ipaddr_t ipaddr, struct uip_neighbor_addr *addr);
+void uip_neighbor_update(uip_ipaddr_t ipaddr);
+struct uip_neighbor_addr *uip_neighbor_lookup(uip_ipaddr_t ipaddr);
+void uip_neighbor_periodic(void);
+
+#endif /* __UIP-NEIGHBOR_H__ */
diff --git a/nuttx/net/uip/uip_poll.c b/nuttx/net/uip/uip_poll.c
new file mode 100644
index 000000000..8c56e7bf6
--- /dev/null
+++ b/nuttx/net/uip/uip_poll.c
@@ -0,0 +1,353 @@
+/****************************************************************************
+ * net/uip/uip_poll.c
+ *
+ * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+#ifdef CONFIG_NET
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_pollicmp
+ *
+ * Description:
+ * Poll all UDP connections for available packets to send.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+static inline int uip_pollicmp(struct uip_driver_s *dev, uip_poll_callback_t callback)
+{
+ /* Perform the UDP TX poll */
+
+ uip_icmppoll(dev);
+
+ /* Call back into the driver */
+
+ return callback(dev);
+}
+#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
+
+/****************************************************************************
+ * Function: uip_polligmp
+ *
+ * Description:
+ * Poll all UDP connections for available packets to send.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static inline int uip_polligmp(struct uip_driver_s *dev, uip_poll_callback_t callback)
+{
+ /* Perform the UDP TX poll */
+
+ uip_igmppoll(dev);
+
+ /* Call back into the driver */
+
+ return callback(dev);
+}
+#endif /* CONFIG_NET_IGMP */
+
+/****************************************************************************
+ * Function: uip_polludpconnections
+ *
+ * Description:
+ * Poll all UDP connections for available packets to send.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+static int uip_polludpconnections(struct uip_driver_s *dev,
+ uip_poll_callback_t callback)
+{
+ struct uip_udp_conn *udp_conn = NULL;
+ int bstop = 0;
+
+ /* Traverse all of the allocated UDP connections and perform the poll action */
+
+ while (!bstop && (udp_conn = uip_nextudpconn(udp_conn)))
+ {
+ /* Perform the UDP TX poll */
+
+ uip_udppoll(dev, udp_conn);
+
+ /* Call back into the driver */
+
+ bstop = callback(dev);
+ }
+
+ return bstop;
+}
+#endif /* CONFIG_NET_UDP */
+
+/****************************************************************************
+ * Function: uip_polltcpconnections
+ *
+ * Description:
+ * Poll all UDP connections for available packets to send.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline int uip_polltcpconnections(struct uip_driver_s *dev,
+ uip_poll_callback_t callback)
+{
+ struct uip_conn *conn = NULL;
+ int bstop = 0;
+
+ /* Traverse all of the active TCP connections and perform the poll action */
+
+ while (!bstop && (conn = uip_nexttcpconn(conn)))
+ {
+ /* Perform the TCP TX poll */
+
+ uip_tcppoll(dev, conn);
+
+ /* Call back into the driver */
+
+ bstop = callback(dev);
+ }
+
+ return bstop;
+}
+#else
+# define uip_polltcpconnections(dev, callback) (0)
+#endif
+
+/****************************************************************************
+ * Function: uip_polltcptimer
+ *
+ * Description:
+ * The TCP timer has expired. Update TCP timing state in each active,
+ * TCP connection.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_TCP
+static inline int uip_polltcptimer(struct uip_driver_s *dev,
+ uip_poll_callback_t callback, int hsec)
+{
+ struct uip_conn *conn = NULL;
+ int bstop = 0;
+
+ /* Traverse all of the active TCP connections and perform the poll action */
+
+ while (!bstop && (conn = uip_nexttcpconn(conn)))
+ {
+ /* Perform the TCP timer poll */
+
+ uip_tcptimer(dev, conn, hsec);
+
+ /* Call back into the driver */
+
+ bstop = callback(dev);
+ }
+
+ return bstop;
+}
+#else
+# define uip_polltcptimer(dev, callback, hsec) (0)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_poll
+ *
+ * Description:
+ * This function will traverse each active uIP connection structure and
+ * will perform TCP and UDP polling operations. uip_poll() may be called
+ * asychronously with the network drvier can accept another outgoing packet.
+ *
+ * This function will call the provided callback function for every active
+ * connection. Polling will continue until all connections have been polled
+ * or until the user-suplied function returns a non-zero value (which it
+ * should do only if it cannot accept further write data).
+ *
+ * When the callback function is called, there may be an outbound packet
+ * waiting for service in the uIP packet buffer, and if so the d_len field
+ * is set to a value larger than zero. The device driver should then send
+ * out the packet.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback)
+{
+ int bstop;
+
+ /* Check for pendig IGMP messages */
+
+#ifdef CONFIG_NET_IGMP
+ bstop = uip_polligmp(dev, callback);
+ if (!bstop)
+#endif
+ {
+ /* Traverse all of the active TCP connections and perform the poll action */
+
+ bstop = uip_polltcpconnections(dev, callback);
+ if (!bstop)
+ {
+#ifdef CONFIG_NET_UDP
+ /* Traverse all of the allocated UDP connections and perform the poll action */
+
+ bstop = uip_polludpconnections(dev, callback);
+ if (!bstop)
+#endif
+ {
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+ /* Traverse all of the tasks waiting to send an ICMP ECHO request */
+
+ bstop = uip_pollicmp(dev, callback);
+#endif
+ }
+ }
+ }
+
+ return bstop;
+}
+
+/****************************************************************************
+ * Function: uip_timer
+ *
+ * Description:
+ * These function will traverse each active uIP connection structure and
+ * perform TCP timer operations (and UDP polling operations). The Ethernet
+ * driver MUST implement logic to periodically call uip_timer().
+ *
+ * This function will call the provided callback function for every active
+ * connection. Polling will continue until all connections have been polled
+ * or until the user-suplied function returns a non-zero value (which it
+ * should do only if it cannot accept further write data).
+ *
+ * When the callback function is called, there may be an outbound packet
+ * waiting for service in the uIP packet buffer, and if so the d_len field
+ * is set to a value larger than zero. The device driver should then send
+ * out the packet.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver and may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+int uip_timer(struct uip_driver_s *dev, uip_poll_callback_t callback, int hsec)
+{
+ int bstop;
+
+ /* Increment the timer used by the IP reassembly logic */
+
+#if UIP_REASSEMBLY
+ if (uip_reasstmr != 0 && uip_reasstmr < UIP_REASS_MAXAGE)
+ {
+ uip_reasstmr += hsec;
+ }
+#endif /* UIP_REASSEMBLY */
+
+ /* Check for pendig IGMP messages */
+
+#ifdef CONFIG_NET_IGMP
+ bstop = uip_polligmp(dev, callback);
+ if (!bstop)
+#endif
+ {
+ /* Traverse all of the active TCP connections and perform the timer action */
+
+ bstop = uip_polltcptimer(dev, callback, hsec);
+ if (!bstop)
+ {
+ /* Traverse all of the allocated UDP connections and perform the poll action */
+
+#ifdef CONFIG_NET_UDP
+ bstop = uip_polludpconnections(dev, callback);
+ if (!bstop)
+#endif
+ {
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+ /* Traverse all of the tasks waiting to send an ICMP ECHO request */
+
+ bstop = uip_pollicmp(dev, callback);
+#endif
+ }
+ }
+ }
+
+ return bstop;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_send.c b/nuttx/net/uip/uip_send.c
new file mode 100644
index 000000000..fd0f4f7da
--- /dev/null
+++ b/nuttx/net/uip/uip_send.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * net/uip/uip_send.c
+ *
+ * Copyright (C) 2007i, 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Based in part on uIP which also has a BSD stylie license:
+ *
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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 <string.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_send
+ *
+ * Description:
+ * Called from socket logic in response to a xmit or poll request from the
+ * the network interface driver.
+ *
+ * Assumptions:
+ * Called from the interrupt level or, at a mimimum, with interrupts
+ * disabled.
+ *
+ ****************************************************************************/
+
+void uip_send(struct uip_driver_s *dev, const void *buf, int len)
+{
+ /* Some sanity checks -- note that the actually available length in the
+ * buffer is considerably less than CONFIG_NET_BUFSIZE.
+ */
+
+ if (dev && len > 0 && len < CONFIG_NET_BUFSIZE)
+ {
+ memcpy(dev->d_snddata, buf, len);
+ dev->d_sndlen = len;
+ }
+}
diff --git a/nuttx/net/uip/uip_setipid.c b/nuttx/net/uip/uip_setipid.c
new file mode 100644
index 000000000..f9d13cc9d
--- /dev/null
+++ b/nuttx/net/uip/uip_setipid.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * net/uip/uip_setipid.c
+ *
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_setipid
+ *
+ * Description:
+ * This function may be used at boot time to set the initial ip_id.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void uip_setipid(uint16_t id)
+{
+ g_ipid = id;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_tcpappsend.c b/nuttx/net/uip/uip_tcpappsend.c
new file mode 100644
index 000000000..d8a187503
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpappsend.c
@@ -0,0 +1,215 @@
+/****************************************************************************
+ * net/uip/uip_tcpappsend.c
+ *
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpappsend
+ *
+ * Description:
+ * Handle application or TCP protocol response. If this function is called
+ * with dev->d_sndlen > 0, then this is an application attempting to send
+ * packet.
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP connection structure holding connection information
+ * result - App result event sent
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t result)
+{
+ /* Handle the result based on the application response */
+
+ nllvdbg("result: %04x d_sndlen: %d conn->unacked: %d\n",
+ result, dev->d_sndlen, conn->unacked);
+
+ /* Check for connection aborted */
+
+ if ((result & UIP_ABORT) != 0)
+ {
+ dev->d_sndlen = 0;
+ conn->tcpstateflags = UIP_CLOSED;
+ nllvdbg("TCP state: UIP_CLOSED\n");
+
+ uip_tcpsend(dev, conn, TCP_RST | TCP_ACK, UIP_IPTCPH_LEN);
+ }
+
+ /* Check for connection closed */
+
+ else if ((result & UIP_CLOSE) != 0)
+ {
+ conn->tcpstateflags = UIP_FIN_WAIT_1;
+ conn->unacked = 1;
+ conn->nrtx = 0;
+ nllvdbg("TCP state: UIP_FIN_WAIT_1\n");
+
+ dev->d_sndlen = 0;
+ uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
+ }
+
+ /* None of the above */
+
+ else
+ {
+ /* If d_sndlen > 0, the application has data to be sent. */
+
+ if (dev->d_sndlen > 0)
+ {
+ /* Remember how much data we send out now so that we know
+ * when everything has been acknowledged. Just increment the amount
+ * of data sent. This will be needed in sequence number calculations
+ * and we know that this is not a re-tranmission. Retransmissions
+ * do not go through this path.
+ */
+
+ conn->unacked += dev->d_sndlen;
+
+ /* The application cannot send more than what is allowed by the
+ * MSS (the minumum of the MSS and the available window).
+ */
+
+ DEBUGASSERT(dev->d_sndlen <= conn->mss);
+ }
+
+ /* Then handle the rest of the operation just as for the rexmit case */
+
+ conn->nrtx = 0;
+ uip_tcprexmit(dev, conn, result);
+ }
+}
+
+/****************************************************************************
+ * Name: uip_tcprexmit
+ *
+ * Description:
+ * Handle application retransmission
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP connection structure holding connection information
+ * result - App result event sent
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t result)
+{
+ nllvdbg("result: %04x d_sndlen: %d conn->unacked: %d\n",
+ result, dev->d_sndlen, conn->unacked);
+
+ dev->d_appdata = dev->d_snddata;
+
+ /* If the application has data to be sent, or if the incoming packet had
+ * new data in it, we must send out a packet.
+ */
+
+ if (dev->d_sndlen > 0 && conn->unacked > 0)
+ {
+ /* We always set the ACK flag in response packets adding the length of
+ * the IP and TCP headers.
+ */
+
+ uip_tcpsend(dev, conn, TCP_ACK | TCP_PSH, dev->d_sndlen + UIP_TCPIP_HLEN);
+ }
+
+ /* If there is no data to send, just send out a pure ACK if one is requested`. */
+
+ else if ((result & UIP_SNDACK) != 0)
+ {
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_TCPIP_HLEN);
+ }
+
+ /* There is nothing to do -- drop the packet */
+
+ else
+ {
+ dev->d_len = 0;
+ }
+}
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpbacklog.c b/nuttx/net/uip/uip_tcpbacklog.c
new file mode 100644
index 000000000..459d54312
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpbacklog.c
@@ -0,0 +1,403 @@
+/****************************************************************************
+ * net/uip/uip_tcpbacklog.c
+ *
+ * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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/net/uip/uipopt.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) && defined(CONFIG_NET_TCPBACKLOG)
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <queue.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-tcp.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_backlogcreate
+ *
+ * Description:
+ * Called from the listen() logic to setup the backlog as specified in the
+ * the listen arguments.
+ *
+ * Assumptions:
+ * Called from normal user code. Interrupts may be disabled.
+ *
+ ****************************************************************************/
+
+int uip_backlogcreate(FAR struct uip_conn *conn, int nblg)
+{
+ FAR struct uip_backlog_s *bls = NULL;
+ FAR struct uip_blcontainer_s *blc;
+ uip_lock_t flags;
+ int size;
+ int offset;
+ int i;
+
+ nllvdbg("conn=%p nblg=%d\n", conn, nblg);
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Then allocate the backlog as requested */
+
+ if (nblg > 0)
+ {
+ /* Align the list of backlog structures to 32-bit boundaries. This
+ * may be excessive on 24-16-bit address machines; and insufficient
+ * on 64-bit address machines -- REVISIT
+ */
+
+ offset = (sizeof(struct uip_backlog_s) + 3) & ~3;
+
+ /* Then determine the full size of the allocation include the
+ * uip_backlog_s, a pre-allocated array of struct uip_blcontainer_s
+ * and alignement padding
+ */
+
+ size = offset + nblg * sizeof(struct uip_blcontainer_s);
+
+ /* Then allocate that much */
+
+ bls = (FAR struct uip_backlog_s *)zalloc(size);
+ if (!bls)
+ {
+ nlldbg("Failed to allocate backlog\n");
+ return -ENOMEM;
+ }
+
+ /* Then add all of the pre-allocated containers to the free list */
+
+ blc = (FAR struct uip_blcontainer_s*)(((FAR uint8_t*)bls) + offset);
+ for (i = 0; i < nblg; i++)
+ {
+ sq_addfirst(&blc->bc_node, &bls->bl_free);
+ }
+ }
+
+ /* Destroy any existing backlog (shouldn't be any) */
+
+ flags = uip_lock();
+ uip_backlogdestroy(conn);
+
+ /* Now install the backlog tear-off in the connection. NOTE that bls may
+ * actually be NULL if nblg is <= 0; In that case, we are disabling backlog
+ * support. Since interrupts are disabled, destroying the old backlog and
+ * replace it with the new is an atomic operation
+ */
+
+ conn->backlog = bls;
+ uip_unlock(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: uip_backlogdestroy
+ *
+ * Description:
+ * (1) Called from uip_tcpfree() whenever a connection is freed.
+ * (2) Called from uip_backlogcreate() to destroy any old backlog
+ *
+ * NOTE: This function may re-enter uip_tcpfree when a connection that
+ * is freed that has pending connections.
+ *
+ * Assumptions:
+ * The caller has disabled interrupts so that there can be no conflict
+ * with ongoing, interrupt driven activity
+ *
+ ****************************************************************************/
+
+int uip_backlogdestroy(FAR struct uip_conn *conn)
+{
+ FAR struct uip_backlog_s *blg;
+ FAR struct uip_blcontainer_s *blc;
+ FAR struct uip_conn *blconn;
+
+ nllvdbg("conn=%p\n", conn);
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Make sure that the connection has a backlog to be destroyed */
+
+ if (conn->backlog)
+ {
+ /* Remove the backlog structure reference from the connection */
+
+ blg = conn->backlog;
+ conn->backlog = NULL;
+
+ /* Handle any pending connections in the backlog */
+
+ while ((blc = (FAR struct uip_blcontainer_s*)sq_remfirst(&blg->bl_pending)) != NULL)
+ {
+ blconn = blc->bc_conn;
+ if (blconn)
+ {
+ /* REVISIT -- such connections really need to be gracefully closed */
+
+ blconn->blparent = NULL;
+ blconn->backlog = NULL;
+ blconn->crefs = 0;
+ uip_tcpfree(blconn);
+ }
+ }
+
+ /* Then free the entire backlog structure */
+
+ free(blg);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Function: uip_backlogadd
+ *
+ * Description:
+ * Called uip_listen when a new connection is made with a listener socket
+ * but when there is no accept() in place to receive the connection. This
+ * function adds the new connection to the backlog.
+ *
+ * Assumptions:
+ * Called from the interrupt level with interrupts disabled
+ *
+ ****************************************************************************/
+
+int uip_backlogadd(FAR struct uip_conn *conn, FAR struct uip_conn *blconn)
+{
+ FAR struct uip_backlog_s *bls;
+ FAR struct uip_blcontainer_s *blc;
+ int ret = -EINVAL;
+
+ nllvdbg("conn=%p blconn=%p\n", conn, blconn);
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ bls = conn->backlog;
+ if (bls && blconn)
+ {
+ /* Allocate a container for the connection from the free list */
+
+ blc = (FAR struct uip_blcontainer_s *)sq_remfirst(&bls->bl_free);
+ if (!blc)
+ {
+ nlldbg("Failed to allocate container\n");
+ ret = -ENOMEM;
+ }
+ else
+ {
+ /* Save the connection reference in the container and put the
+ * container at the end of the pending connection list (FIFO).
+ */
+
+ blc->bc_conn = blconn;
+ sq_addlast(&blc->bc_node, &bls->bl_pending);
+ ret = OK;
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_backlogremove
+ *
+ * Description:
+ * Called from poll(). Before waiting for a new connection, poll will
+ * call this API to see if there are pending connections in the backlog.
+ *
+ * Assumptions:
+ * Called from normal user code, but with interrupts disabled,
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_POLL
+bool uip_backlogavailable(FAR struct uip_conn *conn)
+{
+ return (conn && conn->backlog && !sq_empty(&conn->backlog->bl_pending));
+}
+#endif
+
+/****************************************************************************
+ * Function: uip_backlogremove
+ *
+ * Description:
+ * Called from accept(). Before waiting for a new connection, accept will
+ * call this API to see if there are pending connections in the backlog.
+ *
+ * Assumptions:
+ * Called from normal user code, but with interrupts disabled,
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_backlogremove(FAR struct uip_conn *conn)
+{
+ FAR struct uip_backlog_s *bls;
+ FAR struct uip_blcontainer_s *blc;
+ FAR struct uip_conn *blconn = NULL;
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return NULL;
+ }
+#endif
+
+ bls = conn->backlog;
+ if (bls)
+ {
+ /* Remove the a container at the head of the pending connection list
+ * (FIFO)
+ */
+
+ blc = (FAR struct uip_blcontainer_s *)sq_remfirst(&bls->bl_pending);
+ if (blc)
+ {
+ /* Extract the connection reference from the container and put
+ * container in the free list
+ */
+
+ blconn = blc->bc_conn;
+ blc->bc_conn = NULL;
+ sq_addlast(&blc->bc_node, &bls->bl_free);
+ }
+ }
+
+ nllvdbg("conn=%p, returning %p\n", conn, blconn);
+ return blconn;
+}
+
+/****************************************************************************
+ * Function: uip_backlogdelete
+ *
+ * Description:
+ * Called from uip_tcpfree() when a connection is freed that this also
+ * retained in the pending connectino list of a listener. We simply need
+ * to remove the defunct connecton from the list.
+ *
+ * Assumptions:
+ * Called from the interrupt level with interrupts disabled
+ *
+ ****************************************************************************/
+
+int uip_backlogdelete(FAR struct uip_conn *conn, FAR struct uip_conn *blconn)
+{
+ FAR struct uip_backlog_s *bls;
+ FAR struct uip_blcontainer_s *blc;
+ FAR struct uip_blcontainer_s *prev;
+
+ nllvdbg("conn=%p blconn=%p\n", conn, blconn);
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ bls = conn->backlog;
+ if (bls)
+ {
+ /* Find the container hold the connection */
+
+ for (blc = (FAR struct uip_blcontainer_s *)sq_peek(&bls->bl_pending), prev = NULL;
+ blc;
+ prev = blc, blc = (FAR struct uip_blcontainer_s *)sq_next(&blc->bc_node))
+ {
+ if (blc->bc_conn == blconn)
+ {
+ if (prev)
+ {
+ /* Remove the a container from the middle of the list of
+ * pending connections
+ */
+
+ (void)sq_remafter(&prev->bc_node, &bls->bl_pending);
+ }
+ else
+ {
+ /* Remove the a container from the head of the list of
+ * pending connections
+ */
+
+ (void)sq_remfirst(&bls->bl_pending);
+ }
+
+ /* Put container in the free list */
+
+ blc->bc_conn = NULL;
+ sq_addlast(&blc->bc_node, &bls->bl_free);
+ return OK;
+ }
+ }
+
+ nlldbg("Failed to find pending connection\n");
+ return -EINVAL;
+ }
+ return OK;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP && CONFIG_NET_TCPBACKLOG */
diff --git a/nuttx/net/uip/uip_tcpcallback.c b/nuttx/net/uip/uip_tcpcallback.c
new file mode 100644
index 000000000..9ce8eb132
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpcallback.c
@@ -0,0 +1,339 @@
+/****************************************************************************
+ * net/uip/uip_tcpcallback.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_readahead
+ *
+ * Description:
+ * Copy as much received data as possible into the readahead buffer
+ *
+ * Assumptions:
+ * This function is called at the interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+static int uip_readahead(struct uip_readahead_s *readahead, uint8_t *buf,
+ int len)
+{
+ int available = CONFIG_NET_TCP_READAHEAD_BUFSIZE - readahead->rh_nbytes;
+ int recvlen = 0;
+
+ if (len > 0 && available > 0)
+ {
+ /* Get the length of the data to buffer. */
+
+ if (len > available)
+ {
+ recvlen = available;
+ }
+ else
+ {
+ recvlen = len;
+ }
+
+ /* Copy the new appdata into the read-ahead buffer */
+
+ memcpy(&readahead->rh_buffer[readahead->rh_nbytes], buf, recvlen);
+ readahead->rh_nbytes += recvlen;
+ }
+ return recvlen;
+}
+#endif
+
+/****************************************************************************
+ * Function: uip_dataevent
+ *
+ * Description:
+ * Handle data that is not accepted by the application because there is no
+ * listener in place ready to receive the data.
+ *
+ * Assumptions:
+ * - The caller has checked that UIP_NEWDATA is set in flags and that is no
+ * other handler available to process the incoming data.
+ * - This function is called at the interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+static inline uint16_t
+uip_dataevent(FAR struct uip_driver_s *dev, FAR struct uip_conn *conn,
+ uint16_t flags)
+{
+ uint16_t ret;
+
+ /* Assume that we will ACK the data. The data will be ACKed if it is
+ * placed in the read-ahead buffer -OR- if it zero length
+ */
+
+ ret = (flags & ~UIP_NEWDATA) | UIP_SNDACK;
+
+ /* Is there new data? With non-zero length? (Certain connection events
+ * can have zero-length with UIP_NEWDATA set just to cause an ACK).
+ */
+
+ if (dev->d_len > 0)
+ {
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ uint8_t *buffer = dev->d_appdata;
+ int buflen = dev->d_len;
+ uint16_t recvlen;
+#endif
+
+ nllvdbg("No listener on connection\n");
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ /* Save as much data as possible in the read-ahead buffers */
+
+ recvlen = uip_datahandler(conn, buffer, buflen);
+
+ /* There are several complicated buffering issues that are not addressed
+ * properly here. For example, what if we cannot buffer the entire
+ * packet? In that case, some data will be accepted but not ACKed.
+ * Therefore it will be resent and duplicated. Fixing this could be tricky.
+ */
+
+ if (recvlen < buflen)
+#endif
+ {
+ /* There is no handler to receive new data and there are no free
+ * read-ahead buffers to retain the data -- drop the packet.
+ */
+
+ nllvdbg("Dropped %d bytes\n", dev->d_len);
+
+ #ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.syndrop++;
+ uip_stat.tcp.drop++;
+#endif
+ /* Clear the UIP_SNDACK bit so that no ACK will be sent */
+
+ ret &= ~UIP_SNDACK;
+ }
+ }
+
+ /* In any event, the new data has now been handled */
+
+ dev->d_len = 0;
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_tcpcallback
+ *
+ * Description:
+ * Inform the application holding the TCP socket of a change in state.
+ *
+ * Assumptions:
+ * This function is called at the interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+uint16_t uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t flags)
+{
+ /* Preserve the UIP_ACKDATA, UIP_CLOSE, and UIP_ABORT in the response.
+ * These is needed by uIP to handle responses and buffer state. The
+ * UIP_NEWDATA indication will trigger the ACK response, but must be
+ * explicitly set in the callback.
+ */
+
+ uint16_t ret = flags;
+
+ nllvdbg("flags: %04x\n", flags);
+
+ /* Perform the data callback. When a data callback is executed from 'list',
+ * the input flags are normally returned, however, the implementation
+ * may set one of the following:
+ *
+ * UIP_CLOSE - Gracefully close the current connection
+ * UIP_ABORT - Abort (reset) the current connection on an error that
+ * prevents UIP_CLOSE from working.
+ *
+ * And/Or set/clear the following:
+ *
+ * UIP_NEWDATA - May be cleared to indicate that the data was consumed
+ * and that no further process of the new data should be
+ * attempted.
+ * UIP_SNDACK - If UIP_NEWDATA is cleared, then UIP_SNDACK may be set
+ * to indicate that an ACK should be included in the response.
+ * (In UIP_NEWDATA is cleared bu UIP_SNDACK is not set, then
+ * dev->d_len should also be cleared).
+ */
+
+ ret = uip_callbackexecute(dev, conn, flags, conn->list);
+
+ /* There may be no new data handler in place at them moment that the new
+ * incoming data is received. If the new incoming data was not handled, then
+ * either (1) put the unhandled incoming data in the read-ahead buffer (if
+ * enabled) or (2) suppress the ACK to the data in the hope that it will
+ * be re-transmitted at a better time.
+ */
+
+ if ((ret & UIP_NEWDATA) != 0)
+ {
+ /* Data was not handled.. dispose of it appropriately */
+
+ ret = uip_dataevent(dev, conn, ret);
+ }
+
+ /* Check if there is a connection-related event and a connection
+ * callback.
+ */
+
+ if (((flags & UIP_CONN_EVENTS) != 0) && conn->connection_event)
+ {
+ /* Perform the callback */
+
+ conn->connection_event(conn, flags);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_datahandler
+ *
+ * Description:
+ * Handle data that is not accepted by the application. This may be called
+ * either (1) from the data receive logic if it cannot buffer the data, or
+ * (2) from the TCP event logic is there is no listener in place ready to
+ * receive the data.
+ *
+ * Input Parmeters:
+ * conn - A pointer to the TCP connection structure
+ * buffer - A pointer to the buffer to be copied to the read-ahead
+ * buffers
+ * buflen - The number of bytes to copy to the read-ahead buffer.
+ *
+ * Returned value:
+ * The number of bytes actually buffered. This could be less than 'nbytes'
+ * if there is insufficient buffering available.
+ *
+ * Assumptions:
+ * - The caller has checked that UIP_NEWDATA is set in flags and that is no
+ * other handler available to process the incoming data.
+ * - This function is called at the interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+uint16_t uip_datahandler(FAR struct uip_conn *conn, FAR uint8_t *buffer,
+ uint16_t buflen)
+{
+ FAR struct uip_readahead_s *readahead1;
+ FAR struct uip_readahead_s *readahead2 = NULL;
+ uint16_t remaining;
+ uint16_t recvlen = 0;
+
+ /* First, we need to determine if we have space to buffer the data. This
+ * needs to be verified before we actually begin buffering the data. We
+ * will use any remaining space in the last allocated readahead buffer
+ * plus as much one additional buffer. It is expected that the size of
+ * readahead buffers are tuned so that one full packet will always fit
+ * into one readahead buffer (for example if the buffer size is 420, then
+ * a readahead buffer of 366 will hold a full packet of TCP data).
+ */
+
+ readahead1 = (FAR struct uip_readahead_s*)conn->readahead.tail;
+ if ((readahead1 &&
+ (CONFIG_NET_TCP_READAHEAD_BUFSIZE - readahead1->rh_nbytes) > buflen) ||
+ (readahead2 = uip_tcpreadaheadalloc()) != NULL)
+ {
+ /* We have buffer space. Now try to append add as much data as possible
+ * to the last readahead buffer attached to this connection.
+ */
+
+ remaining = buflen;
+ if (readahead1)
+ {
+ recvlen = uip_readahead(readahead1, buffer, remaining);
+ if (recvlen > 0)
+ {
+ buffer += recvlen;
+ remaining -= recvlen;
+ }
+ }
+
+ /* Do we need to buffer into the newly allocated buffer as well? */
+
+ if (readahead2)
+ {
+ readahead2->rh_nbytes = 0;
+ recvlen += uip_readahead(readahead2, buffer, remaining);
+
+ /* Save the readahead buffer in the connection structure where
+ * it can be found with recv() is called.
+ */
+
+ sq_addlast(&readahead2->rh_node, &conn->readahead);
+ }
+ }
+
+ nllvdbg("Buffered %d bytes (of %d)\n", recvlen, buflen);
+ return recvlen;
+}
+#endif /* CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0 */
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpconn.c b/nuttx/net/uip/uip_tcpconn.c
new file mode 100644
index 000000000..c2b64ad89
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpconn.c
@@ -0,0 +1,636 @@
+/****************************************************************************
+ * net/uip/uip_tcpconn.c
+ *
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Large parts of this file were leveraged from uIP logic:
+ *
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The array containing all uIP TCP connections. */
+
+static struct uip_conn g_tcp_connections[CONFIG_NET_TCP_CONNS];
+
+/* A list of all free TCP connections */
+
+static dq_queue_t g_free_tcp_connections;
+
+/* A list of all connected TCP connections */
+
+static dq_queue_t g_active_tcp_connections;
+
+/* Last port used by a TCP connection connection. */
+
+static uint16_t g_last_tcp_port;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_selectport()
+ *
+ * Description:
+ * If the portnumber is zero; select an unused port for the connection.
+ * If the portnumber is non-zero, verify that no other connection has
+ * been created with this port number.
+ *
+ * Input Parameters:
+ * portno -- the selected port number in host order. Zero means no port
+ * selected.
+ *
+ * Return:
+ * 0 on success, negated errno on failure:
+ *
+ * EADDRINUSE
+ * The given address is already in use.
+ * EADDRNOTAVAIL
+ * Cannot assign requested address (unlikely)
+ *
+ * Assumptions:
+ * Interrupts are disabled
+ *
+ ****************************************************************************/
+
+static int uip_selectport(uint16_t portno)
+{
+ if (portno == 0)
+ {
+ /* No local port assigned. Loop until we find a valid listen port number
+ * that is not being used by any other connection. NOTE the following loop
+ * is assumed to terminate but could not if all 32000-4096+1 ports are
+ * in used (unlikely).
+ */
+
+ do
+ {
+ /* Guess that the next available port number will be the one after
+ * the last port number assigned.
+ */
+ portno = ++g_last_tcp_port;
+
+ /* Make sure that the port number is within range */
+
+ if (g_last_tcp_port >= 32000)
+ {
+ g_last_tcp_port = 4096;
+ }
+ }
+ while (uip_tcplistener(htons(g_last_tcp_port)));
+ }
+ else
+ {
+ /* A port number has been supplied. Verify that no other TCP/IP
+ * connection is using this local port.
+ */
+
+ if (uip_tcplistener(portno))
+ {
+ /* It is in use... return EADDRINUSE */
+
+ return -EADDRINUSE;
+ }
+ }
+
+ /* Return the selected or verified port number */
+
+ return portno;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpinit()
+ *
+ * Description:
+ * Initialize the TCP/IP connection structures. Called only once and only
+ * from the UIP layer at startup in normal user mode.
+ *
+ ****************************************************************************/
+
+void uip_tcpinit(void)
+{
+ int i;
+
+ /* Initialize the queues */
+
+ dq_init(&g_free_tcp_connections);
+ dq_init(&g_active_tcp_connections);
+
+ /* Now initialize each connection structure */
+
+ for (i = 0; i < CONFIG_NET_TCP_CONNS; i++)
+ {
+ /* Mark the connection closed and move it to the free list */
+
+ g_tcp_connections[i].tcpstateflags = UIP_CLOSED;
+ dq_addlast(&g_tcp_connections[i].node, &g_free_tcp_connections);
+ }
+
+ g_last_tcp_port = 1024;
+}
+
+/****************************************************************************
+ * Name: uip_tcpalloc()
+ *
+ * Description:
+ * Find a free TCP/IP connection structure and allocate it
+ * for use. This is normally something done by the implementation of the
+ * socket() API but is also called from the interrupt level when a TCP
+ * packet is received while "listening"
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcpalloc(void)
+{
+ struct uip_conn *conn;
+ uip_lock_t flags;
+
+ /* Because this routine is called from both interrupt level and
+ * and from user level, we have not option but to disable interrupts
+ * while accessing g_free_tcp_connections[];
+ */
+
+ flags = uip_lock();
+
+ /* Return the entry from the head of the free list */
+
+ conn = (struct uip_conn *)dq_remfirst(&g_free_tcp_connections);
+
+#if 0 /* Revisit */
+ /* Is the free list empty? */
+
+ if (!conn)
+ {
+ /* As a fallback, check for connection structures in the TIME_WAIT
+ * state. If no CLOSED connections are found, then take the oldest
+ */
+
+ struct uip_conn *tmp = g_active_tcp_connections.head;
+ while (tmp)
+ {
+ /* Is this connectin in the UIP_TIME_WAIT state? */
+
+ if (tmp->tcpstateflags == UIP_TIME_WAIT)
+ {
+ /* Is it the oldest one we have seen so far? */
+
+ if (!conn || tmp->timer > conn->timer)
+ {
+ /* Yes.. remember it */
+
+ conn = tmp;
+ }
+ }
+
+ /* Look at the next active connection */
+
+ tmp = tmp->node.flink;
+ }
+
+ /* If we found one, remove it from the active connection list */
+
+ dq_rem(&conn->node, &g_active_tcp_connections);
+ }
+#endif
+
+ uip_unlock(flags);
+
+ /* Mark the connection allocated */
+
+ if (conn)
+ {
+ conn->tcpstateflags = UIP_ALLOCATED;
+ }
+
+ return conn;
+}
+
+/****************************************************************************
+ * Name: uip_tcpfree()
+ *
+ * Description:
+ * Free a connection structure that is no longer in use. This should be
+ * done by the implementation of close()
+ *
+ ****************************************************************************/
+
+void uip_tcpfree(struct uip_conn *conn)
+{
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ struct uip_readahead_s *readahead;
+#endif
+ uip_lock_t flags;
+
+ /* Because g_free_tcp_connections is accessed from user level and interrupt
+ * level, code, it is necessary to keep interrupts disabled during this
+ * operation.
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+ flags = uip_lock();
+
+ /* UIP_ALLOCATED means that that the connection is not in the active list
+ * yet.
+ */
+
+ if (conn->tcpstateflags != UIP_ALLOCATED)
+ {
+ /* Remove the connection from the active list */
+
+ dq_rem(&conn->node, &g_active_tcp_connections);
+ }
+
+ /* Release any read-ahead buffers attached to the connection */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ while ((readahead = (struct uip_readahead_s *)sq_remfirst(&conn->readahead)) != NULL)
+ {
+ uip_tcpreadaheadrelease(readahead);
+ }
+#endif
+
+ /* Remove any backlog attached to this connection */
+
+#ifdef CONFIG_NET_TCPBACKLOG
+ if (conn->backlog)
+ {
+ uip_backlogdestroy(conn);
+ }
+
+ /* If this connection is, itself, backlogged, then remove it from the
+ * parent connection's backlog list.
+ */
+
+ if (conn->blparent)
+ {
+ uip_backlogdelete(conn->blparent, conn);
+ }
+#endif
+
+ /* Mark the connection available and put it into the free list */
+
+ conn->tcpstateflags = UIP_CLOSED;
+ dq_addlast(&conn->node, &g_free_tcp_connections);
+ uip_unlock(flags);
+}
+
+/****************************************************************************
+ * Name: uip_tcpactive()
+ *
+ * Description:
+ * Find a connection structure that is the appropriate
+ * connection to be used with the provided TCP/IP header
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf)
+{
+ struct uip_conn *conn = (struct uip_conn *)g_active_tcp_connections.head;
+ in_addr_t srcipaddr = uip_ip4addr_conv(buf->srcipaddr);
+
+ while (conn)
+ {
+ /* Find an open connection matching the tcp input */
+
+ if (conn->tcpstateflags != UIP_CLOSED &&
+ buf->destport == conn->lport && buf->srcport == conn->rport &&
+ uip_ipaddr_cmp(srcipaddr, conn->ripaddr))
+ {
+ /* Matching connection found.. break out of the loop and return a
+ * reference to it.
+ */
+
+ break;
+ }
+
+ /* Look at the next active connection */
+
+ conn = (struct uip_conn *)conn->node.flink;
+ }
+
+ return conn;
+}
+
+/****************************************************************************
+ * Name: uip_nexttcpconn()
+ *
+ * Description:
+ * Traverse the list of active TCP connections
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level (or with
+ * interrupts disabled).
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_nexttcpconn(struct uip_conn *conn)
+{
+ if (!conn)
+ {
+ return (struct uip_conn *)g_active_tcp_connections.head;
+ }
+ else
+ {
+ return (struct uip_conn *)conn->node.flink;
+ }
+}
+
+/****************************************************************************
+ * Name: uip_tcplistener()
+ *
+ * Description:
+ * Given a local port number (in network byte order), find the TCP
+ * connection that listens on this this port.
+ *
+ * Primary uses: (1) to determine if a port number is available, (2) to
+ * To idenfity the socket that will accept new connections on a local port.
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcplistener(uint16_t portno)
+{
+ struct uip_conn *conn;
+ int i;
+
+ /* Check if this port number is in use by any active UIP TCP connection */
+
+ for (i = 0; i < CONFIG_NET_TCP_CONNS; i++)
+ {
+ conn = &g_tcp_connections[i];
+ if (conn->tcpstateflags != UIP_CLOSED && conn->lport == portno)
+ {
+ /* The portnumber is in use, return the connection */
+
+ return conn;
+ }
+ }
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: uip_tcpaccept()
+ *
+ * Description:
+ * Called when uip_interupt matches the incoming packet with a connection
+ * in LISTEN. In that case, this function will create a new connection and
+ * initialize it to send a SYNACK in return.
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf)
+{
+ struct uip_conn *conn = uip_tcpalloc();
+ if (conn)
+ {
+ /* Fill in the necessary fields for the new connection. */
+
+ conn->rto = UIP_RTO;
+ conn->timer = UIP_RTO;
+ conn->sa = 0;
+ conn->sv = 4;
+ conn->nrtx = 0;
+ conn->lport = buf->destport;
+ conn->rport = buf->srcport;
+ uip_ipaddr_copy(conn->ripaddr, uip_ip4addr_conv(buf->srcipaddr));
+ conn->tcpstateflags = UIP_SYN_RCVD;
+
+ uip_tcpinitsequence(conn->sndseq);
+ conn->unacked = 1;
+
+ /* rcvseq should be the seqno from the incoming packet + 1. */
+
+ memcpy(conn->rcvseq, buf->seqno, 4);
+
+ /* Initialize the list of TCP read-ahead buffers */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ sq_init(&conn->readahead);
+#endif
+
+ /* And, finally, put the connection structure into the active list.
+ * Interrupts should already be disabled in this context.
+ */
+
+ dq_addlast(&conn->node, &g_active_tcp_connections);
+ }
+ return conn;
+}
+
+/****************************************************************************
+ * Name: uip_tcpbind()
+ *
+ * Description:
+ * This function implements the UIP specific parts of the standard TCP
+ * bind() operation.
+ *
+ * Return:
+ * 0 on success or -EADDRINUSE on failure
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ uip_lock_t flags;
+ int port;
+
+ /* Verify or select a local port */
+
+ flags = uip_lock();
+ port = uip_selectport(ntohs(addr->sin_port));
+ uip_unlock(flags);
+
+ if (port < 0)
+ {
+ return port;
+ }
+
+ /* Save the local address in the connection structure. Note that the requested
+ * local IP address is saved but not used. At present, only a single network
+ * interface is supported, the IP address is not of importance.
+ */
+
+ conn->lport = addr->sin_port;
+
+#if 0 /* Not used */
+#ifdef CONFIG_NET_IPv6
+ uip_ipaddr_copy(conn->lipaddr, addr->sin6_addr.in6_u.u6_addr16);
+#else
+ uip_ipaddr_copy(conn->lipaddr, addr->sin_addr.s_addr);
+#endif
+#endif
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: uip_tcpconnect()
+ *
+ * Description:
+ * This function implements the UIP specific parts of the standard
+ * TCP connect() operation: It connects to a remote host using TCP.
+ *
+ * This function is used to start a new connection to the specified
+ * port on the specied host. It uses the connection structure that was
+ * allocated by a preceding socket() call. It sets the connection to
+ * the SYN_SENT state and sets the retransmission timer to 0. This will
+ * cause a TCP SYN segment to be sent out the next time this connection
+ * is periodically processed, which usually is done within 0.5 seconds
+ * after the call to uip_tcpconnect().
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ uip_lock_t flags;
+ int port;
+
+ /* The connection is expected to be in the UIP_ALLOCATED state.. i.e.,
+ * allocated via up_tcpalloc(), but not yet put into the active connections
+ * list.
+ */
+
+ if (!conn || conn->tcpstateflags != UIP_ALLOCATED)
+ {
+ return -EISCONN;
+ }
+
+ /* If the TCP port has not alread been bound to a local port, then select
+ * one now.
+ */
+
+ flags = uip_lock();
+ port = uip_selectport(ntohs(conn->lport));
+ uip_unlock(flags);
+
+ if (port < 0)
+ {
+ return port;
+ }
+
+ /* Initialize and return the connection structure, bind it to the port number */
+
+ conn->tcpstateflags = UIP_SYN_SENT;
+ uip_tcpinitsequence(conn->sndseq);
+
+ conn->initialmss = conn->mss = UIP_TCP_MSS;
+ conn->unacked = 1; /* TCP length of the SYN is one. */
+ conn->nrtx = 0;
+ conn->timer = 1; /* Send the SYN next time around. */
+ conn->rto = UIP_RTO;
+ conn->sa = 0;
+ conn->sv = 16; /* Initial value of the RTT variance. */
+ conn->lport = htons((uint16_t)port);
+
+ /* The sockaddr port is 16 bits and already in network order */
+
+ conn->rport = addr->sin_port;
+
+ /* The sockaddr address is 32-bits in network order. */
+
+ uip_ipaddr_copy(conn->ripaddr, addr->sin_addr.s_addr);
+
+ /* Initialize the list of TCP read-ahead buffers */
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+ sq_init(&conn->readahead);
+#endif
+
+ /* And, finally, put the connection structure into the active
+ * list. Because g_active_tcp_connections is accessed from user level and
+ * interrupt level, code, it is necessary to keep interrupts disabled during
+ * this operation.
+ */
+
+ flags = uip_lock();
+ dq_addlast(&conn->node, &g_active_tcp_connections);
+ uip_unlock(flags);
+
+ return OK;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpinput.c b/nuttx/net/uip/uip_tcpinput.c
new file mode 100644
index 000000000..5b40963b6
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpinput.c
@@ -0,0 +1,839 @@
+/****************************************************************************
+ * net/uip/uip_tcpinput.c
+ * Handling incoming TCP input
+ *
+ * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpinput
+ *
+ * Description:
+ * Handle incoming TCP input
+ *
+ * Parameters:
+ * dev - The device driver structure containing the received TCP packet.
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpinput(struct uip_driver_s *dev)
+{
+ struct uip_conn *conn = NULL;
+ struct uip_tcpip_hdr *pbuf = BUF;
+ uint16_t tmp16;
+ uint16_t flags;
+ uint8_t opt;
+ uint8_t result;
+ int len;
+ int i;
+
+ dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+ dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.recv++;
+#endif
+
+ /* Start of TCP input header processing code. */
+
+ if (uip_tcpchksum(dev) != 0xffff)
+ {
+ /* Compute and check the TCP checksum. */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.drop++;
+ uip_stat.tcp.chkerr++;
+#endif
+ nlldbg("Bad TCP checksum\n");
+ goto drop;
+ }
+
+ /* Demultiplex this segment. First check any active connections. */
+
+ conn = uip_tcpactive(pbuf);
+ if (conn)
+ {
+ /* We found an active connection.. Check for the subsequent SYN
+ * arriving in UIP_SYN_RCVD state after the SYNACK packet was
+ * lost. To avoid other issues, reset any active connection
+ * where a SYN arrives in a state != UIP_SYN_RCVD.
+ */
+
+ if ((conn->tcpstateflags & UIP_TS_MASK) != UIP_SYN_RCVD &&
+ (BUF->flags & TCP_CTL) == TCP_SYN)
+ {
+ goto reset;
+ }
+ else
+ {
+ goto found;
+ }
+ }
+
+ /* If we didn't find and active connection that expected the packet,
+ * either (1) this packet is an old duplicate, or (2) this is a SYN packet
+ * destined for a connection in LISTEN. If the SYN flag isn't set,
+ * it is an old packet and we send a RST.
+ */
+
+ if ((pbuf->flags & TCP_CTL) == TCP_SYN)
+ {
+ /* This is a SYN packet for a connection. Find the connection
+ * listening on this port.
+ */
+
+ tmp16 = pbuf->destport;
+ if (uip_islistener(tmp16))
+ {
+ /* We matched the incoming packet with a connection in LISTEN.
+ * We now need to create a new connection and send a SYNACK in
+ * response.
+ */
+
+ /* First allocate a new connection structure and see if there is any
+ * user application to accept it.
+ */
+
+ conn = uip_tcpaccept(pbuf);
+ if (conn)
+ {
+ /* The connection structure was successfully allocated. Now see if
+ * there is an application waiting to accept the connection (or at
+ * least queue it it for acceptance).
+ */
+
+ conn->crefs = 1;
+ if (uip_accept(dev, conn, tmp16) != OK)
+ {
+ /* No, then we have to give the connection back and drop the packet */
+
+ conn->crefs = 0;
+ uip_tcpfree(conn);
+ conn = NULL;
+ }
+ else
+ {
+ /* TCP state machine should move to the ESTABLISHED state only after
+ * it has received ACK from the host. This needs to be investigated
+ * further.
+ */
+
+ conn->tcpstateflags = UIP_ESTABLISHED;
+ }
+ }
+
+ if (!conn)
+ {
+ /* Either (1) all available connections are in use, or (2) there is no
+ * application in place to accept the connection. We drop packet and hope that
+ * the remote end will retransmit the packet at a time when we
+ * have more spare connections or someone waiting to accept the connection.
+ */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.syndrop++;
+#endif
+ nlldbg("No free TCP connections\n");
+ goto drop;
+ }
+
+ uip_incr32(conn->rcvseq, 1);
+
+ /* Parse the TCP MSS option, if present. */
+
+ if ((pbuf->tcpoffset & 0xf0) > 0x50)
+ {
+ for (i = 0; i < ((pbuf->tcpoffset >> 4) - 5) << 2 ;)
+ {
+ opt = dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + i];
+ if (opt == TCP_OPT_END)
+ {
+ /* End of options. */
+
+ break;
+ }
+ else if (opt == TCP_OPT_NOOP)
+ {
+ /* NOP option. */
+
+ ++i;
+ }
+ else if (opt == TCP_OPT_MSS &&
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == TCP_OPT_MSS_LEN)
+ {
+ /* An MSS option with the right option length. */
+
+ tmp16 = ((uint16_t)dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + i] << 8) |
+ (uint16_t)dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + 3 + i];
+ conn->initialmss = conn->mss =
+ tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
+
+ /* And we are done processing options. */
+
+ break;
+ }
+ else
+ {
+ /* All other options have a length field, so that we easily
+ * can skip past them.
+ */
+
+ if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == 0)
+ {
+ /* If the length field is zero, the options are malformed
+ * and we don't process them further.
+ */
+
+ break;
+ }
+ i += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i];
+ }
+ }
+ }
+
+ /* Our response will be a SYNACK. */
+
+ uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
+ return;
+ }
+ }
+
+ /* This is (1) an old duplicate packet or (2) a SYN packet but with
+ * no matching listener found. Send RST packet in either case.
+ */
+
+reset:
+
+ /* We do not send resets in response to resets. */
+
+ if ((pbuf->flags & TCP_RST) != 0)
+ {
+ goto drop;
+ }
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.synrst++;
+#endif
+ uip_tcpreset(dev);
+ return;
+
+found:
+
+ flags = 0;
+
+ /* We do a very naive form of TCP reset processing; we just accept
+ * any RST and kill our connection. We should in fact check if the
+ * sequence number of this reset is within our advertised window
+ * before we accept the reset.
+ */
+
+ if ((pbuf->flags & TCP_RST) != 0)
+ {
+ conn->tcpstateflags = UIP_CLOSED;
+ nlldbg("RESET - TCP state: UIP_CLOSED\n");
+
+ (void)uip_tcpcallback(dev, conn, UIP_ABORT);
+ goto drop;
+ }
+
+ /* Calculated the length of the data, if the application has sent
+ * any data to us.
+ */
+
+ len = (pbuf->tcpoffset >> 4) << 2;
+
+ /* d_len will contain the length of the actual TCP data. This is
+ * calculated by subtracting the length of the TCP header (in
+ * len) and the length of the IP header (20 bytes).
+ */
+
+ dev->d_len -= (len + UIP_IPH_LEN);
+
+ /* First, check if the sequence number of the incoming packet is
+ * what we're expecting next. If not, we send out an ACK with the
+ * correct numbers in, unless we are in the SYN_RCVD state and
+ * receive a SYN, in which case we should retransmit our SYNACK
+ * (which is done further down).
+ */
+
+ if (!((((conn->tcpstateflags & UIP_TS_MASK) == UIP_SYN_SENT) &&
+ ((pbuf->flags & TCP_CTL) == (TCP_SYN | TCP_ACK))) ||
+ (((conn->tcpstateflags & UIP_TS_MASK) == UIP_SYN_RCVD) &&
+ ((pbuf->flags & TCP_CTL) == TCP_SYN))))
+ {
+ if ((dev->d_len > 0 || ((pbuf->flags & (TCP_SYN | TCP_FIN)) != 0)) &&
+ memcmp(pbuf->seqno, conn->rcvseq, 4) != 0)
+ {
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+ }
+
+ /* Next, check if the incoming segment acknowledges any outstanding
+ * data. If so, we update the sequence number, reset the length of
+ * the outstanding data, calculate RTT estimations, and reset the
+ * retransmission timer.
+ */
+
+ if ((pbuf->flags & TCP_ACK) != 0 && conn->unacked > 0)
+ {
+ uint32_t unackseq;
+ uint32_t ackseq;
+
+ /* The next sequence number is equal to the current sequence
+ * number (sndseq) plus the size of the oustanding, unacknowledged
+ * data (unacked).
+ */
+
+ unackseq = uip_tcpaddsequence(conn->sndseq, conn->unacked);
+
+ /* Get the sequence number of that has just been acknowledged by this
+ * incoming packet.
+ */
+
+ ackseq = uip_tcpgetsequence(pbuf->ackno);
+
+ /* Check how many of the outstanding bytes have been acknowledged. For
+ * a most uIP send operation, this should always be true. However,
+ * the send() API sends data ahead when it can without waiting for
+ * the ACK. In this case, the 'ackseq' could be less than then the
+ * new sequence number.
+ */
+
+ if (ackseq <= unackseq)
+ {
+ /* Calculate the new number of oustanding, unacknowledged bytes */
+
+ conn->unacked = unackseq - ackseq;
+ }
+ else
+ {
+ /* What would it mean if ackseq > unackseq? The peer has ACKed
+ * more bytes than we think we have sent? Someone has lost it.
+ * Complain and reset the number of outstanding, unackowledged
+ * bytes
+ */
+
+ nlldbg("ERROR: ackseq[%08x] > unackseq[%08x]\n", ackseq, unackseq);
+ conn->unacked = 0;
+ }
+
+ /* Update sequence number to the unacknowledge sequence number. If
+ * there is still outstanding, unacknowledged data, then this will
+ * be beyond ackseq.
+ */
+
+ nllvdbg("sndseq: %08x->%08x unackseq: %08x new unacked: %d\n",
+ conn->sndseq, ackseq, unackseq, conn->unacked);
+ uip_tcpsetsequence(conn->sndseq, ackseq);
+
+ /* Do RTT estimation, unless we have done retransmissions. */
+
+ if (conn->nrtx == 0)
+ {
+ signed char m;
+ m = conn->rto - conn->timer;
+
+ /* This is taken directly from VJs original code in his paper */
+
+ m = m - (conn->sa >> 3);
+ conn->sa += m;
+ if (m < 0)
+ {
+ m = -m;
+ }
+
+ m = m - (conn->sv >> 2);
+ conn->sv += m;
+ conn->rto = (conn->sa >> 3) + conn->sv;
+ }
+
+ /* Set the acknowledged flag. */
+
+ flags |= UIP_ACKDATA;
+
+ /* Reset the retransmission timer. */
+
+ conn->timer = conn->rto;
+ }
+
+ /* Do different things depending on in what state the connection is. */
+
+ switch (conn->tcpstateflags & UIP_TS_MASK)
+ {
+ /* CLOSED and LISTEN are not handled here. CLOSE_WAIT is not
+ * implemented, since we force the application to close when the
+ * peer sends a FIN (hence the application goes directly from
+ * ESTABLISHED to LAST_ACK).
+ */
+
+ case UIP_SYN_RCVD:
+ /* In SYN_RCVD we have sent out a SYNACK in response to a SYN, and
+ * we are waiting for an ACK that acknowledges the data we sent
+ * out the last time. Therefore, we want to have the UIP_ACKDATA
+ * flag set. If so, we enter the ESTABLISHED state.
+ */
+
+ if ((flags & UIP_ACKDATA) != 0)
+ {
+ conn->tcpstateflags = UIP_ESTABLISHED;
+ conn->unacked = 0;
+ nllvdbg("TCP state: UIP_ESTABLISHED\n");
+
+ flags = UIP_CONNECTED;
+
+ if (dev->d_len > 0)
+ {
+ flags |= UIP_NEWDATA;
+ uip_incr32(conn->rcvseq, dev->d_len);
+ }
+
+ dev->d_sndlen = 0;
+ result = uip_tcpcallback(dev, conn, flags);
+ uip_tcpappsend(dev, conn, result);
+ return;
+ }
+
+ /* We need to retransmit the SYNACK */
+
+ if ((pbuf->flags & TCP_CTL) == TCP_SYN)
+ {
+ uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
+ return;
+ }
+ goto drop;
+
+ case UIP_SYN_SENT:
+ /* In SYN_SENT, we wait for a SYNACK that is sent in response to
+ * our SYN. The rcvseq is set to sequence number in the SYNACK
+ * plus one, and we send an ACK. We move into the ESTABLISHED
+ * state.
+ */
+
+ if ((flags & UIP_ACKDATA) != 0 && (pbuf->flags & TCP_CTL) == (TCP_SYN | TCP_ACK))
+ {
+ /* Parse the TCP MSS option, if present. */
+
+ if ((pbuf->tcpoffset & 0xf0) > 0x50)
+ {
+ for (i = 0; i < ((pbuf->tcpoffset >> 4) - 5) << 2 ;)
+ {
+ opt = dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + i];
+ if (opt == TCP_OPT_END)
+ {
+ /* End of options. */
+
+ break;
+ }
+ else if (opt == TCP_OPT_NOOP)
+ {
+ /* NOP option. */
+
+ ++i;
+ }
+ else if (opt == TCP_OPT_MSS &&
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == TCP_OPT_MSS_LEN)
+ {
+ /* An MSS option with the right option length. */
+
+ tmp16 =
+ (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + i] << 8) |
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 3 + i];
+ conn->initialmss =
+ conn->mss =
+ tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
+
+ /* And we are done processing options. */
+
+ break;
+ }
+ else
+ {
+ /* All other options have a length field, so that we
+ * easily can skip past them.
+ */
+
+ if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == 0)
+ {
+ /* If the length field is zero, the options are
+ * malformed and we don't process them further.
+ */
+
+ break;
+ }
+ i += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i];
+ }
+ }
+ }
+
+ conn->tcpstateflags = UIP_ESTABLISHED;
+ memcpy(conn->rcvseq, pbuf->seqno, 4);
+ nllvdbg("TCP state: UIP_ESTABLISHED\n");
+
+ uip_incr32(conn->rcvseq, 1);
+ conn->unacked = 0;
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+ result = uip_tcpcallback(dev, conn, UIP_CONNECTED | UIP_NEWDATA);
+ uip_tcpappsend(dev, conn, result);
+ return;
+ }
+
+ /* Inform the application that the connection failed */
+
+ (void)uip_tcpcallback(dev, conn, UIP_ABORT);
+
+ /* The connection is closed after we send the RST */
+
+ conn->tcpstateflags = UIP_CLOSED;
+ nllvdbg("Connection failed - TCP state: UIP_CLOSED\n");
+
+ /* We do not send resets in response to resets. */
+
+ if ((pbuf->flags & TCP_RST) != 0)
+ {
+ goto drop;
+ }
+ uip_tcpreset(dev);
+ return;
+
+ case UIP_ESTABLISHED:
+ /* In the ESTABLISHED state, we call upon the application to feed
+ * data into the d_buf. If the UIP_ACKDATA flag is set, the
+ * application should put new data into the buffer, otherwise we are
+ * retransmitting an old segment, and the application should put that
+ * data into the buffer.
+ *
+ * If the incoming packet is a FIN, we should close the connection on
+ * this side as well, and we send out a FIN and enter the LAST_ACK
+ * state. We require that there is no outstanding data; otherwise the
+ * sequence numbers will be screwed up.
+ */
+
+ if ((pbuf->flags & TCP_FIN) != 0 && (conn->tcpstateflags & UIP_STOPPED) == 0)
+ {
+ if (conn->unacked > 0)
+ {
+ goto drop;
+ }
+
+ /* Update the sequence number and indicate that the connection has
+ * been closed.
+ */
+
+ uip_incr32(conn->rcvseq, dev->d_len + 1);
+ flags |= UIP_CLOSE;
+
+ if (dev->d_len > 0)
+ {
+ flags |= UIP_NEWDATA;
+ }
+
+ (void)uip_tcpcallback(dev, conn, flags);
+
+ conn->tcpstateflags = UIP_LAST_ACK;
+ conn->unacked = 1;
+ conn->nrtx = 0;
+ nllvdbg("TCP state: UIP_LAST_ACK\n");
+
+ uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+
+ /* Check the URG flag. If this is set, the segment carries urgent
+ * data that we must pass to the application.
+ */
+
+ if ((pbuf->flags & TCP_URG) != 0)
+ {
+#ifdef CONFIG_NET_TCPURGDATA
+ dev->d_urglen = (pbuf->urgp[0] << 8) | pbuf->urgp[1];
+ if (dev->d_urglen > dev->d_len)
+ {
+ /* There is more urgent data in the next segment to come. */
+
+ dev->d_urglen = dev->d_len;
+ }
+
+ uip_incr32(conn->rcvseq, dev->d_urglen);
+ dev->d_len -= dev->d_urglen;
+ dev->d_urgdata = dev->d_appdata;
+ dev->d_appdata += dev->d_urglen;
+ }
+ else
+ {
+ dev->d_urglen = 0;
+#else /* CONFIG_NET_TCPURGDATA */
+ dev->d_appdata = ((uint8_t*)dev->d_appdata) + ((pbuf->urgp[0] << 8) | pbuf->urgp[1]);
+ dev->d_len -= (pbuf->urgp[0] << 8) | pbuf->urgp[1];
+#endif /* CONFIG_NET_TCPURGDATA */
+ }
+
+ /* If d_len > 0 we have TCP data in the packet, and we flag this
+ * by setting the UIP_NEWDATA flag. If the application has stopped
+ * the dataflow using uip_stop(), we must not accept any data
+ * packets from the remote host.
+ */
+
+ if (dev->d_len > 0 && (conn->tcpstateflags & UIP_STOPPED) == 0)
+ {
+ flags |= UIP_NEWDATA;
+ }
+
+ /* Check if the available buffer space advertised by the other end
+ * is smaller than the initial MSS for this connection. If so, we
+ * set the current MSS to the window size to ensure that the
+ * application does not send more data than the other end can
+ * handle.
+ *
+ * If the remote host advertises a zero window, we set the MSS to
+ * the initial MSS so that the application will send an entire MSS
+ * of data. This data will not be acknowledged by the receiver,
+ * and the application will retransmit it. This is called the
+ * "persistent timer" and uses the retransmission mechanim.
+ */
+
+ tmp16 = ((uint16_t)pbuf->wnd[0] << 8) + (uint16_t)pbuf->wnd[1];
+ if (tmp16 > conn->initialmss || tmp16 == 0)
+ {
+ tmp16 = conn->initialmss;
+ }
+ conn->mss = tmp16;
+
+ /* If this packet constitutes an ACK for outstanding data (flagged
+ * by the UIP_ACKDATA flag), we should call the application since it
+ * might want to send more data. If the incoming packet had data
+ * from the peer (as flagged by the UIP_NEWDATA flag), the
+ * application must also be notified.
+ *
+ * When the application is called, the d_len field
+ * contains the length of the incoming data. The application can
+ * access the incoming data through the global pointer
+ * d_appdata, which usually points UIP_IPTCPH_LEN + UIP_LLH_LEN
+ * bytes into the d_buf array.
+ *
+ * If the application wishes to send any data, this data should be
+ * put into the d_appdata and the length of the data should be
+ * put into d_len. If the application don't have any data to
+ * send, d_len must be set to 0.
+ */
+
+ if ((flags & (UIP_NEWDATA | UIP_ACKDATA)) != 0)
+ {
+ /* Clear sndlen and remember the size in d_len. The application
+ * may modify d_len and we will need this value later when we
+ * update the sequence number.
+ */
+
+ dev->d_sndlen = 0;
+ len = dev->d_len;
+
+ /* Provide the packet to the application */
+
+ result = uip_tcpcallback(dev, conn, flags);
+
+ /* If the application successfully handled the incoming data,
+ * then UIP_SNDACK will be set in the result. In this case,
+ * we need to update the sequence number. The ACK will be
+ * send by uip_tcpappsend().
+ */
+
+ if ((result & UIP_SNDACK) != 0)
+ {
+ /* Update the sequence number using the saved length */
+
+ uip_incr32(conn->rcvseq, len);
+ }
+
+ /* Send the response, ACKing the data or not, as appropriate */
+
+ uip_tcpappsend(dev, conn, result);
+ return;
+ }
+ goto drop;
+
+ case UIP_LAST_ACK:
+ /* We can close this connection if the peer has acknowledged our
+ * FIN. This is indicated by the UIP_ACKDATA flag.
+ */
+
+ if ((flags & UIP_ACKDATA) != 0)
+ {
+ conn->tcpstateflags = UIP_CLOSED;
+ nllvdbg("UIP_LAST_ACK TCP state: UIP_CLOSED\n");
+
+ (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
+ }
+ break;
+
+ case UIP_FIN_WAIT_1:
+ /* The application has closed the connection, but the remote host
+ * hasn't closed its end yet. Thus we do nothing but wait for a
+ * FIN from the other side.
+ */
+
+ if (dev->d_len > 0)
+ {
+ uip_incr32(conn->rcvseq, dev->d_len);
+ }
+
+ if ((pbuf->flags & TCP_FIN) != 0)
+ {
+ if ((flags & UIP_ACKDATA) != 0)
+ {
+ conn->tcpstateflags = UIP_TIME_WAIT;
+ conn->timer = 0;
+ conn->unacked = 0;
+ nllvdbg("TCP state: UIP_TIME_WAIT\n");
+ }
+ else
+ {
+ conn->tcpstateflags = UIP_CLOSING;
+ nllvdbg("TCP state: UIP_CLOSING\n");
+ }
+
+ uip_incr32(conn->rcvseq, 1);
+ (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+ else if ((flags & UIP_ACKDATA) != 0)
+ {
+ conn->tcpstateflags = UIP_FIN_WAIT_2;
+ conn->unacked = 0;
+ nllvdbg("TCP state: UIP_FIN_WAIT_2\n");
+ goto drop;
+ }
+
+ if (dev->d_len > 0)
+ {
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+ goto drop;
+
+ case UIP_FIN_WAIT_2:
+ if (dev->d_len > 0)
+ {
+ uip_incr32(conn->rcvseq, dev->d_len);
+ }
+
+ if ((pbuf->flags & TCP_FIN) != 0)
+ {
+ conn->tcpstateflags = UIP_TIME_WAIT;
+ conn->timer = 0;
+ nllvdbg("TCP state: UIP_TIME_WAIT\n");
+
+ uip_incr32(conn->rcvseq, 1);
+ (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+
+ if (dev->d_len > 0)
+ {
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+ }
+ goto drop;
+
+ case UIP_TIME_WAIT:
+ uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
+ return;
+
+ case UIP_CLOSING:
+ if ((flags & UIP_ACKDATA) != 0)
+ {
+ conn->tcpstateflags = UIP_TIME_WAIT;
+ conn->timer = 0;
+ nllvdbg("TCP state: UIP_TIME_WAIT\n");
+ }
+
+ default:
+ break;
+ }
+
+drop:
+ dev->d_len = 0;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcppoll.c b/nuttx/net/uip/uip_tcppoll.c
new file mode 100644
index 000000000..29cb6d4b4
--- /dev/null
+++ b/nuttx/net/uip/uip_tcppoll.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * net/uip/uip_tcppoll.c
+ * Poll for the availability of TCP TX data
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcppoll
+ *
+ * Description:
+ * Poll a TCP connection structure for availability of TX data
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP "connection" to poll for TX data
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcppoll(struct uip_driver_s *dev, struct uip_conn *conn)
+{
+ uint8_t result;
+
+ /* Verify that the connection is established */
+
+ if ((conn->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
+ {
+ /* Set up for the callback */
+
+ dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+ dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+
+ /* Perfom the callback */
+
+ result = uip_tcpcallback(dev, conn, UIP_POLL);
+
+ /* Handle the callback response */
+
+ uip_tcpappsend(dev, conn, result);
+ }
+ else
+ {
+ /* Nothing to do for this connection */
+
+ dev->d_len = 0;
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpreadahead.c b/nuttx/net/uip/uip_tcpreadahead.c
new file mode 100644
index 000000000..21ed58b99
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpreadahead.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ * net/uip/uip_tcpreadahead.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/net/uip/uipopt.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) && (CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0)
+
+#include <queue.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uip.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* These are the pre-allocated read-ahead buffers */
+
+static struct uip_readahead_s g_buffers[CONFIG_NET_NTCP_READAHEAD_BUFFERS];
+
+/* This is the list of available read-ahead buffers */
+
+static sq_queue_t g_freebuffers;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_tcpreadaheadinit
+ *
+ * Description:
+ * Initialize the list of free read-ahead buffers
+ *
+ * Assumptions:
+ * Called once early initialization.
+ *
+ ****************************************************************************/
+
+void uip_tcpreadaheadinit(void)
+{
+ int i;
+
+ sq_init(&g_freebuffers);
+ for (i = 0; i < CONFIG_NET_NTCP_READAHEAD_BUFFERS; i++)
+ {
+ sq_addfirst(&g_buffers[i].rh_node, &g_freebuffers);
+ }
+}
+
+/****************************************************************************
+ * Function: uip_tcpreadaheadalloc
+ *
+ * Description:
+ * Allocate a TCP read-ahead buffer by taking a pre-allocated buffer from
+ * the free list. This function is called from TCP logic when new,
+ * incoming TCP data is received but there is no user logic recving the
+ * the data. Note: malloc() cannot be used because this function is
+ * called from interrupt level.
+ *
+ * Assumptions:
+ * Called from interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+struct uip_readahead_s *uip_tcpreadaheadalloc(void)
+{
+ return (struct uip_readahead_s*)sq_remfirst(&g_freebuffers);
+}
+
+/****************************************************************************
+ * Function: uip_tcpreadaheadrelease
+ *
+ * Description:
+ * Release a TCP read-ahead buffer by returning the buffer to the free list.
+ * This function is called from user logic after it is consumed the buffered
+ * data.
+ *
+ * Assumptions:
+ * Called from user logic BUT with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpreadaheadrelease(struct uip_readahead_s *buf)
+{
+ sq_addfirst(&buf->rh_node, &g_freebuffers);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP && CONFIG_NET_NTCP_READAHEAD_BUFFERS*/
diff --git a/nuttx/net/uip/uip_tcpsend.c b/nuttx/net/uip/uip_tcpsend.c
new file mode 100644
index 000000000..7051d7621
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpsend.c
@@ -0,0 +1,369 @@
+/****************************************************************************
+ * net/uip/uip_tcpsend.c
+ *
+ * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <string.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpsendcomplete
+ *
+ * Description:
+ * Complete the final portions of the send operation. This function sets
+ * up IP header and computes the TCP checksum
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+static void uip_tcpsendcomplete(struct uip_driver_s *dev)
+{
+ struct uip_tcpip_hdr *pbuf = BUF;
+
+ pbuf->ttl = UIP_TTL;
+
+#ifdef CONFIG_NET_IPv6
+
+ /* For IPv6, the IP length field does not include the IPv6 IP header
+ * length.
+ */
+
+ pbuf->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
+ pbuf->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
+
+#else /* CONFIG_NET_IPv6 */
+
+ pbuf->len[0] = (dev->d_len >> 8);
+ pbuf->len[1] = (dev->d_len & 0xff);
+
+#endif /* CONFIG_NET_IPv6 */
+
+ pbuf->urgp[0] = pbuf->urgp[1] = 0;
+
+ /* Calculate TCP checksum. */
+
+ pbuf->tcpchksum = 0;
+ pbuf->tcpchksum = ~(uip_tcpchksum(dev));
+
+#ifdef CONFIG_NET_IPv6
+
+ pbuf->vtc = 0x60;
+ pbuf->tcf = 0x00;
+ pbuf->flow = 0x00;
+
+#else /* CONFIG_NET_IPv6 */
+
+ pbuf->vhl = 0x45;
+ pbuf->tos = 0;
+ pbuf->ipoffset[0] = 0;
+ pbuf->ipoffset[1] = 0;
+ ++g_ipid;
+ pbuf->ipid[0] = g_ipid >> 8;
+ pbuf->ipid[1] = g_ipid & 0xff;
+
+ /* Calculate IP checksum. */
+
+ pbuf->ipchksum = 0;
+ pbuf->ipchksum = ~(uip_ipchksum(dev));
+
+#endif /* CONFIG_NET_IPv6 */
+
+ nllvdbg("Outgoing TCP packet length: %d (%d)\n",
+ dev->d_len, (pbuf->len[0] << 8) | pbuf->len[1]);
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.sent++;
+ uip_stat.ip.sent++;
+#endif
+}
+
+/****************************************************************************
+ * Name: uip_tcpsendcommon
+ *
+ * Description:
+ * We're done with the input processing. We are now ready to send a reply
+ * Our job is to fill in all the fields of the TCP and IP headers before
+ * calculating the checksum and finally send the packet.
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP connection structure holding connection information
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+static void uip_tcpsendcommon(struct uip_driver_s *dev, struct uip_conn *conn)
+{
+ struct uip_tcpip_hdr *pbuf = BUF;
+
+ memcpy(pbuf->ackno, conn->rcvseq, 4);
+ memcpy(pbuf->seqno, conn->sndseq, 4);
+
+ pbuf->proto = UIP_PROTO_TCP;
+ pbuf->srcport = conn->lport;
+ pbuf->destport = conn->rport;
+
+ uiphdr_ipaddr_copy(pbuf->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(pbuf->destipaddr, &conn->ripaddr);
+
+ if (conn->tcpstateflags & UIP_STOPPED)
+ {
+ /* If the connection has issued uip_stop(), we advertise a zero
+ * window so that the remote host will stop sending data.
+ */
+
+ pbuf->wnd[0] = 0;
+ pbuf->wnd[1] = 0;
+ }
+ else
+ {
+ pbuf->wnd[0] = ((CONFIG_NET_RECEIVE_WINDOW) >> 8);
+ pbuf->wnd[1] = ((CONFIG_NET_RECEIVE_WINDOW) & 0xff);
+ }
+
+ /* Finish the IP portion of the message, calculate checksums and send
+ * the message.
+ */
+
+ uip_tcpsendcomplete(dev);
+
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpsend
+ *
+ * Description:
+ * Setup to send a TCP packet
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP connection structure holding connection information
+ * flags - flags to apply to the TCP header
+ * len - length of the message
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn,
+ uint16_t flags, uint16_t len)
+{
+ struct uip_tcpip_hdr *pbuf = BUF;
+
+ pbuf->flags = flags;
+ dev->d_len = len;
+ pbuf->tcpoffset = (UIP_TCPH_LEN / 4) << 4;
+ uip_tcpsendcommon(dev, conn);
+}
+
+/****************************************************************************
+ * Name: uip_tcpreset
+ *
+ * Description:
+ * Send a TCP reset (no-data) message
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpreset(struct uip_driver_s *dev)
+{
+ struct uip_tcpip_hdr *pbuf = BUF;
+
+ uint16_t tmp16;
+ uint8_t seqbyte;
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.rst++;
+#endif
+
+ pbuf->flags = TCP_RST | TCP_ACK;
+ dev->d_len = UIP_IPTCPH_LEN;
+ pbuf->tcpoffset = 5 << 4;
+
+ /* Flip the seqno and ackno fields in the TCP header. */
+
+ seqbyte = pbuf->seqno[3];
+ pbuf->seqno[3] = pbuf->ackno[3];
+ pbuf->ackno[3] = seqbyte;
+
+ seqbyte = pbuf->seqno[2];
+ pbuf->seqno[2] = pbuf->ackno[2];
+ pbuf->ackno[2] = seqbyte;
+
+ seqbyte = pbuf->seqno[1];
+ pbuf->seqno[1] = pbuf->ackno[1];
+ pbuf->ackno[1] = seqbyte;
+
+ seqbyte = pbuf->seqno[0];
+ pbuf->seqno[0] = pbuf->ackno[0];
+ pbuf->ackno[0] = seqbyte;
+
+ /* We also have to increase the sequence number we are
+ * acknowledging. If the least significant byte overflowed, we need
+ * to propagate the carry to the other bytes as well.
+ */
+
+ if (++(pbuf->ackno[3]) == 0)
+ {
+ if (++(pbuf->ackno[2]) == 0)
+ {
+ if (++(pbuf->ackno[1]) == 0)
+ {
+ ++(pbuf->ackno[0]);
+ }
+ }
+ }
+
+ /* Swap port numbers. */
+
+ tmp16 = pbuf->srcport;
+ pbuf->srcport = pbuf->destport;
+ pbuf->destport = tmp16;
+
+ /* Swap IP addresses. */
+
+ uiphdr_ipaddr_copy(pbuf->destipaddr, pbuf->srcipaddr);
+ uiphdr_ipaddr_copy(pbuf->srcipaddr, &dev->d_ipaddr);
+
+ /* And send out the RST packet */
+
+ uip_tcpsendcomplete(dev);
+}
+
+/****************************************************************************
+ * Name: uip_tcpack
+ *
+ * Description:
+ * Send the SYN or SYNACK response.
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP connection structure holding connection information
+ * ack - The ACK response to send
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn, uint8_t ack)
+{
+ struct uip_tcpip_hdr *pbuf = BUF;
+
+ /* Save the ACK bits */
+
+ pbuf->flags = ack;
+
+ /* We send out the TCP Maximum Segment Size option with our ack. */
+
+ pbuf->optdata[0] = TCP_OPT_MSS;
+ pbuf->optdata[1] = TCP_OPT_MSS_LEN;
+ pbuf->optdata[2] = (UIP_TCP_MSS) / 256;
+ pbuf->optdata[3] = (UIP_TCP_MSS) & 255;
+ dev->d_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN;
+ pbuf->tcpoffset = ((UIP_TCPH_LEN + TCP_OPT_MSS_LEN) / 4) << 4;
+
+ /* Complete the common portions of the TCP message */
+
+ uip_tcpsendcommon(dev, conn);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpseqno.c b/nuttx/net/uip/uip_tcpseqno.c
new file mode 100755
index 000000000..eab3a054a
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpseqno.c
@@ -0,0 +1,173 @@
+/****************************************************************************
+ * net/uip/uip_tcpseqno.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Large parts of this file were leveraged from uIP logic:
+ *
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* g_tcpsequence is used to generate initial TCP sequence numbers */
+
+static uint32_t g_tcpsequence;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpsetsequence
+ *
+ * Description:
+ * Set the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value)
+{
+ /* Copy the sequence number in network (big-endian) order */
+
+ *seqno++ = value >> 24;
+ *seqno++ = (value >> 16) & 0xff;
+ *seqno++ = (value >> 8) & 0xff;
+ *seqno = value & 0xff;
+}
+
+/****************************************************************************
+ * Name: uip_tcpgetsequence
+ *
+ * Description:
+ * Get the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+uint32_t uip_tcpgetsequence(FAR uint8_t *seqno)
+{
+ uint32_t value;
+
+ /* Combine the sequence number from network (big-endian) order */
+
+ value = (uint32_t)seqno[0] << 24 |
+ (uint32_t)seqno[1] << 16 |
+ (uint32_t)seqno[2] << 8 |
+ (uint32_t)seqno[3];
+ return value;
+}
+
+/****************************************************************************
+ * Name: uip_tcpaddsequence
+ *
+ * Description:
+ * Add the length to get the next TCP sequence number.
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len)
+{
+ return uip_tcpgetsequence(seqno) + (uint32_t)len;
+}
+
+/****************************************************************************
+ * Name: uip_tcpinitsequence
+ *
+ * Description:
+ * Set the (initial) the TCP/IP sequence number when a TCP connection is
+ * established.
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpinitsequence(FAR uint8_t *seqno)
+{
+ uip_tcpsetsequence(seqno, g_tcpsequence);
+}
+
+/****************************************************************************
+ * Name: uip_tcpnextsequence
+ *
+ * Description:
+ * Increment the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function is called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpnextsequence(void)
+{
+ g_tcpsequence++;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcptimer.c b/nuttx/net/uip/uip_tcptimer.c
new file mode 100644
index 000000000..c95376ab0
--- /dev/null
+++ b/nuttx/net/uip/uip_tcptimer.c
@@ -0,0 +1,250 @@
+/****************************************************************************
+ * net/uip/uip_tcptimer.c
+ * Poll for the availability of TCP TX data
+ *
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcptimer
+ *
+ * Description:
+ * Handle a TCP timer expiration for the provided TCP connection
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The TCP "connection" to poll for TX data
+ * hsed - The polling interval in halves of a second
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_tcptimer(struct uip_driver_s *dev, struct uip_conn *conn, int hsec)
+{
+ uint8_t result;
+
+ dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+ dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+
+ /* Increase the TCP sequence number */
+
+ uip_tcpnextsequence();
+
+ /* Reset the length variables. */
+
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+
+ /* Check if the connection is in a state in which we simply wait
+ * for the connection to time out. If so, we increase the
+ * connection's timer and remove the connection if it times
+ * out.
+ */
+
+ if (conn->tcpstateflags == UIP_TIME_WAIT || conn->tcpstateflags == UIP_FIN_WAIT_2)
+ {
+ /* Increment the connection timer */
+
+ (conn->timer) += hsec;
+ if (conn->timer >= UIP_TIME_WAIT_TIMEOUT)
+ {
+ conn->tcpstateflags = UIP_CLOSED;
+ nllvdbg("TCP state: UIP_CLOSED\n");
+ }
+ }
+ else if (conn->tcpstateflags != UIP_CLOSED)
+ {
+ /* If the connection has outstanding data, we increase the connection's
+ * timer and see if it has reached the RTO value in which case we
+ * retransmit.
+ */
+
+ if (conn->unacked > 0)
+ {
+ /* The connection has outstanding data */
+
+ if (conn->timer > hsec)
+ {
+ /* Will not yet decrement to zero */
+
+ conn->timer -= hsec;
+ }
+ else
+ {
+ /* Will decrement to zero */
+
+ conn->timer = 0;
+
+ /* Should we close the connection? */
+
+ if (conn->nrtx == UIP_MAXRTX ||
+ ((conn->tcpstateflags == UIP_SYN_SENT ||
+ conn->tcpstateflags == UIP_SYN_RCVD) &&
+ conn->nrtx == UIP_MAXSYNRTX))
+ {
+ conn->tcpstateflags = UIP_CLOSED;
+ nllvdbg("TCP state: UIP_CLOSED\n");
+
+ /* We call uip_tcpcallback() with UIP_TIMEDOUT to
+ * inform the application that the connection has
+ * timed out.
+ */
+
+ result = uip_tcpcallback(dev, conn, UIP_TIMEDOUT);
+
+ /* We also send a reset packet to the remote host. */
+
+ uip_tcpsend(dev, conn, TCP_RST | TCP_ACK, UIP_IPTCPH_LEN);
+ goto done;
+ }
+
+ /* Exponential backoff. */
+
+ conn->timer = UIP_RTO << (conn->nrtx > 4 ? 4: conn->nrtx);
+ (conn->nrtx)++;
+
+ /* Ok, so we need to retransmit. We do this differently
+ * depending on which state we are in. In ESTABLISHED, we
+ * call upon the application so that it may prepare the
+ * data for the retransmit. In SYN_RCVD, we resend the
+ * SYNACK that we sent earlier and in LAST_ACK we have to
+ * retransmit our FINACK.
+ */
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.rexmit++;
+#endif
+ switch(conn->tcpstateflags & UIP_TS_MASK)
+ {
+ case UIP_SYN_RCVD:
+ /* In the SYN_RCVD state, we should retransmit our
+ * SYNACK.
+ */
+
+ uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
+ goto done;
+
+ case UIP_SYN_SENT:
+ /* In the SYN_SENT state, we retransmit out SYN. */
+
+ uip_tcpack(dev, conn, TCP_SYN);
+ goto done;
+
+ case UIP_ESTABLISHED:
+ /* In the ESTABLISHED state, we call upon the application
+ * to do the actual retransmit after which we jump into
+ * the code for sending out the packet.
+ */
+
+ result = uip_tcpcallback(dev, conn, UIP_REXMIT);
+ uip_tcprexmit(dev, conn, result);
+ goto done;
+
+ case UIP_FIN_WAIT_1:
+ case UIP_CLOSING:
+ case UIP_LAST_ACK:
+ /* In all these states we should retransmit a FINACK. */
+
+ uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
+ goto done;
+ }
+ }
+ }
+
+ /* The connection does not have outstanding data */
+
+ else if ((conn->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
+ {
+ /* If there was no need for a retransmission, we poll the
+ * application for new data.
+ */
+
+ result = uip_tcpcallback(dev, conn, UIP_POLL);
+ uip_tcpappsend(dev, conn, result);
+ goto done;
+ }
+ }
+
+ /* Nothing to be done */
+
+ dev->d_len = 0;
+
+done:
+ return;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_udpcallback.c b/nuttx/net/uip/uip_udpcallback.c
new file mode 100644
index 000000000..f00c5e0f8
--- /dev/null
+++ b/nuttx/net/uip/uip_udpcallback.c
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * net/uip/uip_udpcallback.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_udpcallback
+ *
+ * Description:
+ * Inform the application holding the UDP socket of a change in state.
+ *
+ * Assumptions:
+ * This function is called at the interrupt level with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_udpcallback(struct uip_driver_s *dev, struct uip_udp_conn *conn,
+ uint16_t flags)
+{
+ nllvdbg("flags: %04x\n", flags);
+
+ /* Some sanity checking */
+
+ if (conn)
+ {
+ /* Perform the callback */
+
+ flags = uip_callbackexecute(dev, conn, flags, conn->list);
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpconn.c b/nuttx/net/uip/uip_udpconn.c
new file mode 100644
index 000000000..3c4ee5add
--- /dev/null
+++ b/nuttx/net/uip/uip_udpconn.c
@@ -0,0 +1,492 @@
+/****************************************************************************
+ * net/uip/uip_udpconn.c
+ *
+ * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Large parts of this file were leveraged from uIP logic:
+ *
+ * Copyright (c) 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+#include <stdint.h>
+#include <string.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The array containing all uIP UDP connections. */
+
+struct uip_udp_conn g_udp_connections[CONFIG_NET_UDP_CONNS];
+
+/* A list of all free UDP connections */
+
+static dq_queue_t g_free_udp_connections;
+static sem_t g_free_sem;
+
+/* A list of all allocated UDP connections */
+
+static dq_queue_t g_active_udp_connections;
+
+/* Last port used by a UDP connection connection. */
+
+static uint16_t g_last_udp_port;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _uip_semtake() and _uip_semgive()
+ *
+ * Description:
+ * Take/give semaphore
+ *
+ ****************************************************************************/
+
+static inline void _uip_semtake(sem_t *sem)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (uip_lockedwait(sem) != 0)
+ {
+ /* The only case that an error should occur here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(*get_errno_ptr() == EINTR);
+ }
+}
+
+#define _uip_semgive(sem) sem_post(sem)
+
+/****************************************************************************
+ * Name: uip_find_conn()
+ *
+ * Description:
+ * Find the UDP connection that uses this local port number. Called only
+ * from user user level code, but with interrupts disabled.
+ *
+ ****************************************************************************/
+
+static struct uip_udp_conn *uip_find_conn(uint16_t portno)
+{
+ int i;
+
+ /* Now search each connection structure.*/
+
+ for (i = 0; i < CONFIG_NET_UDP_CONNS; i++)
+ {
+ if (g_udp_connections[ i ].lport == portno)
+ {
+ return &g_udp_connections[ i ];
+ }
+ }
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: uip_selectport()
+ *
+ * Description:
+ * Select an unused port number.
+ *
+ * NOTE that in prinicple this function could fail if there is no available
+ * port number. There is no check for that case and it would actually
+ * in an infinite loop if that were the case. In this simple, small UDP
+ * implementation, it is reasonable to assume that that error cannot happen
+ * and that a port number will always be available.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Return:
+ * Next available port number
+ *
+ ****************************************************************************/
+
+static uint16_t uip_selectport(void)
+{
+ uint16_t portno;
+
+ /* Find an unused local port number. Loop until we find a valid
+ * listen port number that is not being used by any other connection.
+ */
+
+ uip_lock_t flags = uip_lock();
+ do
+ {
+ /* Guess that the next available port number will be the one after
+ * the last port number assigned.
+ */
+
+ ++g_last_udp_port;
+
+ /* Make sure that the port number is within range */
+
+ if (g_last_udp_port >= 32000)
+ {
+ g_last_udp_port = 4096;
+ }
+ }
+ while (uip_find_conn(htons(g_last_udp_port)));
+
+ /* Initialize and return the connection structure, bind it to the
+ * port number
+ */
+
+ portno = g_last_udp_port;
+ uip_unlock(flags);
+
+ return portno;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_udpinit()
+ *
+ * Description:
+ * Initialize the UDP connection structures. Called once and only from
+ * the UIP layer.
+ *
+ ****************************************************************************/
+
+void uip_udpinit(void)
+{
+ int i;
+
+ /* Initialize the queues */
+
+ dq_init(&g_free_udp_connections);
+ dq_init(&g_active_udp_connections);
+ sem_init(&g_free_sem, 0, 1);
+
+ for (i = 0; i < CONFIG_NET_UDP_CONNS; i++)
+ {
+ /* Mark the connection closed and move it to the free list */
+
+ g_udp_connections[i].lport = 0;
+ dq_addlast(&g_udp_connections[i].node, &g_free_udp_connections);
+ }
+
+ g_last_udp_port = 1024;
+}
+
+/****************************************************************************
+ * Name: uip_udpalloc()
+ *
+ * Description:
+ * Alloc a new, uninitialized UDP connection structure.
+ *
+ ****************************************************************************/
+
+struct uip_udp_conn *uip_udpalloc(void)
+{
+ struct uip_udp_conn *conn;
+
+ /* The free list is only accessed from user, non-interrupt level and
+ * is protected by a semaphore (that behaves like a mutex).
+ */
+
+ _uip_semtake(&g_free_sem);
+ conn = (struct uip_udp_conn *)dq_remfirst(&g_free_udp_connections);
+ if (conn)
+ {
+ /* Make sure that the connection is marked as uninitialized */
+
+ conn->lport = 0;
+ }
+ _uip_semgive(&g_free_sem);
+ return conn;
+}
+
+/****************************************************************************
+ * Name: uip_udpfree()
+ *
+ * Description:
+ * Free a UDP connection structure that is no longer in use. This should be
+ * done by the implementation of close(). uip_udpdisable must have been
+ * previously called.
+ *
+ ****************************************************************************/
+
+void uip_udpfree(struct uip_udp_conn *conn)
+{
+ /* The free list is only accessed from user, non-interrupt level and
+ * is protected by a semaphore (that behaves like a mutex).
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+
+ _uip_semtake(&g_free_sem);
+ conn->lport = 0;
+ dq_addlast(&conn->node, &g_free_udp_connections);
+ _uip_semgive(&g_free_sem);
+}
+
+/****************************************************************************
+ * Name: uip_udpactive()
+ *
+ * Description:
+ * Find a connection structure that is the appropriate
+ * connection to be used withi the provided TCP/IP header
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level
+ *
+ ****************************************************************************/
+
+struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf)
+{
+ struct uip_udp_conn *conn = (struct uip_udp_conn *)g_active_udp_connections.head;
+
+ while (conn)
+ {
+ /* If the local UDP port is non-zero, the connection is considered
+ * to be used. If so, the local port number is checked against the
+ * destination port number in the received packet. If the two port
+ * numbers match, the remote port number is checked if the
+ * connection is bound to a remote port. Finally, if the
+ * connection is bound to a remote IP address, the source IP
+ * address of the packet is checked.
+ */
+
+ if (conn->lport != 0 && buf->destport == conn->lport &&
+ (conn->rport == 0 || buf->srcport == conn->rport) &&
+ (uip_ipaddr_cmp(conn->ripaddr, g_allzeroaddr) ||
+ uip_ipaddr_cmp(conn->ripaddr, g_alloneaddr) ||
+ uiphdr_ipaddr_cmp(buf->srcipaddr, &conn->ripaddr)))
+ {
+ /* Matching connection found.. return a reference to it */
+
+ break;
+ }
+
+ /* Look at the next active connection */
+
+ conn = (struct uip_udp_conn *)conn->node.flink;
+ }
+
+ return conn;
+}
+
+/****************************************************************************
+ * Name: uip_nextudpconn()
+ *
+ * Description:
+ * Traverse the list of allocated UDP connections
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level (or with
+ * interrupts disabled).
+ *
+ ****************************************************************************/
+
+struct uip_udp_conn *uip_nextudpconn(struct uip_udp_conn *conn)
+{
+ if (!conn)
+ {
+ return (struct uip_udp_conn *)g_active_udp_connections.head;
+ }
+ else
+ {
+ return (struct uip_udp_conn *)conn->node.flink;
+ }
+}
+
+/****************************************************************************
+ * Name: uip_udpbind()
+ *
+ * Description:
+ * This function implements the UIP specific parts of the standard UDP
+ * bind() operation.
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ int ret = -EADDRINUSE;
+ uip_lock_t flags;
+
+ /* Is the user requesting to bind to any port? */
+
+ if (!addr->sin_port)
+ {
+ /* Yes.. Find an unused local port number */
+
+ conn->lport = htons(uip_selectport());
+ ret = OK;
+ }
+ else
+ {
+ /* Interrupts must be disabled while access the UDP connection list */
+
+ flags = uip_lock();
+
+ /* Is any other UDP connection bound to this port? */
+
+ if (!uip_find_conn(addr->sin_port))
+ {
+ /* No.. then bind the socket to the port */
+
+ conn->lport = addr->sin_port;
+ ret = OK;
+ }
+
+ uip_unlock(flags);
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: uip_udpconnect()
+ *
+ * Description:
+ * This function sets up a new UDP connection. The function will
+ * automatically allocate an unused local port for the new
+ * connection. However, another port can be chosen by using the
+ * uip_udpbind() call, after the uip_udpconnect() function has been
+ * called.
+ *
+ * uip_udpenable() must be called before the connection is made active (i.e.,
+ * is eligible for callbacks.
+ *
+ * addr The address of the remote host.
+ *
+ * Assumptions:
+ * This function is called user code. Interrupts may be enabled.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ /* Has this address already been bound to a local port (lport)? */
+
+ if (!conn->lport)
+ {
+ /* No.. Find an unused local port number and bind it to the
+ * connection structure.
+ */
+
+ conn->lport = htons(uip_selectport());
+ }
+
+ /* Is there a remote port (rport) */
+
+ if (addr)
+ {
+ conn->rport = addr->sin_port;
+ uip_ipaddr_copy(conn->ripaddr, addr->sin_addr.s_addr);
+ }
+ else
+ {
+ conn->rport = 0;
+ uip_ipaddr_copy(conn->ripaddr, g_allzeroaddr);
+ }
+
+ conn->ttl = UIP_TTL;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: uip_udpenable() uip_udpdisable.
+ *
+ * Description:
+ * Enable/disable callbacks for the specified connection
+ *
+ * Assumptions:
+ * This function is called user code. Interrupts may be enabled.
+ *
+ ****************************************************************************/
+
+void uip_udpenable(struct uip_udp_conn *conn)
+{
+ /* Add the connection structure to the active connectionlist. This list
+ * is modifiable from interrupt level, we we must disable interrupts to
+ * access it safely.
+ */
+
+ uip_lock_t flags = uip_lock();
+ dq_addlast(&conn->node, &g_active_udp_connections);
+ uip_unlock(flags);
+}
+
+void uip_udpdisable(struct uip_udp_conn *conn)
+{
+ /* Remove the connection structure from the active connectionlist. This list
+ * is modifiable from interrupt level, we we must disable interrupts to
+ * access it safely.
+ */
+
+ uip_lock_t flags = uip_lock();
+ dq_rem(&conn->node, &g_active_udp_connections);
+ uip_unlock(flags);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpinput.c b/nuttx/net/uip/uip_udpinput.c
new file mode 100644
index 000000000..456c34799
--- /dev/null
+++ b/nuttx/net/uip/uip_udpinput.c
@@ -0,0 +1,156 @@
+/****************************************************************************
+ * net/uip/uip_udpinput.c
+ * Handling incoming UDP input
+ *
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_udpinput
+ *
+ * Description:
+ * Handle incoming UDP input
+ *
+ * Parameters:
+ * dev - The device driver structure containing the received UDP packet
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_udpinput(struct uip_driver_s *dev)
+{
+ struct uip_udp_conn *conn;
+ struct uip_udpip_hdr *pbuf = UDPBUF;
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.udp.recv++;
+#endif
+
+ /* UDP processing is really just a hack. We don't do anything to the UDP/IP
+ * headers, but let the UDP application do all the hard work. If the
+ * application sets d_sndlen, it has a packet to send.
+ */
+
+ dev->d_len -= UIP_IPUDPH_LEN;
+#ifdef CONFIG_NET_UDP_CHECKSUMS
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ if (pbuf->udpchksum != 0 && uip_udpchksum(dev) != 0xffff)
+ {
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.udp.drop++;
+ uip_stat.udp.chkerr++;
+#endif
+ nlldbg("Bad UDP checksum\n");
+ dev->d_len = 0;
+ }
+ else
+#endif
+ {
+ /* Demultiplex this UDP packet between the UDP "connections". */
+
+ conn = uip_udpactive(pbuf);
+ if (conn)
+ {
+ /* Setup for the application callback */
+
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ dev->d_sndlen = 0;
+
+ /* Perform the application callback */
+
+ uip_udpcallback(dev, conn, UIP_NEWDATA);
+
+ /* If the application has data to send, setup the UDP/IP header */
+
+ if (dev->d_sndlen > 0)
+ {
+ uip_udpsend(dev, conn);
+ }
+ }
+ else
+ {
+ nlldbg("No listener on UDP port\n");
+ dev->d_len = 0;
+ }
+ }
+
+ return;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udppoll.c b/nuttx/net/uip/uip_udppoll.c
new file mode 100644
index 000000000..984566ed4
--- /dev/null
+++ b/nuttx/net/uip/uip_udppoll.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ * net/uip/uip_udppoll.c
+ * Poll for the availability of UDP TX data
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_udppoll
+ *
+ * Description:
+ * Poll a UDP "connection" structure for availability of TX data
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The UDP "connection" to poll for TX data
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_udppoll(struct uip_driver_s *dev, struct uip_udp_conn *conn)
+{
+ /* Verify that the UDP connection is valid */
+
+ if (conn->lport != 0)
+ {
+ /* Setup for the application callback */
+
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+
+ /* Perform the application callback */
+
+ uip_udpcallback(dev, conn, UIP_POLL);
+
+ /* If the application has data to send, setup the UDP/IP header */
+
+ if (dev->d_sndlen > 0)
+ {
+ uip_udpsend(dev, conn);
+ return;
+ }
+ }
+
+ /* Make sure that d_len is zero meaning that there is nothing to be sent */
+
+ dev->d_len = 0;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpsend.c b/nuttx/net/uip/uip_udpsend.c
new file mode 100644
index 000000000..1dc33bbd1
--- /dev/null
+++ b/nuttx/net/uip/uip_udpsend.c
@@ -0,0 +1,177 @@
+/****************************************************************************
+ * net/uip/uip_udpsend.c
+ *
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Adapted for NuttX from logic in uIP which also has a BSD-like license:
+ *
+ * Original author Adam Dunkels <adam@dunkels.com>
+ * Copyright () 2001-2003, 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/uip/uip.h>
+#include <nuttx/net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_udpsend
+ *
+ * Description:
+ * Setup to send a UDP packet
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ * conn - The UDP "connection" structure holding port information
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_udpsend(struct uip_driver_s *dev, struct uip_udp_conn *conn)
+{
+ struct uip_udpip_hdr *pudpbuf = UDPBUF;
+
+ if (dev->d_sndlen > 0)
+ {
+ /* The total lenth to send is the size of the application data plus
+ * the IP and UDP headers (and, eventually, the ethernet header)
+ */
+
+ dev->d_len = dev->d_sndlen + UIP_IPUDPH_LEN;
+
+ /* Initialize the IP header. Note that for IPv6, the IP length field
+ * does not include the IPv6 IP header length.
+ */
+
+#ifdef CONFIG_NET_IPv6
+
+ pudpbuf->vtc = 0x60;
+ pudpbuf->tcf = 0x00;
+ pudpbuf->flow = 0x00;
+ pudpbuf->len[0] = (dev->d_sndlen >> 8);
+ pudpbuf->len[1] = (dev->d_sndlen & 0xff);
+ pudpbuf->nexthdr = UIP_PROTO_UDP;
+ pudpbuf->hoplimit = conn->ttl;
+
+ uip_ipaddr_copy(pudpbuf->srcipaddr, &dev->d_ipaddr);
+ uip_ipaddr_copy(pudpbuf->destipaddr, &conn->ripaddr);
+
+#else /* CONFIG_NET_IPv6 */
+
+ pudpbuf->vhl = 0x45;
+ pudpbuf->tos = 0;
+ pudpbuf->len[0] = (dev->d_len >> 8);
+ pudpbuf->len[1] = (dev->d_len & 0xff);
+ ++g_ipid;
+ pudpbuf->ipid[0] = g_ipid >> 8;
+ pudpbuf->ipid[1] = g_ipid & 0xff;
+ pudpbuf->ipoffset[0] = 0;
+ pudpbuf->ipoffset[1] = 0;
+ pudpbuf->ttl = conn->ttl;
+ pudpbuf->proto = UIP_PROTO_UDP;
+
+ uiphdr_ipaddr_copy(pudpbuf->srcipaddr, &dev->d_ipaddr);
+ uiphdr_ipaddr_copy(pudpbuf->destipaddr, &conn->ripaddr);
+
+ /* Calculate IP checksum. */
+
+ pudpbuf->ipchksum = 0;
+ pudpbuf->ipchksum = ~(uip_ipchksum(dev));
+
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Initialize the UDP header */
+
+ pudpbuf->srcport = conn->lport;
+ pudpbuf->destport = conn->rport;
+ pudpbuf->udplen = HTONS(dev->d_sndlen + UIP_UDPH_LEN);
+
+#ifdef CONFIG_NET_UDP_CHECKSUMS
+ /* Calculate UDP checksum. */
+
+ pudpbuf->udpchksum = 0;
+ pudpbuf->udpchksum = ~(uip_udpchksum(dev));
+ if (pudpbuf->udpchksum == 0)
+ {
+ pudpbuf->udpchksum = 0xffff;
+ }
+#else
+ pudpbuf->udpchksum = 0;
+#endif
+
+ nllvdbg("Outgoing UDP packet length: %d (%d)\n",
+ dev->d_len, (pudpbuf->len[0] << 8) | pudpbuf->len[1]);
+
+#ifdef CONFIG_NET_STATISTICS
+ uip_stat.udp.sent++;
+ uip_stat.ip.sent++;
+#endif
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_UDP */