summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-20 19:24:06 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-20 19:24:06 +0000
commit8cd8607510ca423089ca1b0266c22aeee685dcee (patch)
tree826e23653aecaf5f85d08ae94f3651a35634ace4 /nuttx/net
parentf4f6f592170662f664998c9a1ae938bda35cf8d9 (diff)
downloadpx4-nuttx-8cd8607510ca423089ca1b0266c22aeee685dcee.tar.gz
px4-nuttx-8cd8607510ca423089ca1b0266c22aeee685dcee.tar.bz2
px4-nuttx-8cd8607510ca423089ca1b0266c22aeee685dcee.zip
Add support for TCP/IP connection backlog
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1294 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/accept.c112
-rw-r--r--nuttx/net/listen.c19
-rw-r--r--nuttx/net/net-poll.c10
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip-internal.h2
-rw-r--r--nuttx/net/uip/uip-listen.c29
-rw-r--r--nuttx/net/uip/uip-tcpbacklog.c348
-rw-r--r--nuttx/net/uip/uip-tcpconn.c18
-rw-r--r--nuttx/net/uip/uip-tcpinput.c2
-rw-r--r--nuttx/net/uip/uip-tcpreadahead.c2
-rw-r--r--nuttx/net/uip/uip-tcptimer.c2
11 files changed, 479 insertions, 67 deletions
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
index 122e67c43..3fea60b19 100644
--- a/nuttx/net/accept.c
+++ b/nuttx/net/accept.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/accept.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * 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
@@ -289,7 +289,9 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
goto errout;
}
- /* Verify that a valid memory block has been provided to receive the address address */
+ /* Verify that a valid memory block has been provided to receive
+ * the address
+ */
#ifdef CONFIG_NET_IPv6
if (addr->sa_family != AF_INET6 || *addrlen < sizeof(struct sockaddr_in6))
@@ -301,7 +303,9 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
goto errout;
}
- /* Allocate a socket descriptor for the new connection now (so that it cannot fail later) */
+ /* Allocate a socket descriptor for the new connection now
+ * (so that it cannot fail later)
+ */
newfd = sockfd_allocate();
if (newfd < 0)
@@ -317,68 +321,79 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
goto errout_with_socket;
}
- /* Set the socket state to accepting */
+ /* Check the backlog to see if there is a connection already pending
+ * for this listener.
+ */
- psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_ACCEPT);
+ save = irqsave();
+ conn = (struct uip_conn *)psock->s_conn;
- /* Perform the TCP accept operation */
+#ifdef CONFIG_NET_TCPBACKLOG
+ state.acpt_newconn = uip_backlogremove(conn);
+ if (!state.acpt_newconn)
+#endif
+ {
+ /* Set the socket state to accepting */
- /* Initialize the state structure. This is done with interrupts
- * disabled because we don't want anything to happen until we
- * are ready.
- */
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_ACCEPT);
- save = irqsave();
- state.acpt_addr = inaddr;
- state.acpt_newconn = NULL;
- state.acpt_result = OK;
- sem_init(&state.acpt_sem, 0, 0);
+ /* Perform the TCP accept operation */
- /* Set up the callback in the connection */
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
- conn = (struct uip_conn *)psock->s_conn;
- conn->accept_private = (void*)&state;
- conn->accept = accept_interrupt;
+ state.acpt_addr = inaddr;
+ state.acpt_newconn = NULL;
+ state.acpt_result = OK;
+ sem_init(&state.acpt_sem, 0, 0);
- /* Wait for the send to complete or an error to occur: NOTES: (1)
- * sem_wait 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.
- */
+ /* Set up the callback in the connection */
- ret = sem_wait(&state.acpt_sem);
+ conn->accept_private = (void*)&state;
+ conn->accept = accept_interrupt;
- /* Make sure that no further interrupts are processed */
+ /* Wait for the send to complete or an error to occur: NOTES: (1)
+ * sem_wait 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.
+ */
- conn->accept_private = NULL;
- conn->accept = NULL;
+ ret = sem_wait(&state.acpt_sem);
- sem_destroy(&state. acpt_sem);
- irqrestore(save);
+ /* Make sure that no further interrupts are processed */
- /* Set the socket state to idle */
+ conn->accept_private = NULL;
+ conn->accept = NULL;
- psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+ sem_destroy(&state. acpt_sem);
- /* Check for a errors. Errors are signaled by negative errno values
- * for the send length
- */
+ /* Set the socket state to idle */
- if (state.acpt_result != 0)
- {
- err = state.acpt_result;
- goto errout_with_socket;
- }
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
- /* If sem_wait failed, then we were probably reawakened by a signal. In
- * this case, sem_wait will have set errno appropriately.
- */
+ /* Check for a errors. Errors are signaled by negative errno values
+ * for the send length
+ */
- if (ret < 0)
- {
- err = -ret;
- goto errout_with_socket;
+ if (state.acpt_result != 0)
+ {
+ err = state.acpt_result;
+ goto errout_with_irq;
+ }
+
+ /* If sem_wait failed, then we were probably reawakened by a signal. In
+ * this case, sem_wait will have set errno appropriately.
+ */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout_with_irq;
+ }
}
+ irqrestore(save);
/* Initialize the socket structure and mark the socket as connected */
@@ -387,6 +402,9 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
pnewsock->s_flags |= _SF_CONNECTED;
return newfd;
+errout_with_irq:
+ irqrestore(save);
+
errout_with_socket:
sockfd_release(newfd);
diff --git a/nuttx/net/listen.c b/nuttx/net/listen.c
index f2f91b1f4..46bad5d94 100644
--- a/nuttx/net/listen.c
+++ b/nuttx/net/listen.c
@@ -114,7 +114,7 @@ int listen(int sockfd, int backlog)
}
/* 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)
{
@@ -122,16 +122,27 @@ int listen(int sockfd, int backlog)
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 someday should enable post() or select() logic.
+ * is called and enables poll()/select() logic.
*/
-
+
uip_listen(conn);
psock->s_flags |= _SF_LISTENING;
return OK;
errout:
- *get_errno_ptr() = err;
+ errno = err;
return ERROR;
}
diff --git a/nuttx/net/net-poll.c b/nuttx/net/net-poll.c
index 22bd03ce9..6dcb4c2d0 100644
--- a/nuttx/net/net-poll.c
+++ b/nuttx/net/net-poll.c
@@ -114,9 +114,9 @@ static uint16 poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
{
pollevent_t eventset = 0;
- /* Check for data availability events. */
+ /* Check for data or connection availability events. */
- if ((flags & UIP_NEWDATA) != 0)
+ if ((flags & (UIP_NEWDATA|UIP_BACKLOG)) != 0)
{
eventset |= POLLIN & fds->events;
}
@@ -174,8 +174,7 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
#ifdef CONFIG_DEBUG
if (!conn || !fds)
{
- ret = -EINVAL;
- goto errout;
+ return -EINVAL;
}
#endif
@@ -194,7 +193,7 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
/* Initialize the callbcack structure */
- cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ cb->flags = UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
cb->private = (FAR void *)fds;
cb->event = poll_interrupt;
@@ -219,7 +218,6 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
errout_with_irq:
irqrestore(flags);
-errout:
return ret;
}
#endif /* HAVE_NETPOLL */
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index 0a1031684..543a8e856 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -53,7 +53,7 @@ ifeq ($(CONFIG_NET_TCP),y)
UIP_CSRCS += uip-tcpconn.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-tcpreadahead.c uip-tcpbacklog.c
endif
diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h
index 362cecc57..841555760 100644
--- a/nuttx/net/uip/uip-internal.h
+++ b/nuttx/net/uip/uip-internal.h
@@ -123,7 +123,7 @@ EXTERN void uip_tcptimer(struct uip_driver_s *dev, struct uip_conn *conn, int hs
EXTERN void uip_listeninit(void);
EXTERN boolean uip_islistener(uint16 port);
-EXTERN int uip_accept(struct uip_conn *conn, uint16 portno);
+EXTERN int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn, uint16 portno);
/* Defined in uip-tcpsend.c *************************************************/
diff --git a/nuttx/net/uip/uip-listen.c b/nuttx/net/uip/uip-listen.c
index 82d4238cd..b5e17a6bf 100644
--- a/nuttx/net/uip/uip-listen.c
+++ b/nuttx/net/uip/uip-listen.c
@@ -228,22 +228,41 @@ boolean uip_islistener(uint16 portno)
*
****************************************************************************/
-int uip_accept(struct uip_conn *conn, uint16 portno)
+int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn, uint16 portno)
{
struct uip_conn *listener;
int ret = ERROR;
/* The interrupt logic has already allocated and initialized a TCP
- * connection -- now check if is an application in place to accept the
+ * connection -- now check there if is an application in place to accept the
* connection.
*/
listener = uip_tcplistener(portno);
- if (listener && listener->accept)
+ if (listener)
{
- /* Yes.. accept the connection */
+ /* Yes, there is a listener. Is it accepting connections now? */
- ret = listener->accept(listener, conn);
+ 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, conn, UIP_BACKLOG);
+ }
+ }
+#endif
}
return ret;
}
diff --git a/nuttx/net/uip/uip-tcpbacklog.c b/nuttx/net/uip/uip-tcpbacklog.c
new file mode 100644
index 000000000..152d374ba
--- /dev/null
+++ b/nuttx/net/uip/uip-tcpbacklog.c
@@ -0,0 +1,348 @@
+/****************************************************************************
+ * net/uip/uip-tcpbacklog.c
+ *
+ * Copyright (C) 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 <net/uip/uipopt.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) && defined(CONFIG_NET_TCPBACKLOG)
+
+#include <sys/types.h>
+
+#include <stdlib.h>
+#include <queue.h>
+#include <debug.h>
+
+#include <net/uip/uip.h>
+#include <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;
+ irqstate_t flags;
+ int size;
+ int offset;
+ int i;
+
+#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)
+ {
+ return -ENOMEM;
+ }
+
+ /* Then add all of the pre-allocated containers to the the free list */
+
+ blc = (FAR struct uip_blcontainer_s*)(((FAR ubyte*)bls) + offset);
+ for (i = 0; i < nblg; i++)
+ {
+ dq_addfirst(&blc->bc_node, &bls->bl_free);
+ }
+ }
+
+ /* Destroy any existing backlog (shouldn't be any) */
+
+ flags = irqsave();
+ 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;
+ irqrestore(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;
+
+#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*)dq_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;
+ 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 not 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;
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ bls = conn->backlog;
+ if (conn->backlog && blconn)
+ {
+ /* Allocate a container for the connection from the free list */
+
+ blc = (FAR struct uip_blcontainer_s *)dq_remfirst(&bls->bl_free);
+ if (!blc)
+ {
+ 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;
+ dq_addlast(&blc->bc_node, &bls->bl_pending);
+ ret = OK;
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * 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 && blconn)
+ {
+ /* Remove the a container at the head of the pending connection list
+ * (FIFO)
+ */
+
+ blc = (FAR struct uip_blcontainer_s *)dq_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;
+ dq_addlast(&blc->bc_node, &bls->bl_free);
+ }
+ }
+ 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;
+
+#ifdef CONFIG_DEBUG
+ if (!conn)
+ {
+ return NULL;
+ }
+#endif
+ bls = conn->backlog;
+ if (bls)
+ {
+ /* Find the container hold the connection */
+
+ for (blc = (FAR struct uip_blcontainer_s *)dq_peek(&bls->bl_pending);
+ blc;
+ blc = (FAR struct uip_blcontainer_s *)dq_next(&blc->bc_node))
+ {
+ if (blc->bc_conn == blconn)
+ {
+ /* Remove the a container from the list of pending connections */
+
+ dq_rem(&blc->bc_node, &bls->bl_pending);
+ return OK;
+ }
+ }
+ return -EINVAL;
+ }
+ return OK;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP && CONFIG_NET_TCPBACKLOG */
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 0f48a4607..e36520b05 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -316,6 +316,24 @@ void uip_tcpfree(struct uip_conn *conn)
}
#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;
diff --git a/nuttx/net/uip/uip-tcpinput.c b/nuttx/net/uip/uip-tcpinput.c
index 5a7b5b923..5d220aeb5 100644
--- a/nuttx/net/uip/uip-tcpinput.c
+++ b/nuttx/net/uip/uip-tcpinput.c
@@ -165,7 +165,7 @@ void uip_tcpinput(struct uip_driver_s *dev)
* least queue it it for acceptance).
*/
- if (uip_accept(conn, tmp16) != OK)
+ if (uip_accept(dev, conn, tmp16) != OK)
{
/* No, then we have to give the connection back */
diff --git a/nuttx/net/uip/uip-tcpreadahead.c b/nuttx/net/uip/uip-tcpreadahead.c
index abadb4f50..c00ea7b38 100644
--- a/nuttx/net/uip/uip-tcpreadahead.c
+++ b/nuttx/net/uip/uip-tcpreadahead.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip-tcpreadahead.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
*
diff --git a/nuttx/net/uip/uip-tcptimer.c b/nuttx/net/uip/uip-tcptimer.c
index e0da04ead..aadd2b5ea 100644
--- a/nuttx/net/uip/uip-tcptimer.c
+++ b/nuttx/net/uip/uip-tcptimer.c
@@ -2,7 +2,7 @@
* net/uip/uip-tcptimer.c
* Poll for the availability of TCP TX data
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 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: