summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-07-19 13:50:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-07-19 13:50:08 +0000
commit85f8218d49dfea1bea70633d38cede541143a1df (patch)
tree05dbb3d914eaf7434bd20987200ba57e3aafaa24 /nuttx/net
parent17553d10657c2a395a2ab1f7d6629453fc5ed342 (diff)
downloadpx4-nuttx-85f8218d49dfea1bea70633d38cede541143a1df.tar.gz
px4-nuttx-85f8218d49dfea1bea70633d38cede541143a1df.tar.bz2
px4-nuttx-85f8218d49dfea1bea70633d38cede541143a1df.zip
Add non-blocking capability for TCP sockets
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1996 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/net_internal.h7
-rw-r--r--nuttx/net/net_vfcntl.c52
-rw-r--r--nuttx/net/recvfrom.c25
3 files changed, 77 insertions, 7 deletions
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index a403a269f..a4b1fe4dd 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -53,13 +53,14 @@
/* Definitions of 8-bit socket flags */
- /* Bits 0:2 : Socket state */
+ /* 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 */
- /* Bits 3:4 : unused */
+ /* 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 */
@@ -69,6 +70,8 @@
#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)
diff --git a/nuttx/net/net_vfcntl.c b/nuttx/net/net_vfcntl.c
index 537a9031d..ccaf4e2cd 100644
--- a/nuttx/net/net_vfcntl.c
+++ b/nuttx/net/net_vfcntl.c
@@ -39,11 +39,13 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/socket.h>
#include <stdarg.h>
#include <fcntl.h>
#include <errno.h>
+#include <arch/irq.h>
#include <nuttx/net.h>
#include "net_internal.h"
@@ -60,6 +62,7 @@
int net_vfcntl(int sockfd, int cmd, va_list ap)
{
FAR struct socket *psock = sockfd_socket(sockfd);
+ irqstate_t flags;
int err = 0;
int ret = 0;
@@ -71,6 +74,10 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
goto errout;
}
+ /* Interrupts must be disabled in order to perform operations on socket structures */
+
+ flags = irqsave();
+
#warning "Most fcntl() commands not yet implemented"
switch (cmd)
{
@@ -105,6 +112,9 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
* 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
@@ -114,6 +124,22 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
* 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,
@@ -123,6 +149,28 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
* 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_type |= _SF_NONBLOCK;
+ }
+ else
+ {
+ psock->s_type &= ~_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
@@ -165,7 +213,7 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
* not be done.
*/
- err = ENOSYS;
+ err = ENOSYS; /* F_GETOWN, F_SETOWN, F_GETLK, F_SETLK, F_SETLKW */
break;
default:
@@ -173,6 +221,8 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
break;
}
+ irqrestore(flags);
+
errout:
if (err != 0)
{
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 6ff8e5724..345ec380a 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -868,7 +868,6 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
return -ENOTCONN;
}
-
/* Initialize the state structure. This is done with interrupts
* disabled because we don't want anything to happen until we
* are ready.
@@ -883,11 +882,29 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
recvfrom_readahead(&state);
- /* If there is space to receive anything more, then we will
- * wait to receive the data.
+ /* In general, this uI-based implementation will not support non-blocking
+ * socket operations... except in this one case: 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.
+ */
+
+ if (_SS_ISNONBLOCK(psock->s_flags))
+ {
+ /* Return OK if something was received; EGAIN if not */
+
+ if (state.rf_recvlen <= 0)
+ {
+ /* Nothing was received */
+
+ return -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.
*/
- if (state.rf_buflen > 0)
+ else if (state.rf_buflen > 0)
#endif
{
struct uip_conn *conn = (struct uip_conn *)psock->s_conn;