summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-09 17:20:56 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-09 17:20:56 +0000
commit7a65f932826220c741ffbf5698b48692a787d915 (patch)
tree825e048f8fc18b7e69cb155ad96b7254566a3ffe /nuttx/net
parentd12e00bdd6ffbb39ab5d45d5d5a484d293108021 (diff)
downloadpx4-nuttx-7a65f932826220c741ffbf5698b48692a787d915.tar.gz
px4-nuttx-7a65f932826220c741ffbf5698b48692a787d915.tar.bz2
px4-nuttx-7a65f932826220c741ffbf5698b48692a787d915.zip
Implement TCP send; remove uIP proto-sockets
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@339 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/bind.c1
-rw-r--r--nuttx/net/connect.c20
-rw-r--r--nuttx/net/net-internal.h20
-rw-r--r--nuttx/net/recv.c2
-rw-r--r--nuttx/net/recvfrom.c286
-rw-r--r--nuttx/net/send.c200
-rw-r--r--nuttx/net/sendto.c10
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/psock.c385
-rw-r--r--nuttx/net/uip/uip-tcpconn.c109
10 files changed, 526 insertions, 509 deletions
diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c
index edc9776d4..f1d5dbbd9 100644
--- a/nuttx/net/bind.c
+++ b/nuttx/net/bind.c
@@ -119,6 +119,7 @@ int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
case SOCK_STREAM:
ret = uip_tcpbind(psock->s_conn, inaddr);
+ psock->s_flags |= _SF_BOUND;
break;
#ifdef CONFIG_NET_UDP
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index aaa267227..5bc978fe9 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -90,7 +90,7 @@
* sa_family field.
* EAGAIN
* No more free local ports or insufficient entries in the routing
- * cache. For PF_INET.
+ * cache.
* EALREADY
* The socket is non-blocking and a previous connection attempt has
* not yet been completed.
@@ -155,12 +155,28 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
case SOCK_STREAM:
{
- int ret = uip_tcpconnect(psock->s_conn, inaddr);
+ int ret;
+
+ /* Verify that the socket is not already connected */
+
+ if (_SS_ISCONNECTED(psock->s_flags))
+ {
+ err = -EISCONN;
+ goto errout;
+ }
+
+ /* Perform the uIP connection operation */
+
+ ret = uip_tcpconnect(psock->s_conn, inaddr);
if (ret < 0)
{
err = -ret;
goto errout;
}
+
+ /* Mark the connection bound and connected */
+
+ psock->s_flags |= (_SF_BOUND|_SF_CONNECTED);
}
break;
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index b62099a16..f517f863d 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -52,6 +52,26 @@
* Definitions
****************************************************************************/
+/* Definitions of 8-bit socket flags */
+
+ /* Bits 0:2 : Socket state */
+#define _SF_IDLE 0x00 /* There is no socket activity */
+#define _SF_LISTEN 0x01 /* Socket is listening */
+#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:5 : unused */
+#define _SF_BOUND 0x40 /* Bit 6: SOCK_STREAM is bound to an address */
+#define _SF_CONNECTED 0x80 /* Bit 7: SOCK_STREAM is connected */
+
+/* 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_ISCONNECTED(s) (((s) & _SF_CONNECTED) != 0)
+#define _SS_ISBOUND(s) (((s) & _SF_CONNECTED) != 0)
+
/* This macro converts a socket option value into a bit setting */
#define _SO_BIT(o) (1 << (o))
diff --git a/nuttx/net/recv.c b/nuttx/net/recv.c
index e03fbd495..135b6f319 100644
--- a/nuttx/net/recv.c
+++ b/nuttx/net/recv.c
@@ -69,7 +69,7 @@
*
****************************************************************************/
-ssize_t recv(int sockfd, void *buf, size_t len, int flags)
+ssize_t recv(int sockfd, FAR void *buf, size_t len, int flags)
{
return recvfrom(sockfd, buf, len, flags, NULL, 0);
}
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 318f0d1bf..a8bc59505 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -77,6 +77,7 @@ struct recvfrom_s
void recvfrom_interrupt(void *private)
{
struct recvfrom_s *pstate = (struct recvfrom_s *)private;
+ struct uip_udp_conn *udp_conn;
size_t recvlen;
/* 'private' might be null in some race conditions (?) */
@@ -88,9 +89,9 @@ void recvfrom_interrupt(void *private)
if (uip_newdata())
{
/* Get the length of the data to return */
- if (uip_len > pstate-> rf_buflen)
+ if (uip_len > pstate->rf_buflen)
{
- recvlen = pstate-> rf_buflen;
+ recvlen = pstate->rf_buflen;
}
else
{
@@ -103,15 +104,16 @@ void recvfrom_interrupt(void *private)
/* Don't allow any further call backs. */
- uip_conn->private = NULL;
- uip_conn->callback = NULL;
+ udp_conn = (struct uip_udp_conn *)pstate->rf_sock->s_conn;
+ udp_conn->private = NULL;
+ udp_conn->callback = NULL;
/* Wake up the waiting thread, returning the number of bytes
* actually read.
*/
pstate->rf_buflen = recvlen;
- sem_post(&pstate-> rf_sem);
+ sem_post(&pstate->rf_sem);
}
/* No data has been received -- this is some other event... probably a
@@ -131,15 +133,16 @@ void recvfrom_interrupt(void *private)
{
/* Don't allow any further call backs. */
- uip_conn->private = NULL;
- uip_conn->callback = NULL;
+ udp_conn = (struct uip_udp_conn *)pstate->rf_sock->s_conn;
+ udp_conn->private = NULL;
+ udp_conn->callback = NULL;
/* Wake up the waiting thread, returning the error -EAGAIN
* that signals the timeout event
*/
pstate->rf_buflen = -EAGAIN;
- sem_post(&pstate-> rf_sem);
+ sem_post(&pstate->rf_sem);
}
}
}
@@ -148,6 +151,157 @@ void recvfrom_interrupt(void *private)
}
/****************************************************************************
+ * 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
+ *
+ * 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 const struct sockaddr_in6 *infrom )
+#else
+static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR const struct sockaddr_in *infrom )
+#endif
+{
+ struct uip_udp_conn *udp_conn;
+ struct recvfrom_s state;
+ irqstate_t save;
+ int err;
+ 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 = irqsave();
+ memset(&state, 0, sizeof(struct recvfrom_s));
+ (void)sem_init(&state. rf_sem, 0, 0); /* Doesn't really fail */
+ state.rf_sock = psock;
+ state.rf_buflen = len;
+ state.rf_buffer = buf;
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ /* Set up the start time for the timeout */
+
+ state.rf_starttime = g_system_timer;
+#endif
+
+ /* Setup the UDP socket */
+
+ err = uip_udpconnect(psock->s_conn, NULL);
+ if (err < 0)
+ {
+ irqrestore(save);
+ return err;
+ }
+
+ /* Set up the callback in the connection */
+
+ udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ udp_conn->private = (void*)&state;
+ udp_conn->callback = recvfrom_interrupt;
+
+ /* Wait for either the receive to complete or for an error/timeout 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.
+ */
+
+ ret = sem_wait(&state. rf_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ udp_conn->private = NULL;
+ udp_conn->callback = NULL;
+ sem_destroy(&state. rf_sem);
+ irqrestore(save);
+
+ /* Check for a error/timeout detected by the interrupt handler. Errors are
+ * signaled by negative errno values for the rcv length
+ */
+
+ if (state.rf_buflen < 0)
+ {
+ /* Return EGAIN on a timeout */
+
+ return state.rf_buflen;
+ }
+
+ /* 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)
+ {
+ return -*get_errno_ptr();
+ }
+
+#warning "Needs to return server address"
+ return state.rf_buflen;
+}
+#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
+ *
+ * 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_IPv6
+static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR const struct sockaddr_in6 *infrom )
+#else
+static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ FAR const struct sockaddr_in *infrom )
+#endif
+{
+ /* Verify that the SOCK_STREAM has been connected */
+
+ if (_SS_ISCONNECTED(psock->s_flags))
+ {
+ /* The SOCK_STREAM must be connect in order to recive */
+
+ return -ENOTCONN;
+ }
+
+#warning "TCP/IP recv not implemented"
+ return -ENOSYS;
+}
+
+/****************************************************************************
* Global Functions
****************************************************************************/
@@ -203,8 +357,8 @@ void recvfrom_interrupt(void *private)
*
****************************************************************************/
-ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *from,
- socklen_t *fromlen)
+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;
#ifdef CONFIG_NET_IPv6
@@ -212,13 +366,16 @@ ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *
#else
FAR const struct sockaddr_in *infrom = (const struct sockaddr_in *)from;
#endif
-#ifdef CONFIG_NET_UDP
- struct uip_udp_conn *udp_conn;
- struct recvfrom_s state;
- irqstate_t save;
-#endif
+ ssize_t ret;
int err;
- int ret;
+
+ /* Verify that non-NULL pointers were passed */
+
+ if (!buf || !from || !fromlen)
+ {
+ err = EINVAL;
+ goto errout;
+ }
/* Get the underlying socket structure */
/* Verify that the sockfd corresponds to valid, allocated socket */
@@ -230,95 +387,52 @@ ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *
goto errout;
}
- /* Perform the TCP/IP recv() operation */
+ /* Verify that a valid address has been provided */
- if (psock->s_type == SOCK_STREAM)
- {
-#warning "TCP/IP recv not implemented"
- err = ENOSYS;
+#ifdef CONFIG_NET_IPv6
+ if (from->sa_family != AF_INET6 || *fromlen < sizeof(struct sockaddr_in6))
+#else
+ if (from->sa_family != AF_INET || *fromlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
goto errout;
- }
+ }
- /* Perform the UDP recvfrom() operation */
+ /* Set the socket state to receiving */
-#ifdef CONFIG_NET_UDP
- /* 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_RECV);
- save = irqsave();
- memset(&state, 0, sizeof(struct recvfrom_s));
- (void)sem_init(&state. rf_sem, 0, 0); /* Doesn't really fail */
- state. rf_buflen = len;
- state. rf_buffer = buf;
+ /* Perform the TCP/IP or UDP recv() operation */
-#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- /* Set up the start time for the timeout */
-
- state.rf_starttime = g_system_timer;
+#ifdef CONFIG_NET_UDP
+ if (psock->s_type == SOCK_STREAM)
#endif
-
- /* Setup the UDP socket */
-
- ret = uip_udpconnect(psock->s_conn, NULL);
- if (ret < 0)
{
- irqrestore(save);
- err = -ret;
- goto errout;
+ ret = tcp_recvfrom(psock, buf, len, infrom);
}
-
- /* Set up the callback in the connection */
-
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = (void*)&state;
- udp_conn->callback = recvfrom_interrupt;
-
- /* Wait for either the read to complete: 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.
- */
-
- ret = sem_wait(&state. rf_sem);
-
- /* Make sure that no further interrupts are processed */
-
- uip_conn->private = NULL;
- uip_conn->callback = NULL;
- sem_destroy(&state. rf_sem);
- irqrestore(save);
-
- /* Check for a timeout. Errors are signaled by negative errno values
- * for the rcv length
- */
-
-#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- if (state.rf_buflen < 0)
+#ifdef CONFIG_NET_UDP
+ else
{
- /* Return EGAIN on a timeout */
-
- err = -state.rf_buflen;
- goto errout;
+ ret = udp_recvfrom(psock, buf, len, infrom);
}
#endif
- /* If sem_wait failed, then we were probably reawakened by a signal. In
- * this case, sem_wait will have set errno appropriately.
- */
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
+
+ /* Handle returned errors */
if (ret < 0)
{
- return ERROR;
+ err = -ret;
+ goto errout;
}
-#warning "Needs to return server address"
- return state.rf_buflen;
+ /* Success return */
-#else
- err = ENOSYS;
-#endif
+ return ret;
errout:
*get_errno_ptr() = err;
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index cc2b154a2..037455faf 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -42,12 +42,125 @@
#include <sys/types.h>
#include <sys/socket.h>
+#include <string.h>
#include <errno.h>
+#include <arch/irq.h>
#include "net-internal.h"
/****************************************************************************
- * Global Functions
+ * Definitions
+ ****************************************************************************/
+
+#define STATE_POLLWAIT 1
+#define STATE_DATA_SENT 2
+
+/****************************************************************************
+ * 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 */
+ sem_t snd_sem; /* Used to wake up the waiting thread */
+ FAR const uint8 *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 */
+ uint8 snd_state; /* The state of the send operation. */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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:
+ * private An instance of struct send_s cast to void*
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static void send_interrupt(void *private)
+{
+ struct send_s *pstate = (struct send_s *)private;
+ struct uip_conn *conn;
+
+ /* If the data has not been sent OR if it needs to be retransmitted,
+ * then send it now.
+ */
+
+ if (pstate->snd_state != STATE_DATA_SENT || uip_rexmit())
+ {
+ if (pstate->snd_buflen > uip_mss())
+ {
+ uip_send(pstate->snd_buffer, uip_mss());
+ }
+ else
+ {
+ uip_send(pstate->snd_buffer, pstate->snd_buflen);
+ }
+
+ pstate->snd_state = STATE_DATA_SENT;
+ }
+
+ /* Check if all data has been sent and acknowledged */
+
+ else if (pstate->snd_state == STATE_DATA_SENT && uip_acked())
+ {
+ /* Yes.. the data has been sent AND acknowledge */
+
+ if (pstate->snd_buflen > uip_mss())
+ {
+ /* Not all data has been sent */
+
+ pstate->snd_sent += uip_mss();
+ pstate->snd_buflen -= uip_mss();
+ pstate->snd_buffer += uip_mss();
+
+ /* Send again on the next poll */
+
+ pstate->snd_state = STATE_POLLWAIT;
+ }
+ else
+ {
+ /* All data has been sent */
+
+ pstate->snd_sent += pstate->snd_buflen;
+ pstate->snd_buffer += pstate->snd_buflen;
+ pstate->snd_buflen = 0;
+
+ /* Don't allow any further call backs. */
+
+ conn = (struct uip_conn *)pstate->snd_sock->s_conn;
+ conn->private = NULL;
+ conn->callback = NULL;
+
+ /* Wake up the waiting thread, returning the number of bytes
+ * actually sent.
+ */
+
+ sem_post(&pstate->snd_sem);
+ }
+ }
+}
+
+/****************************************************************************
+ * Public Functions
****************************************************************************/
/****************************************************************************
@@ -57,8 +170,8 @@
* 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(s,buf,len,flags) is
- * equivalent to sendto(s,buf,len,flags,NULL,0).
+ * 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
@@ -117,7 +230,11 @@
ssize_t send(int sockfd, const void *buf, size_t len, int flags)
{
FAR struct socket *psock = sockfd_socket(sockfd);
+ struct uip_conn *conn;
+ struct send_s state;
+ irqstate_t save;
int err;
+ int ret;
/* Verify that the sockfd corresponds to valid, allocated socket */
@@ -129,21 +246,86 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
/* If this is a connected socket, then return ENOTCONN */
- if (psock->s_type != SOCK_STREAM)
+ 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 */
-#warning "send() not implemented"
- err = ENOSYS;
+ /* Initialize the state structure. This is done with interrupts
+ * disabled because we don't want anything to happen until we
+ * are ready.
+ */
+
+ save = irqsave();
+ memset(&state, 0, sizeof(struct send_s));
+ (void)sem_init(&state. snd_sem, 0, 0); /* Doesn't really fail */
+ state.snd_sock = psock;
+ state.snd_buflen = len;
+ state.snd_buffer = buf;
+ state.snd_state = STATE_POLLWAIT;
+
+ if (len > 0)
+ {
+ /* Set up the callback in the connection */
+
+ conn = (struct uip_conn *)psock->s_conn;
+ conn->private = (void*)&state;
+ conn->callback = send_interrupt;
+
+ /* 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.
+ */
+
+ ret = sem_wait(&state. snd_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ conn->private = NULL;
+ conn->callback = NULL;
+ }
+
+ sem_destroy(&state. snd_sem);
+ irqrestore(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 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;
+ }
+
+ /* Return the number of bytes actually sent */
+
+ return state.snd_sent;
errout:
- *get_errno_ptr() = ENOSYS;
- return ERROR;
- *get_errno_ptr() = ENOSYS;
+ *get_errno_ptr() = err;
return ERROR;
}
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index eef1a31b4..bba9c5b47 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -97,7 +97,7 @@ void sendto_interrupt(void *private)
*
* 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
+ * 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.
*
@@ -214,6 +214,10 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* 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.
@@ -244,6 +248,10 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
sem_wait(&state.st_sem);
sem_destroy(&state.st_sem);
+
+ /* Set the socket state to idle */
+
+ psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
return len;
#else
err = ENOSYS;
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index 96691792d..4ad51f9bc 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -34,6 +34,6 @@
############################################################################
UIP_ASRCS =
-UIP_CSRCS = psock.c uip-arp.c uip.c uip-fw.c uip-neighbor.c uip-split.c \
+UIP_CSRCS = uip-arp.c uip.c uip-fw.c uip-neighbor.c uip-split.c \
uip-tcpconn.c uip-udpconn.c uip-wait.c
diff --git a/nuttx/net/uip/psock.c b/nuttx/net/uip/psock.c
deleted file mode 100644
index 55676c3c2..000000000
--- a/nuttx/net/uip/psock.c
+++ /dev/null
@@ -1,385 +0,0 @@
-/****************************************************************************
- * net/uip/psock.c
- *
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Based on uIP which also has a BSD style license:
- *
- * Copyright (c) 2004, 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <stdio.h>
-#include <string.h>
-#include <pthread.h>
-#include <debug.h>
-
-#include <net/uip/uip.h>
-#include <net/uip/uipopt.h>
-#include <net/uip/psock.h>
-
-#define STATE_NONE 0
-#define STATE_ACKED 1
-#define STATE_READ 2
-#define STATE_BLOCKED_NEWDATA 3
-#define STATE_BLOCKED_CLOSE 4
-#define STATE_BLOCKED_SEND 5
-#define STATE_DATA_SENT 6
-
-/*
- * Return value of the buffering functions that indicates that a
- * buffer was not filled by incoming data.
- *
- */
-#define BUF_NOT_FULL 0
-#define BUF_NOT_FOUND 0
-
-/*
- * Return value of the buffering functions that indicates that a
- * buffer was completely filled by incoming data.
- *
- */
-#define BUF_FULL 1
-
-/*
- * Return value of the buffering functions that indicates that an
- * end-marker byte was found.
- *
- */
-#define BUF_FOUND 2
-
-static void buf_setup(struct psock_buf *buf, uint8 *bufptr, uint16 bufsize)
-{
- buf->ptr = bufptr;
- buf->left = bufsize;
-}
-
-static uint8 buf_bufdata(struct psock_buf *buf, uint16 len, uint8 **dataptr, uint16 *datalen)
-{
- if (*datalen < buf->left)
- {
- memcpy(buf->ptr, *dataptr, *datalen);
- buf->ptr += *datalen;
- buf->left -= *datalen;
- *dataptr += *datalen;
- *datalen = 0;
- return BUF_NOT_FULL;
- }
- else if (*datalen == buf->left)
- {
- memcpy(buf->ptr, *dataptr, *datalen);
- buf->ptr += *datalen;
- buf->left = 0;
- *dataptr += *datalen;
- *datalen = 0;
- return BUF_FULL;
- }
- else
- {
- memcpy(buf->ptr, *dataptr, buf->left);
- buf->ptr += buf->left;
- *datalen -= buf->left;
- *dataptr += buf->left;
- buf->left = 0;
- return BUF_FULL;
- }
-}
-
-static uint8 buf_bufto(struct psock_buf *buf, uint8 endmarker, uint8 **dataptr, uint16 *datalen)
-{
- uint8 c;
- while(buf->left > 0 && *datalen > 0)
- {
- c = *buf->ptr = **dataptr;
- ++*dataptr;
- ++buf->ptr;
- --*datalen;
- --buf->left;
-
- if (c == endmarker)
- {
- return BUF_FOUND;
- }
- }
-
- if (*datalen == 0)
- {
- return BUF_NOT_FOUND;
- }
-
- while(*datalen > 0)
- {
- c = **dataptr;
- --*datalen;
- ++*dataptr;
-
- if (c == endmarker)
- {
- return BUF_FOUND | BUF_FULL;
- }
- }
-
- return BUF_FULL;
-}
-
-static boolean send_data(register struct psock *s)
-{
- /* Inidicate that we are blocked waiting for the send to complete */
-
- s->state = STATE_BLOCKED_SEND;
-
- /* Loop until we successfully send the data */
-
- for (;;)
- {
- /* If the data has not been sent OR if it needs to be retransmitted,
- * then send it now.
- */
-
- if (s->state != STATE_DATA_SENT || uip_rexmit())
- {
- if (s->sendlen > uip_mss())
- {
- uip_send(s->sendptr, uip_mss());
- }
- else
- {
- uip_send(s->sendptr, s->sendlen);
- }
-
- s->state = STATE_DATA_SENT;
- }
-
- /* Check if all data has been sent and acknowledged */
-
- if (s->state == STATE_DATA_SENT && uip_acked())
- {
- /* Yes.. the data has been sent AND acknowledge */
-
- if (s->sendlen > uip_mss())
- {
- s->sendlen -= uip_mss();
- s->sendptr += uip_mss();
- }
- else
- {
- s->sendptr += s->sendlen;
- s->sendlen = 0;
- }
-
- s->state = STATE_ACKED;
- return TRUE;
- }
-
- /* No.. then wait on the retransmit or acked events */
-
- (void)uip_event_wait(UIP_ACKDATA|UIP_REXMIT);
- }
-
- return FALSE; /* We never get here */
-}
-
-void psock_send(struct psock *s, const char *buf, unsigned int len)
-{
- /* If there is no data to send, we exit immediately. */
-
- if (len > 0)
- {
- /* Save the length of and a pointer to the data that is to be sent. */
-
- s->sendptr = (const uint8*)buf;
- s->sendlen = len;
- s->state = STATE_NONE;
-
- /* Loop here until all data is sent. The s->sendlen variable is updated
- * by the data_sent() function.
- */
-
- while(s->sendlen > 0) {
-
- /* Wait until the data has been sent and acknowledged */
-
- send_data(s);
- }
-
- /* Done */
-
- s->state = STATE_NONE;
- }
-}
-
-void psock_generator_send(register struct psock *s, unsigned short (*generate)(void *), void *arg)
-{
- /* Ensure that there is a generator function to call. */
-
- if (generate != NULL)
- {
- /* Call the generator function to generate the data in the uip_appdata
- * buffer.
- */
-
- s->sendlen = generate(arg);
- s->sendptr = uip_appdata;
- s->state = STATE_NONE;
-
- do
- {
- /* Call the generator function again if we are called to perform a
- * retransmission.
- */
-
- if (uip_rexmit())
- {
- generate(arg);
- }
-
- /* Wait until all data is sent and acknowledged. */
-
- send_data(s);
- }
- while(s->sendlen > 0);
-
- /* Done */
-
- s->state = STATE_NONE;
- }
-}
-
-uint16 psock_datalen(struct psock *psock)
-{
- return psock->bufsize - psock->buf.left;
-}
-
-boolean psock_checknewdata(struct psock *s)
-{
- if (s->readlen > 0)
- {
- /* There is data in the uip_appdata buffer that has not yet been read
- * with the PSOCK_READ functions.
- */
- return TRUE;
- }
- else if (s->state == STATE_READ)
- {
- /* All data in uip_appdata buffer already consumed. */
-
- s->state = STATE_BLOCKED_NEWDATA;
- return FALSE;
- }
- else if (uip_newdata())
- {
- /* There is new data that has not been consumed. */
-
- return TRUE;
- }
- else
- {
- /* There is no new data. */
-
- return FALSE;
- }
-}
-
-void psock_waitnewdata(struct psock *s)
-{
- while (!psock_checknewdata(s))
- {
- uip_event_wait(UIP_NEWDATA);
- }
-}
-
-void psock_readto(register struct psock *psock, unsigned char c)
-{
-restart:
- buf_setup(&psock->buf, psock->bufptr, psock->bufsize);
-
- /* XXX: Should add buf_checkmarker() before do{} loop, if
- incoming data has been handled while waiting for a write. */
-
- do
- {
- if (psock->readlen == 0)
- {
- psock_waitnewdata(psock);
- psock->state = STATE_READ;
- psock->readptr = (uint8 *)uip_appdata;
- psock->readlen = uip_datalen();
- }
- }
- while((buf_bufto(&psock->buf, c, &psock->readptr, &psock->readlen) & BUF_FOUND) == 0);
-
- if (psock_datalen(psock) == 0)
- {
- psock->state = STATE_NONE;
- goto restart;
- }
-}
-
-void psock_readbuf(register struct psock *psock)
-{
-restart:
- buf_setup(&psock->buf, psock->bufptr, psock->bufsize);
-
- /* XXX: Should add buf_checkmarker() before do{} loop, if
- incoming data has been handled while waiting for a write. */
-
- do
- {
- if (psock->readlen == 0)
- {
- psock_waitnewdata(psock);
- dbg("Waited for newdata\n");
- psock->state = STATE_READ;
- psock->readptr = (uint8 *)uip_appdata;
- psock->readlen = uip_datalen();
- }
- }
- while(buf_bufdata(&psock->buf, psock->bufsize, &psock->readptr, &psock->readlen) != BUF_FULL);
-
- if (psock_datalen(psock) == 0)
- {
- psock->state = STATE_NONE;
- goto restart;
- }
-}
-
-void psock_init(register struct psock *psock, char *buffer, unsigned int buffersize)
-{
- psock->state = STATE_NONE;
- psock->readlen = 0;
- psock->bufptr = (uint8*)buffer;
- psock->bufsize = buffersize;
- buf_setup(&psock->buf, (uint8*)buffer, buffersize);
-}
-
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 9d1380f6b..8f14dc24b 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -123,6 +123,69 @@ static struct uip_conn *uip_find_conn(uint16 portno)
}
/****************************************************************************
+ * 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, -ERRNO on failure
+ *
+ * Assumptions:
+ * Interrupts are disabled
+ *
+ ****************************************************************************/
+
+static int uip_selectport(uint16 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.
+ */
+
+ 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_find_conn(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_find_conn(portno))
+ {
+ /* It is in use... return EADDRINUSE */
+
+ return -EADDRINUSE;
+ }
+ }
+
+ /* Return the selecte or verified port number */
+
+ return portno;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -422,6 +485,20 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in6 *addr)
int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
#endif
{
+ irqstate_t flags;
+ int port;
+
+ /* Verify or select a local port */
+
+ flags = irqsave();
+ port = uip_selectport(ntohs(conn->lport));
+ irqrestore(flags);
+
+ if (port < 0)
+ {
+ return port;
+ }
+
#warning "Need to implement bind logic"
return -ENOSYS;
}
@@ -453,7 +530,7 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
#endif
{
irqstate_t flags;
- uint16 port;
+ 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
@@ -469,29 +546,13 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
* one now.
*/
- port = ntohs(conn->lport);
- if (port == 0)
- {
- /* No local port assigned. Loop until we find a valid listen port number\
- * that is not being used by any other connection.
- */
-
- do
- {
- /* Guess that the next available port number will be the one after
- * the last port number assigned.
- */
-#warning "This need protection from other threads and from interrupts"
- port = ++g_last_tcp_port;
-
- /* Make sure that the port number is within range */
+ flags = irqsave();
+ port = uip_selectport(ntohs(conn->lport));
+ irqrestore(flags);
- if (g_last_tcp_port >= 32000)
- {
- g_last_tcp_port = 4096;
- }
- }
- while (uip_find_conn(g_last_tcp_port));
+ if (port < 0)
+ {
+ return port;
}
/* Initialize and return the connection structure, bind it to the port number */
@@ -511,7 +572,7 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
conn->rto = UIP_RTO;
conn->sa = 0;
conn->sv = 16; /* Initial value of the RTT variance. */
- conn->lport = htons(port);
+ conn->lport = htons((uint16)port);
/* The sockaddr port is 16 bits and already in network order */