From 58e84b6b86d6270523ee50a63f8530cbd9063533 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 22 Feb 2012 16:03:10 +0000 Subject: [PATCH] Fix accept() logic. it was not monitoring for losses in connections. git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4412 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- nuttx/ChangeLog | 5 ++ nuttx/net/Makefile | 2 +- nuttx/net/accept.c | 24 ++--- nuttx/net/connect.c | 110 ++++------------------- nuttx/net/net_internal.h | 7 ++ nuttx/net/net_monitor.c | 186 +++++++++++++++++++++++++++++++++++++++ 6 files changed, 231 insertions(+), 103 deletions(-) create mode 100644 nuttx/net/net_monitor.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f585e1a50e..4dd369ef43 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -2477,3 +2477,8 @@ * arch/arm/src/stm32_sdio.c: STM32 F4 SDIO DMA is now supported * configs/stm3240g-eval/nsh/defconfig: This configuration now supports SDIO with DMA (see configs/stm3240g-eval/README.txt for some issues). + * net/accept.c, connect.c,and net_monitor.c: Correct an error in the accept + logic. After a new connection is made via accept(), monitoring for losses + of TCP connection must be set up (just as with connect()). The new file + net_monitor.c holds the common TCP connection monitoring logic used by both + the accecpt() and connect() logic. Contributed by Max Nekludov. diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index 94af9e0d23..598933cc45 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -47,7 +47,7 @@ SOCK_CSRCS = bind.c connect.c getsockname.c recv.c recvfrom.c socket.c \ # TCP/IP support ifeq ($(CONFIG_NET_TCP),y) -SOCK_CSRCS += send.c listen.c accept.c +SOCK_CSRCS += send.c listen.c accept.c net_monitor.c endif # Socket options diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c index b45eb6cd7d..4dfe4c09da 100644 --- a/nuttx/net/accept.c +++ b/nuttx/net/accept.c @@ -89,7 +89,7 @@ struct accept_s * * Parameters: * conn - The newly accepted TCP connection - * pstate - the recvfrom state structure + * pstate - the recvfrom state structure * * Returned Value: * None @@ -290,7 +290,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) } /* We have a socket descriptor, but it is a stream? */ - + if (psock->s_type != SOCK_STREAM) { err = EOPNOTSUPP; @@ -305,8 +305,8 @@ 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 + /* Verify that a valid memory block has been provided to receive the + * address */ if (addr) @@ -322,8 +322,8 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) } } - /* 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(0); @@ -340,8 +340,8 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) goto errout_with_socket; } - /* Check the backlog to see if there is a connection already pending - * for this listener. + /* Check the backlog to see if there is a connection already pending for + * this listener. */ save = uip_lock(); @@ -412,7 +412,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) 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 + * for the send length. */ if (state.acpt_result != 0) @@ -431,7 +431,6 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) goto errout_with_lock; } } - uip_unlock(save); /* Initialize the socket structure and mark the socket as connected. * (The reference count on the new connection structure was set in the @@ -442,6 +441,11 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen) 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: diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c index d07bf92fcf..be7a3ae1d9 100644 --- a/nuttx/net/connect.c +++ b/nuttx/net/connect.c @@ -1,8 +1,8 @@ /**************************************************************************** * net/connect.c * - * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -72,7 +72,6 @@ struct tcp_connect_s ****************************************************************************/ #ifdef CONFIG_NET_TCP -static void connection_event(struct uip_conn *conn, uint16_t flags); 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); @@ -89,81 +88,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in * Private Functions ****************************************************************************/ /**************************************************************************** - * Function: 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 - * - ****************************************************************************/ - -#ifdef CONFIG_NET_TCP -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; - } - } -} -#endif /* CONFIG_NET_TCP */ - -/**************************************************************************** - * Function: tcp_setup_callbacks + * Name: tcp_setup_callbacks ****************************************************************************/ #ifdef CONFIG_NET_TCP @@ -184,14 +109,15 @@ static inline int tcp_setup_callbacks(FAR struct socket *psock, 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 to receive callbacks on connection-related events */ + /* Set up the connection event monitor */ - conn->connection_private = (void*)psock; - conn->connection_event = connection_event; + net_startmonitor(psock); ret = OK; } return ret; @@ -199,34 +125,34 @@ static inline int tcp_setup_callbacks(FAR struct socket *psock, #endif /* CONFIG_NET_TCP */ /**************************************************************************** - * Function: tcp_teardown_callbacks + * Name: tcp_teardown_callbacks ****************************************************************************/ #ifdef CONFIG_NET_TCP -static inline void tcp_teardown_callbacks(struct tcp_connect_s *pstate, int status) +static inline void tcp_teardown_callbacks(struct tcp_connect_s *pstate, + int status) { - struct uip_conn *conn = pstate->tc_conn; + 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 we successfully connected, we will continue to monitor the connection + * state via callbacks. */ if (status < 0) { - /* Failed to connect */ + /* Stop the connection event monitor */ - conn->connection_private = NULL; - conn->connection_event = NULL; + net_stopmonitor(conn); } } #endif /* CONFIG_NET_TCP */ /**************************************************************************** - * Function: tcp_connect_interrupt + * Name: tcp_connect_interrupt * * Description: * This function is called from the interrupt level to perform the actual @@ -323,7 +249,7 @@ static uint16_t tcp_connect_interrupt(struct uip_driver_s *dev, void *pvconn, #endif /* CONFIG_NET_TCP */ /**************************************************************************** - * Function: tcp_connect + * Name: tcp_connect * * Description: * Perform a TCP connection @@ -428,7 +354,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in * Public Functions ****************************************************************************/ /**************************************************************************** - * Function: connect + * Name: connect * * Description: * connect() connects the socket referred to by the file descriptor sockfd diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h index e130b42e88..d12397e749 100644 --- a/nuttx/net/net_internal.h +++ b/nuttx/net/net_internal.h @@ -165,6 +165,13 @@ 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); diff --git a/nuttx/net/net_monitor.c b/nuttx/net/net_monitor.c new file mode 100644 index 0000000000..40d4196b26 --- /dev/null +++ b/nuttx/net/net_monitor.c @@ -0,0 +1,186 @@ +/**************************************************************************** + * net/net_monitor.c + * + * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) + +#include +#include + +#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 */