summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-18 18:13:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-18 18:13:30 +0000
commitfadbb925a6a118790d8d661fea3956bb0f76348a (patch)
treeca4c58d32d12949e8d08cb69a652b5e3f7fd0e58 /nuttx/net
parent376af5201c555ee163045a8103d8e592f9a1b1bc (diff)
downloadpx4-nuttx-fadbb925a6a118790d8d661fea3956bb0f76348a.tar.gz
px4-nuttx-fadbb925a6a118790d8d661fea3956bb0f76348a.tar.bz2
px4-nuttx-fadbb925a6a118790d8d661fea3956bb0f76348a.zip
Correct and error in recv() and recvfrom() return value
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4402 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/accept.c5
-rw-r--r--nuttx/net/connect.c33
-rw-r--r--nuttx/net/net_internal.h30
-rw-r--r--nuttx/net/recvfrom.c66
-rw-r--r--nuttx/net/sendto.c13
5 files changed, 89 insertions, 58 deletions
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
index 27e5d2b0a..b45eb6cd7 100644
--- a/nuttx/net/accept.c
+++ b/nuttx/net/accept.c
@@ -1,8 +1,8 @@
/****************************************************************************
* net/accept.c
*
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -441,6 +441,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
pnewsock->s_type = SOCK_STREAM;
pnewsock->s_conn = state.acpt_newconn;
pnewsock->s_flags |= _SF_CONNECTED;
+ pnewsock->s_flags &= ~_SF_CLOSED;
return newfd;
errout_with_lock:
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index f6006e3e6..d07bf92fc 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -116,15 +116,37 @@ static void connection_event(struct uip_conn *conn, uint16_t flags)
{
nllvdbg("flags: %04x s_flags: %02x\n", flags, psock->s_flags);
- /* 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.
+ /* 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|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+
+ if ((flags & UIP_CLOSE) != 0)
{
- /* Indicate that the socket is no longer connected */
+ /* 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 */
@@ -134,6 +156,7 @@ static void connection_event(struct uip_conn *conn, uint16_t flags)
/* Indicate that the socket is now connected */
psock->s_flags |= _SF_CONNECTED;
+ psock->s_flags &= ~_SF_CLOSED;
}
}
}
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index 190d57815..e130b42e8 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -57,16 +57,25 @@
/* 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 */
- /* Bit 3: unused */
-#define _SF_NONBLOCK 0x10 /* Bit 4: Don't block if no data (TCP/READ only) */
-#define _SF_LISTENING 0x20 /* Bit 5: SOCK_STREAM is listening */
-#define _SF_BOUND 0x40 /* Bit 6: SOCK_STREAM is bound to an address */
-#define _SF_CONNECTED 0x80 /* Bit 7: SOCK_STREAM is connected */
+#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 */
@@ -78,6 +87,7 @@
#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 */
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index f1f08d66d..aabfcedfd 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -419,7 +419,12 @@ static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
#endif
}
- /* Check for a loss of connection */
+ /* 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)
{
@@ -431,9 +436,18 @@ static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
pstate->rf_cb->priv = NULL;
pstate->rf_cb->event = NULL;
- /* Report not connected */
+ /* If the peer gracefully closed the connection, then return zero
+ * (end-of-file). Otherwise, report a not-connected error
+ */
- pstate->rf_result = -ENOTCONN;
+ if ((flags & UIP_CLOSE) != 0)
+ {
+ pstate->rf_result = 0;
+ }
+ else
+ {
+ pstate->rf_result = -ENOTCONN;
+ }
/* Wake up the waiting thread */
@@ -585,27 +599,6 @@ static uint16_t recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
sem_post(&pstate->rf_sem);
}
- /* Check for a loss of connection */
-
- 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;
-
- /* Report not connected */
-
- 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.
*/
@@ -719,7 +712,9 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
if (pstate->rf_result < 0)
{
- /* Return EGAIN on a timeout or ENOTCONN on loss of connection */
+ /* This might return EGAIN on a timeout or ENOTCONN on loss of
+ * connection (TCP only)
+ */
return pstate->rf_result;
}
@@ -796,7 +791,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
{
/* Set up the callback in the connection */
- state.rf_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.rf_cb->flags = UIP_NEWDATA|UIP_POLL;
state.rf_cb->priv = (void*)&state;
state.rf_cb->event = recvfrom_udpinterrupt;
@@ -900,11 +895,20 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
if (!_SS_ISCONNECTED(psock->s_flags))
{
/* Was any data transferred from the readahead buffer after we were
- * disconnected?
+ * 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)
+ if (ret <= 0 && !_SS_ISCLOSED(psock->s_flags))
+#else
+ if (!_SS_ISCLOSED(psock->s_flags))
#endif
{
/* Nothing was previously received from the readahead buffers.
@@ -1008,8 +1012,10 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* 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:
+ * 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,
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index 4e1f9015f..cd3026eac 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -103,22 +103,13 @@ static uint16_t sendto_interrupt(struct uip_driver_s *dev, void *conn,
nllvdbg("flags: %04x\n", flags);
if (pstate)
{
- /* Check if the connection was rejected */
-
- if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
- {
- /* Yes.. then terminate with an error */
-
- pstate->st_sndlen = -ENOTCONN;
- }
-
/* 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.
*/
- else if (dev->d_sndlen > 0 || (flags & UIP_NEWDATA) != 0)
+ 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
@@ -314,7 +305,7 @@ ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
state.st_cb = uip_udpcallbackalloc(conn);
if (state.st_cb)
{
- state.st_cb->flags = UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.st_cb->flags = UIP_POLL;
state.st_cb->priv = (void*)&state;
state.st_cb->event = sendto_interrupt;