summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-01 13:59:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-01 13:59:54 +0000
commit17edc87d5eadbdcd81add3cd4ff8941fee253e14 (patch)
treec55719a909501c0098b9f96ec08e40cb2fe97729 /nuttx/net
parent50041ff73393316f3c4da440844279d49136a9a2 (diff)
downloadpx4-nuttx-17edc87d5eadbdcd81add3cd4ff8941fee253e14.tar.gz
px4-nuttx-17edc87d5eadbdcd81add3cd4ff8941fee253e14.tar.bz2
px4-nuttx-17edc87d5eadbdcd81add3cd4ff8941fee253e14.zip
Add uIP support more multi-threaded socket access
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@858 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/connect.c147
-rw-r--r--nuttx/net/net-close.c56
-rw-r--r--nuttx/net/recvfrom.c169
-rw-r--r--nuttx/net/send.c77
-rw-r--r--nuttx/net/sendto.c25
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip-callback.c252
-rw-r--r--nuttx/net/uip/uip-initialize.c6
-rw-r--r--nuttx/net/uip/uip-internal.h22
-rw-r--r--nuttx/net/uip/uip-tcpappsend.c12
-rw-r--r--nuttx/net/uip/uip-tcpcallback.c107
-rw-r--r--nuttx/net/uip/uip-tcpinput.c2
-rw-r--r--nuttx/net/uip/uip-tcpsend.c2
-rw-r--r--nuttx/net/uip/uip-udpcallback.c8
14 files changed, 618 insertions, 269 deletions
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 8d26f8e7e..3bb28638c 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -50,6 +50,7 @@
#include <net/uip/uip-arch.h>
#include "net-internal.h"
+#include "uip/uip-internal.h"
/****************************************************************************
* Private Types
@@ -58,9 +59,10 @@
#ifdef CONFIG_NET_TCP
struct tcp_connect_s
{
- FAR struct uip_conn *tc_conn; /* Reference to TCP connection structure */
- sem_t tc_sem; /* Semaphore signals recv completion */
- int tc_result; /* OK on success, otherwise a negated errno. */
+ FAR struct uip_conn *tc_conn; /* Reference to TCP connection structure */
+ FAR struct uip_callback_s *tc_cb; /* Reference to callback instance */
+ sem_t tc_sem; /* Semaphore signals recv completion */
+ int tc_result; /* OK on success, otherwise a negated errno. */
};
#endif
@@ -69,12 +71,12 @@ struct tcp_connect_s
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static void connection_event(struct uip_conn *conn, uint8 flags);
-static inline void tcp_setup_callbacks(struct uip_conn *conn, FAR struct socket *psock,
- FAR struct tcp_connect_s *pstate);
-static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status);
-static uint8 tcp_connect_interrupt(struct uip_driver_s *dev,
- struct uip_conn *conn, uint8 flags);
+static void connection_event(struct uip_conn *conn, uint16 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);
+static uint16 tcp_connect_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvprivate, uint16 flags);
#ifdef CONFIG_NET_IPv6
static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in6 *inaddr);
#else
@@ -105,13 +107,13 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static void connection_event(struct uip_conn *conn, uint8 flags)
+static void connection_event(struct uip_conn *conn, uint16 flags)
{
FAR struct socket *psock = (FAR struct socket *)conn->connection_private;
if (psock)
{
- nvdbg("flags: %02x s_flags: %02x\n", flags, psock->s_flags);
+ nvdbg("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
@@ -141,19 +143,34 @@ static void connection_event(struct uip_conn *conn, uint8 flags)
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static inline void tcp_setup_callbacks(struct uip_conn *conn, FAR struct socket *psock,
+static inline int tcp_setup_callbacks(FAR struct socket *psock,
FAR struct tcp_connect_s *pstate)
{
+ FAR struct uip_conn *conn = psock->s_conn;
+ int ret = -EBUSY;
+
+ /* Initialize the TCP state structure */
+
+ (void)sem_init(&pstate->tc_sem, 0, 0); /* Doesn't really fail */
+ pstate->tc_conn = conn;
+ pstate->tc_result = -EAGAIN;
+
/* Set up the callbacks in the connection */
- conn->data_flags = UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT|UIP_CONNECTED;
- conn->data_private = (void*)pstate;
- conn->data_event = tcp_connect_interrupt;
+ pstate->tc_cb = uip_tcpcallbackalloc(conn);
+ if (pstate->tc_cb)
+ {
+ pstate->tc_cb->flags = UIP_NEWDATA|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT|UIP_CONNECTED;
+ pstate->tc_cb->private = (void*)pstate;
+ pstate->tc_cb->event = tcp_connect_interrupt;
- /* Set up to receive callbacks on connection-related events */
+ /* Set up to receive callbacks on connection-related events */
- conn->connection_private = (void*)psock;
- conn->connection_event = connection_event;
+ conn->connection_private = (void*)psock;
+ conn->connection_event = connection_event;
+ ret = OK;
+ }
+ return ret;
}
#endif /* CONFIG_NET_TCP */
@@ -162,13 +179,13 @@ static inline void tcp_setup_callbacks(struct uip_conn *conn, FAR struct socket
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status)
+static inline void tcp_teardown_callbacks(struct tcp_connect_s *pstate, int status)
{
+ struct uip_conn *conn = pstate->tc_conn;
+
/* Make sure that no further interrupts are processed */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ uip_tcpcallbackfree(conn, pstate->tc_cb);
/* If we successfully connected, we will continue to monitor the connection state
* via callbacks.
@@ -193,11 +210,11 @@ static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status)
*
* Parameters:
* dev The sructure of the network driver that caused the interrupt
- * conn The connection structure associated with the socket
+ * pvconn The connection structure associated with the socket
* flags Set of events describing why the callback was invoked
*
* Returned Value:
- * None
+ * The new flags setting
*
* Assumptions:
* Running at the interrupt level
@@ -205,12 +222,12 @@ static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status)
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static uint8 tcp_connect_interrupt(struct uip_driver_s *dev,
- struct uip_conn *conn, uint8 flags)
+static uint16 tcp_connect_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvprivate, uint16 flags)
{
- struct tcp_connect_s *pstate = (struct tcp_connect_s *)conn->data_private;
+ struct tcp_connect_s *pstate = (struct tcp_connect_s *)pvprivate;
- nvdbg("flags: %02x\n", flags);
+ nvdbg("flags: %04x\n", flags);
/* 'private' might be null in some race conditions (?) */
@@ -270,7 +287,7 @@ static uint8 tcp_connect_interrupt(struct uip_driver_s *dev,
/* Stop further callbacks */
- tcp_teardown_callbacks(pstate->tc_conn, pstate->tc_result);
+ tcp_teardown_callbacks(pstate, pstate->tc_result);
/* Wake up the waiting thread */
@@ -306,7 +323,6 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in *inaddr)
#endif
{
- FAR struct uip_conn *conn;
struct tcp_connect_s state;
irqstate_t flags;
int ret = OK;
@@ -320,8 +336,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
/* Get the connection reference from the socket */
- conn = psock->s_conn;
- if (!conn) /* Should always be non-NULL */
+ if (!psock->s_conn) /* Should always be non-NULL */
{
ret = -EINVAL;
}
@@ -329,60 +344,62 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
{
/* Perform the uIP connection operation */
- ret = uip_tcpconnect(conn, inaddr);
+ ret = uip_tcpconnect(psock->s_conn, inaddr);
}
if (ret >= 0)
{
- /* Initialize the TCP state structure */
-
- (void)sem_init(&state.tc_sem, 0, 0); /* Doesn't really fail */
- state.tc_conn = conn;
- state.tc_result = -EAGAIN;
-
/* Set up the callbacks in the connection */
- tcp_setup_callbacks(conn, psock, &state);
-
- /* Wait for either the connect 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 = tcp_setup_callbacks(psock, &state);
+ if (ret >= 0)
+ {
+ /* Wait for either the connect 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-disabled
+ * when the task restarts.
+ */
- ret = sem_wait(&state.tc_sem);
+ ret = sem_wait(&state.tc_sem);
- /* Uninitialize the state structure */
+ /* Uninitialize the state structure */
- (void)sem_destroy(&state.tc_sem);
+ (void)sem_destroy(&state.tc_sem);
- /* If sem_wait failed, recover the negated error (probably -EINTR) */
+ /* If sem_wait failed, recover the negated error (probably -EINTR) */
- if (ret < 0)
- {
- int err = *get_errno_ptr();
- if (err >= 0)
+ if (ret < 0)
{
- err = ENOSYS;
+ int err = errno;
+ if (err >= 0)
+ {
+ err = ENOSYS;
+ }
+ ret = -err;
}
- ret = -err;
- }
- else
- {
- /* If the wait succeeded, then get the new error value from the state structure */
+ else
+ {
+ /* If the wait succeeded, then get the new error value from
+ * the state structure
+ */
- ret = state.tc_result;
- }
+ ret = state.tc_result;
+ }
+
+ /* Make sure that no further interrupts are processed */
- /* Make sure that no further interrupts are processed */
- tcp_teardown_callbacks(conn, ret);
+ tcp_teardown_callbacks(&state, ret);
+ }
/* Mark the connection bound and connected */
+
if (ret >= 0)
{
psock->s_flags |= (_SF_BOUND|_SF_CONNECTED);
}
}
+
irqrestore(flags);
return ret;
}
@@ -543,7 +560,7 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
return OK;
errout:
- *get_errno_ptr() = err;
+ errno = err;
return ERROR;
}
diff --git a/nuttx/net/net-close.c b/nuttx/net/net-close.c
index 8d1be9099..1f704ca00 100644
--- a/nuttx/net/net-close.c
+++ b/nuttx/net/net-close.c
@@ -50,6 +50,7 @@
#include <net/uip/uip-arch.h>
#include "net-internal.h"
+#include "uip/uip-internal.h"
/****************************************************************************
* Private Types
@@ -58,8 +59,9 @@
#ifdef CONFIG_NET_TCP
struct tcp_close_s
{
- FAR struct socket *cl_psock; /* Reference to the TCP socket */
- sem_t cl_sem; /* Semaphore signals disconnect completion */
+ FAR struct socket *cl_psock; /* Reference to the TCP socket */
+ FAR struct uip_callback_s *cl_cb; /* Reference to TCP callback instance */
+ sem_t cl_sem; /* Semaphore signals disconnect completion */
};
#endif
@@ -85,12 +87,12 @@ struct tcp_close_s
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static uint8 netclose_interrupt(struct uip_driver_s *dev,
- struct uip_conn *conn, uint8 flags)
+static uint16 netclose_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvprivate, uint16 flags)
{
- struct tcp_close_s *pstate = (struct tcp_close_s *)conn->data_private;
+ struct tcp_close_s *pstate = (struct tcp_close_s *)pvprivate;
- nvdbg("flags: %02x\n", flags);
+ nvdbg("flags: %04x\n", flags);
if (pstate)
{
@@ -102,9 +104,9 @@ static uint8 netclose_interrupt(struct uip_driver_s *dev,
{
/* The disconnection is complete */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ pstate->cl_cb->flags = 0;
+ pstate->cl_cb->private = NULL;
+ pstate->cl_cb->event = NULL;
sem_post(&pstate->cl_sem);
nvdbg("Resuming\n");
}
@@ -144,7 +146,6 @@ static uint8 netclose_interrupt(struct uip_driver_s *dev,
static inline void netclose_disconnect(FAR struct socket *psock)
{
struct tcp_close_s state;
- struct uip_conn *conn;
irqstate_t flags;
/* Interrupts are disabled here to avoid race conditions */
@@ -155,30 +156,33 @@ static inline void netclose_disconnect(FAR struct socket *psock)
if (_SS_ISCONNECTED(psock->s_flags))
{
- /* Set up to receive TCP data events */
+ struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
- state.cl_psock = psock;
- sem_init(&state.cl_sem, 0, 0);
+ /* Set up to receive TCP data event callbacks */
- conn = psock->s_conn;
- conn->data_flags = UIP_NEWDATA|UIP_CLOSE|UIP_ABORT;
- conn->data_private = (void*)&state;
- conn->data_event = netclose_interrupt;
+ state.cl_cb = uip_tcpcallbackalloc(conn);
+ if (state.cl_cb)
+ {
+ state.cl_psock = psock;
+ sem_init(&state.cl_sem, 0, 0);
- /* Notify the device driver of the availaibilty of TX data */
+ state.cl_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT;
+ state.cl_cb->private = (void*)&state;
+ state.cl_cb->event = netclose_interrupt;
- netdev_txnotify(&conn->ripaddr);
+ /* Notify the device driver of the availaibilty of TX data */
- /* Wait for the disconnect event */
+ netdev_txnotify(&conn->ripaddr);
- (void)sem_wait(&state.cl_sem);
+ /* Wait for the disconnect event */
- /* We are now disconnected */
+ (void)sem_wait(&state.cl_sem);
- sem_destroy(&state.cl_sem);
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ /* We are now disconnected */
+
+ sem_destroy(&state.cl_sem);
+ uip_tcpcallbackfree(conn, state.cl_cb);
+ }
}
irqrestore(flags);
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 9013b6fae..9b0e31d42 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -52,6 +52,7 @@
#include <net/uip/uip-arch.h>
#include "net-internal.h"
+#include "uip/uip-internal.h"
/****************************************************************************
* Definitions
@@ -70,19 +71,20 @@
struct recvfrom_s
{
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- FAR struct socket *rf_sock; /* The parent socket structure */
- uint32 rf_starttime; /* rcv start time for determining timeout */
+ FAR struct socket *rf_sock; /* The parent socket structure */
+ uint32 rf_starttime; /* rcv start time for determining timeout */
#endif
- sem_t rf_sem; /* Semaphore signals recv completion */
- size_t rf_buflen; /* Length of receive buffer */
- char *rf_buffer; /* Pointer to receive buffer */
+ FAR struct uip_callback_s *rf_cb; /* Reference to callback instance */
+ sem_t rf_sem; /* Semaphore signals recv completion */
+ size_t rf_buflen; /* Length of receive buffer */
+ char *rf_buffer; /* Pointer to receive buffer */
#ifdef CONFIG_NET_IPv6
- FAR struct sockaddr_in6 *rf_from; /* Address of sender */
+ FAR struct sockaddr_in6 *rf_from; /* Address of sender */
#else
- FAR struct sockaddr_in *rf_from; /* Address of sender */
+ FAR struct sockaddr_in *rf_from; /* Address of sender */
#endif
- size_t rf_recvlen; /* The received length */
- int rf_result; /* OK:success, failure:negated errno */
+ size_t rf_recvlen; /* The received length */
+ int rf_result; /* OK:success, failure:negated errno */
};
#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
@@ -356,12 +358,12 @@ static inline void recvfrom_tcpsender(struct uip_driver_s *dev, struct recvfrom_
****************************************************************************/
#ifdef CONFIG_NET_TCP
-static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
- struct uip_conn *conn, uint8 flags)
+static uint16 recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
+ void *pvprivate, uint16 flags)
{
- struct recvfrom_s *pstate = (struct recvfrom_s *)conn->data_private;
+ struct recvfrom_s *pstate = (struct recvfrom_s *)pvprivate;
- nvdbg("flags: %02x\n", flags);
+ nvdbg("flags: %04x\n", flags);
/* 'private' might be null in some race conditions (?) */
@@ -379,6 +381,12 @@ static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
recvfrom_tcpsender(dev, pstate);
+ /* Indicate that the data has been consumed and that an ACK
+ * should be sent.
+ */
+
+ flags = (flags & ~UIP_NEWDATA) | UIP_SNDACK;
+
/* If the user buffer has been filled, then we are finished. */
if (pstate->rf_buflen == 0)
@@ -391,9 +399,9 @@ static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
* Don't allow any further TCP call backs.
*/
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Wake up the waiting thread, returning the number of bytes
* actually read.
@@ -419,9 +427,9 @@ static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
/* Stop further callbacks */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Report not connected */
@@ -445,9 +453,9 @@ static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
nvdbg("TCP timeout\n");
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Report an error only if no data has been received */
@@ -533,12 +541,13 @@ static inline void recvfrom_udpsender(struct uip_driver_s *dev, struct recvfrom_
****************************************************************************/
#ifdef CONFIG_NET_UDP
-static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
- struct uip_udp_conn *conn, uint8 flags)
+static uint16 recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvprivate, uint16 flags)
{
- struct recvfrom_s *pstate = (struct recvfrom_s *)conn->private;
+ struct uip_udp_conn *conn = (struct uip_udp_conn *)pvconn;
+ struct recvfrom_s *pstate = (struct recvfrom_s *)pvprivate;
- nvdbg("flags: %02x\n", flags);
+ nvdbg("flags: %04x\n", flags);
/* 'private' might be null in some race conditions (?) */
@@ -558,14 +567,19 @@ static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
/* Don't allow any further UDP call backs. */
- conn->private = NULL;
- conn->event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Save the sender's address in the caller's 'from' location */
recvfrom_udpsender(dev, pstate);
- /* Wake up the waiting thread, returning the number of bytes
+ /* Indicate that the data has been consumed */
+
+ flags &= ~UIP_NEWDATA;
+
+ /* Wake up the waiting thread, returning the number of bytes
* actually read.
*/
@@ -580,8 +594,9 @@ static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
/* Stop further callbacks */
- conn->private = NULL;
- conn->event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Report not connected */
@@ -607,8 +622,9 @@ static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
/* Stop further callbacks */
- conn->private = NULL;
- conn->event = NULL;
+ pstate->rf_cb->flags = 0;
+ pstate->rf_cb->private = NULL;
+ pstate->rf_cb->event = NULL;
/* Report a timeout error */
@@ -620,6 +636,7 @@ static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
}
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
}
+ return flags;
}
#endif /* CONFIG_NET_UDP */
@@ -773,29 +790,40 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Set up the callback in the connection */
- udp_conn->private = (void*)&state;
- udp_conn->event = recvfrom_udpinterrupt;
+ state.rf_cb = uip_udpcallbackalloc(psock->s_conn);
+ if (state.rf_cb)
+ {
+ /* Set up the callback in the connection */
- /* Enable the UDP socket */
+ state.rf_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.rf_cb->private = (void*)&state;
+ state.rf_cb->event = recvfrom_udpinterrupt;
- uip_udpenable(udp_conn);
+ /* Enable the UDP socket */
- /* 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.
- */
+ uip_udpenable(udp_conn);
- ret = sem_wait(&state. rf_sem);
+ /* 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.
+ */
- /* Make sure that no further interrupts are processed */
+ ret = sem_wait(&state. rf_sem);
- uip_udpdisable(udp_conn);
- udp_conn->private = NULL;
- udp_conn->event = NULL;
- irqrestore(save);
+ /* Make sure that no further interrupts are processed */
- return recvfrom_result(ret, &state);
+ uip_udpdisable(udp_conn);
+ uip_udpcallbackfree(psock->s_conn, state.rf_cb);
+ irqrestore(save);
+ ret = recvfrom_result(ret, &state);
+ }
+ else
+ {
+ ret = -EBUSY;
+ }
+
+ return ret;
}
#endif /* CONFIG_NET_UDP */
@@ -828,7 +856,6 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
FAR struct sockaddr_in *infrom )
#endif
{
- struct uip_conn *conn;
struct recvfrom_s state;
irqstate_t save;
int ret = OK;
@@ -864,30 +891,38 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
if (state.rf_buflen > 0)
#endif
{
- /* Set up the callback in the connection */
+ struct uip_conn *conn = (struct uip_conn *)psock->s_conn;
- conn = (struct uip_conn *)psock->s_conn;
- conn->data_flags = UIP_NEWDATA|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
- conn->data_private = (void*)&state;
- conn->data_event = recvfrom_tcpinterrupt;
+ /* Set up the callback in the connection */
- /* 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.
- */
+ state.rf_cb = uip_tcpcallbackalloc(conn);
+ if (state.rf_cb)
+ {
+ state.rf_cb->flags = UIP_NEWDATA|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.rf_cb->private = (void*)&state;
+ state.rf_cb->event = recvfrom_tcpinterrupt;
+
+ /* 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);
+ ret = sem_wait(&state.rf_sem);
- /* Make sure that no further interrupts are processed */
+ /* Make sure that no further interrupts are processed */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ uip_tcpcallbackfree(conn, state.rf_cb);
+ ret = recvfrom_result(ret, &state);
+ }
+ else
+ {
+ ret = -EBUSY;
+ }
}
- irqrestore(save);
- return recvfrom_result(ret, &state);
+ irqrestore(save);
+ return ret;
}
#endif /* CONFIG_NET_TCP */
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index e67b2f3e4..872adb391 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -51,6 +51,7 @@
#include <net/uip/uip-arch.h>
#include "net-internal.h"
+#include "uip/uip-internal.h"
/****************************************************************************
* Definitions
@@ -68,15 +69,16 @@
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 */
- uint32 snd_isn; /* Initial sequence number */
- uint32 snd_acked; /* The number of bytes acked */
+ FAR struct socket *snd_sock; /* Points to the parent socket structure */
+ FAR struct uip_callback_s *snd_cb; /* Reference to callback instance */
+ 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 */
+ uint32 snd_isn; /* Initial sequence number */
+ uint32 snd_acked; /* The number of bytes acked */
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- uint32 snd_time; /* last send time for determining timeout */
+ uint32 snd_time; /* last send time for determining timeout */
#endif
};
@@ -192,12 +194,13 @@ static inline int send_timeout(struct send_s *pstate)
*
****************************************************************************/
-static uint8 send_interrupt(struct uip_driver_s *dev, struct uip_conn *conn,
- uint8 flags)
+static uint16 send_interrupt(struct uip_driver_s *dev, void *pvconn,
+ void *pvprivate, uint16 flags)
{
- struct send_s *pstate = (struct send_s *)conn->data_private;
+ struct uip_conn *conn = (struct uip_conn*)pvconn;
+ struct send_s *pstate = (struct send_s *)pvprivate;
- nvdbg("flags: %02x acked: %d sent: %d\n", flags, pstate->snd_acked, pstate->snd_sent);
+ nvdbg("flags: %04x acked: %d sent: %d\n", flags, pstate->snd_acked, pstate->snd_sent);
/* If this packet contains an acknowledgement, then update the count of
* acknowldged bytes.
@@ -301,9 +304,9 @@ static uint8 send_interrupt(struct uip_driver_s *dev, struct uip_conn *conn,
end_wait:
/* Do not allow any further callbacks */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ pstate->snd_cb->flags = 0;
+ pstate->snd_cb->private = NULL;
+ pstate->snd_cb->event = NULL;
/* Wake up the waiting thread */
@@ -382,7 +385,6 @@ end_wait:
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;
@@ -424,34 +426,39 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
if (len > 0)
{
- /* Get the initial sequence number that will be used */
+ struct uip_conn *conn = (struct uip_conn*)psock->s_conn;
- conn = (struct uip_conn *)psock->s_conn;
- state.snd_isn = send_getisn(conn); /* Initial sequence number */
+ /* Allocate resources to receive a callback */
- /* Set up the callback in the connection */
+ state.snd_cb = uip_tcpcallbackalloc(conn);
+ if (state.snd_cb)
+ {
+ /* Get the initial sequence number that will be used */
- conn->data_flags = UIP_REXMIT|UIP_ACKDATA|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
- conn->data_private = (void*)&state;
- conn->data_event = send_interrupt;
+ state.snd_isn = send_getisn(conn); /* Initial sequence number */
- /* Notify the device driver of the availaibilty of TX data */
+ /* Set up the callback in the connection */
- netdev_txnotify(&conn->ripaddr);
+ state.snd_cb->flags = UIP_ACKDATA|UIP_REXMIT|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.snd_cb->private = (void*)&state;
+ state.snd_cb->event = 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.
- */
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&conn->ripaddr);
- ret = sem_wait(&state. snd_sem);
+ /* 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 */
+ /* Make sure that no further interrupts are processed */
- conn->data_flags = 0;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ uip_tcpcallbackfree(conn, state.snd_cb);
+ }
}
sem_destroy(&state. snd_sem);
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index 0e5b80032..89133d200 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -60,6 +60,7 @@
struct sendto_s
{
+ FAR struct uip_callback_s *snd_cb; /* Reference to callback instance */
sem_t st_sem; /* Semaphore signals sendto completion */
uint16 st_buflen; /* Length of send buffer (error if <0) */
const char *st_buffer; /* Pointer to send buffer */
@@ -95,7 +96,7 @@ void sendto_interrupt(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8
{
struct sendto_s *pstate = (struct sendto_s *)conn->private;
- nvdbg("flags: %02x\n");
+ nvdbg("flags: %04x\n", flags);
if (pstate)
{
/* Check if the connection was rejected */
@@ -116,8 +117,9 @@ void sendto_interrupt(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8
/* Don't allow any further call backs. */
- conn->private = NULL;
- conn->event = NULL;
+ pstate->st_cb->flags = 0;
+ pstate->st_cb->private = NULL;
+ pstate->st_cb->event = NULL;
/* Wake up the waiting thread */
@@ -205,7 +207,6 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
#else
FAR const struct sockaddr_in *into = (const struct sockaddr_in *)to;
#endif
- struct uip_udp_conn *udp_conn;
struct sendto_s state;
irqstate_t save;
int ret;
@@ -286,9 +287,13 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Set up the callback in the connection */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = (void*)&state;
- udp_conn->event = sendto_interrupt;
+ state.st_cb = uip_udpcallbackalloc((struct uip_udp_conn *)psock->s_conn);
+ if (state.st_cb)
+ {
+ state.st_cb->flags = UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
+ state.st_cb->flags = 0;
+ state.st_cb->private = (void*)&state;
+ state.st_cb->event = sendto_interrupt;
/* Enable the UDP socket */
@@ -309,8 +314,8 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Make sure that no further interrupts are processed */
uip_udpdisable(psock->s_conn);
- udp_conn->private = NULL;
- udp_conn->event = NULL;
+ uip_udpcallbackfree(psock->s_conn, state.st_cb);
+ }
irqrestore(save);
sem_destroy(&state.st_sem);
@@ -335,7 +340,7 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
#endif
errout:
- *get_errno_ptr() = err;
+ errno = err;
return ERROR;
}
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index 4512e11c3..71fcdf67c 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -41,7 +41,7 @@ ifeq ($(CONFIG_NET),y)
# Common IP source files
UIP_CSRCS += uip-initialize.c uip-setipid.c uip-arp.c uip-input.c uip-send.c \
- uip-poll.c uip-chksum.c
+ uip-poll.c uip-chksum.c uip-callback.c
ifeq ($(CONFIG_NET_IPv6),y)
UIP_CSRCS += uip-neighbor.c
diff --git a/nuttx/net/uip/uip-callback.c b/nuttx/net/uip/uip-callback.c
new file mode 100644
index 000000000..22755a43a
--- /dev/null
+++ b/nuttx/net/uip/uip-callback.c
@@ -0,0 +1,252 @@
+/****************************************************************************
+ * net/uip/uip-callback.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 <nuttx/config.h>
+#if defined(CONFIG_NET)
+
+#include <sys/types.h>
+#include <string.h>
+#include <debug.h>
+
+#include <net/uip/uipopt.h>
+#include <net/uip/uip.h>
+#include <net/uip/uip-arch.h>
+
+#include "uip-internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct uip_callback_s g_cbprealloc[CONFIG_NET_NACTIVESOCKETS];
+static FAR struct uip_callback_s *g_cbfreelist = NULL;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_callbackinit
+ *
+ * Description:
+ * Configure the pre-allocated callaback structures into a free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_callbackinit(void)
+{
+ int i;
+ for (i = 0; i < CONFIG_NET_NACTIVESOCKETS; i++)
+ {
+ g_cbprealloc[i].flink = g_cbfreelist;
+ g_cbfreelist = &g_cbprealloc[i];
+ }
+}
+
+/****************************************************************************
+ * Function: uip_callbackalloc
+ *
+ * Description:
+ * Allocate a callback container from the free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+FAR struct uip_callback_s *uip_callbackalloc(FAR struct uip_callback_s **list)
+{
+ struct uip_callback_s *ret;
+ irqstate_t save;
+
+ /* Check the head of the free list */
+
+ save = irqsave();
+ ret = g_cbfreelist;
+ if (ret)
+ {
+ /* Remove the next instance from the head of the free list */
+
+ g_cbfreelist = ret->flink;
+ memset(ret, 0, sizeof(struct uip_callback_s));
+
+ /* Add the newly allocated instance to the head of the specified list */
+
+ if (list)
+ {
+ ret->flink = *list;
+ *list = ret;
+ }
+ else
+ {
+ ret->flink = NULL;
+ }
+ }
+#ifdef CONFIG_DEBUG
+ else
+ {
+ dbg("Failed to allocate callback\n");
+ }
+#endif
+
+ irqrestore(save);
+ return ret;
+}
+
+/****************************************************************************
+ * Function: uip_callbackfree
+ *
+ * Description:
+ * Return a callback container to the free list.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+void uip_callbackfree(FAR struct uip_callback_s *cb, FAR struct uip_callback_s **list)
+{
+ FAR struct uip_callback_s *prev;
+ FAR struct uip_callback_s *curr;
+ irqstate_t save;
+
+ if (cb)
+ {
+ /* Find the callback structure in the connection's list */
+
+ save = irqsave();
+ if (list)
+ {
+ for (prev = NULL, curr = *list;
+ curr && curr != cb;
+ prev = curr, curr = curr->flink);
+
+ /* Remove the structure from the connection's list */
+
+ if (curr)
+ {
+ if (prev)
+ {
+ prev->flink = cb->flink;
+ }
+ else
+ {
+ *list = cb->flink;
+ }
+ }
+ }
+
+ /* Put the structure into the free list */
+
+ cb->flink = g_cbfreelist;
+ g_cbfreelist = cb;
+ irqrestore(save);
+ }
+}
+
+/****************************************************************************
+ * Function: uip_callbackexecute
+ *
+ * Description:
+ * Execute a list of callbacks.
+ * This is called internally as part of uIP initialization and should not
+ * be accessed from the application or socket layer.
+ *
+ * Assumptions:
+ * This function is called with interrupts disabled.
+ *
+ ****************************************************************************/
+
+uint16 uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn, uint16 flags,
+ FAR struct uip_callback_s *list)
+{
+ FAR struct uip_callback_s *next;
+ irqstate_t save;
+
+ /* Loop for each callback in the list and while there are still events
+ * set in the flags set.
+ */
+
+ save = irqsave();
+ while (list && flags)
+ {
+ /* Save the pointer to the next callback in the lists. This is done
+ * because the callback action might delete the entry pointed to by
+ * list.
+ */
+
+ next = list->flink;
+
+ /* Check if this callback handles any of the events in the flag set */
+
+ if (list->event && (flags & list->flags) != 0)
+ {
+ /* Yes.. perform the callback. Actions perform by the callback
+ * may delete the current list entry or add a new list entry to
+ * beginning of the list (which will be ignored on this pass)
+ */
+
+ vdbg("Call event=%p with flags=%04x\n", list->event, flags);
+ flags = list->event(dev, pvconn, list->private, flags);
+ }
+
+ /* Set up for the next time through the loop */
+
+ list = next;
+ }
+
+ irqrestore(save);
+ return flags;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip-initialize.c b/nuttx/net/uip/uip-initialize.c
index 9b51e1735..c2ea121ec 100644
--- a/nuttx/net/uip/uip-initialize.c
+++ b/nuttx/net/uip/uip-initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip-initialize.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>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
@@ -114,6 +114,10 @@ uint8 uip_reasstmr;
void uip_initialize(void)
{
+ /* Initialize callback support */
+
+ uip_callbackinit();
+
/* Initialize the listening port structures */
#ifdef CONFIG_NET_TCP
diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h
index 2aab6fbe3..e408a66b3 100644
--- a/nuttx/net/uip/uip-internal.h
+++ b/nuttx/net/uip/uip-internal.h
@@ -118,6 +118,14 @@ extern "C" {
#define EXTERN extern
#endif
+/* Defined in uip_callback.c ************************************************/
+
+EXTERN void uip_callbackinit(void);
+EXTERN FAR struct uip_callback_s *uip_callbackalloc(struct uip_callback_s **list);
+EXTERN void uip_callbackfree(FAR struct uip_callback_s *cb, struct uip_callback_s **list);
+EXTERN uint16 uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
+ uint16 flags, FAR struct uip_callback_s *list);
+
#ifdef CONFIG_NET_TCP
/* Defined in uip_tcpconn.c *************************************************/
@@ -145,7 +153,7 @@ EXTERN int uip_accept(struct uip_conn *conn, uint16 portno);
/* Defined in uip-tcpsend.c *************************************************/
EXTERN void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint8 flags, uint16 len);
+ uint16 flags, uint16 len);
EXTERN void uip_tcpreset(struct uip_driver_s *dev);
EXTERN void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn,
uint8 ack);
@@ -153,9 +161,9 @@ EXTERN void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn,
/* Defined in uip-tcpappsend.c **********************************************/
EXTERN void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint8 result);
+ uint16 result);
EXTERN void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn,
- uint8 result);
+ uint16 result);
/* Defined in uip-tcpinput.c ************************************************/
@@ -163,8 +171,8 @@ EXTERN void uip_tcpinput(struct uip_driver_s *dev);
/* Defined in uip_tcpcallback.c *********************************************/
-EXTERN uint8 uip_tcpcallback(struct uip_driver_s *dev,
- struct uip_conn *conn, uint8 flags);
+EXTERN uint16 uip_tcpcallback(struct uip_driver_s *dev,
+ struct uip_conn *conn, uint16 flags);
/* Defined in uip-tcpreadahead.c ********************************************/
@@ -195,10 +203,10 @@ EXTERN void uip_udpsend(struct uip_driver_s *dev, struct uip_udp_conn *conn);
EXTERN void uip_udpinput(struct uip_driver_s *dev);
-/* Defined in uip_uipcallback.c *********************************************/
+/* Defined in uip_udpcallback.c *********************************************/
EXTERN void uip_udpcallback(struct uip_driver_s *dev,
- struct uip_udp_conn *conn, uint8 flags);
+ struct uip_udp_conn *conn, uint16 flags);
#endif /* CONFIG_NET_UDP */
#ifdef CONFIG_NET_ICMP
diff --git a/nuttx/net/uip/uip-tcpappsend.c b/nuttx/net/uip/uip-tcpappsend.c
index 2ef57004b..93f840b02 100644
--- a/nuttx/net/uip/uip-tcpappsend.c
+++ b/nuttx/net/uip/uip-tcpappsend.c
@@ -94,11 +94,11 @@
*
****************************************************************************/
-void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn, uint8 result)
+void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn, uint16 result)
{
/* Handle the result based on the application response */
- nvdbg("result: %02x\n", result);
+ nvdbg("result: %04x\n", result);
/* Check for connection aborted */
@@ -202,9 +202,9 @@ void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn, uint8 resul
*
****************************************************************************/
-void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn, uint8 result)
+void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn, uint16 result)
{
- nvdbg("result: %02x\n", result);
+ nvdbg("result: %04x\n", result);
dev->d_appdata = dev->d_snddata;
@@ -221,9 +221,9 @@ void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn, uint8 result
uip_tcpsend(dev, conn, TCP_ACK | TCP_PSH, conn->len + UIP_TCPIP_HLEN);
}
- /* If there is no data to send, just send out a pure ACK if there is newdata. */
+ /* If there is no data to send, just send out a pure ACK if one is requested`. */
- else if (result & UIP_NEWDATA)
+ else if (result & UIP_SNDACK)
{
uip_tcpsend(dev, conn, TCP_ACK, UIP_TCPIP_HLEN);
}
diff --git a/nuttx/net/uip/uip-tcpcallback.c b/nuttx/net/uip/uip-tcpcallback.c
index 7c7fb2209..b99e41f9f 100644
--- a/nuttx/net/uip/uip-tcpcallback.c
+++ b/nuttx/net/uip/uip-tcpcallback.c
@@ -102,24 +102,32 @@ static int uip_readahead(struct uip_readahead_s *readahead, uint8 *buf, int len)
* Function: uip_dataevent
*
* Description:
- * This is the default data_event handler that is called when there is no
- * use data handler in place
+ * This is the default data event handler that is called when there is no
+ * user data handler in place
*
* Assumptions:
- * This function is called at the interrupt level with interrupts disabled.
+ * - The called has checked that UIP_NEWDATA is set in flags and that is no
+ * other handler available to process the incoming data.
+ * - This function is called at the interrupt level with interrupts disabled.
*
****************************************************************************/
-static inline uint8
-uip_dataevent(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags)
+static inline uint16
+uip_dataevent(struct uip_driver_s *dev, struct uip_conn *conn, uint16 flags)
{
- uint8 ret = flags;
+ uint16 ret;
+
+ /* Assume that we will ACK the data. The data will be ACKed if it is
+ * placed in the read-ahead buffer -OR- if it zero length
+ */
+
+ ret = (flags & ~UIP_NEWDATA) | UIP_SNDACK;
/* Is there new data? With non-zero length? (Certain connection events
* can have zero-length with UIP_NEWDATA set just to cause an ACK).
*/
- if ((flags & UIP_NEWDATA) != 0 && dev->d_len > 0)
+ if (dev->d_len > 0)
{
#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
struct uip_readahead_s *readahead1;
@@ -127,7 +135,11 @@ uip_dataevent(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags)
uint16 recvlen = 0;
uint8 *buf = dev->d_appdata;
int buflen = dev->d_len;
+#endif
+ nvdbg("No listener on connection\n");
+
+#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
/* First, we need to determine if we have space to buffer the data. This
* needs to be verified before we actually begin buffering the data. We
* will use any remaining space in the last allocated readahead buffer
@@ -169,28 +181,30 @@ uip_dataevent(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags)
sq_addlast(&readahead2->rh_node, &conn->readahead);
}
- /* Indicate that all of the data in the buffer has been consumed */
-
nvdbg("Buffered %d bytes\n", dev->d_len);
- dev->d_len = 0;
}
else
#endif
{
/* There is no handler to receive new data and there are no free
- * read-ahead buffers to retain the data. In this case, clear the
- * UIP_NEWDATA bit so that no ACK will be sent and drop the packet.
+ * read-ahead buffers to retain the data -- drop the packet.
*/
-#ifdef CONFIG_NET_STATISTICS
+ nvdbg("Dropped %d bytes\n", dev->d_len);
+
+ #ifdef CONFIG_NET_STATISTICS
uip_stat.tcp.syndrop++;
uip_stat.tcp.drop++;
#endif
- ret &= ~UIP_NEWDATA;
- dev->d_len = 0;
+ /* Clear the UIP_SNDACK bit so that no ACK will be sent */
+
+ ret &= ~UIP_SNDACK;
}
}
+ /* In any event, the new data has now been handled */
+
+ dev->d_len = 0;
return ret;
}
@@ -209,7 +223,7 @@ uip_dataevent(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags)
*
****************************************************************************/
-uint8 uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags)
+uint16 uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn, uint16 flags)
{
/* Preserve the UIP_ACKDATA, UIP_CLOSE, and UIP_ABORT in the response.
* These is needed by uIP to handle responses and buffer state. The
@@ -217,39 +231,42 @@ uint8 uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn, uint8 fla
* explicitly set in the callback.
*/
- uint8 ret = flags;
-
- nvdbg("flags: %02x\n", flags);
-
- /* Check if there is a data callback */
-
- if (conn->data_event)
- {
- /* Perform the callback. Callback function normally returns the input flags,
- * however, the implementation may set one of the following:
- *
- * UIP_CLOSE - Gracefully close the current connection
- * UIP_ABORT - Abort (reset) the current connection on an error that
- * prevents UIP_CLOSE from working.
- *
- * Or clear the following:
- *
- * UIP_NEWDATA - May be cleared to suppress returning the ACK response.
- * (dev->d_len should also be set to zero in this case).
- */
-
- ret = conn->data_event(dev, conn, flags);
- }
-
- /* If there is no data callback -OR- if the data callback does not handle the
- * newdata event, then there is no handler in place to handle new incoming data.
+ uint16 ret = flags;
+
+ nvdbg("flags: %04x\n", flags);
+
+ /* Perform the data callback. When a data callback is executed from 'list',
+ * the input flags are normally returned, however, the implementation
+ * may set one of the following:
+ *
+ * UIP_CLOSE - Gracefully close the current connection
+ * UIP_ABORT - Abort (reset) the current connection on an error that
+ * prevents UIP_CLOSE from working.
+ *
+ * And/Or set/clear the following:
+ *
+ * UIP_NEWDATA - May be cleared to indicate that the data was consumed
+ * and that no further process of the new data should be
+ * attempted.
+ * UIP_SNDACK - If UIP_NEWDATA is cleared, then UIP_SNDACK may be set
+ * to indicate that an ACK should be included in the response.
+ * (In UIP_NEWDATA is cleared bu UIP_SNDACK is not set, then
+ * dev->d_len should also be cleared).
+ */
+
+ ret = uip_callbackexecute(dev, conn, flags, conn->list);
+
+ /* There may be no new data handler in place at them moment that the new
+ * incoming data is received. If the new incoming data was not handled, then
+ * either (1) put the unhandled incoming data in the read-ahead buffer (if
+ * enabled) or (2) suppress the ACK to the data in the hope that it will
+ * be re-transmitted at a better time.
*/
- if (!conn->data_event || (conn->data_flags & UIP_NEWDATA) == 0)
+ if ((ret & UIP_NEWDATA) != 0)
{
- /* In either case, we will take a default newdata action */
+ /* Data was not handled.. dispose of it appropriately */
- nvdbg("No listener on connection\n");
ret = uip_dataevent(dev, conn, ret);
}
diff --git a/nuttx/net/uip/uip-tcpinput.c b/nuttx/net/uip/uip-tcpinput.c
index 73eb73592..5a7b5b923 100644
--- a/nuttx/net/uip/uip-tcpinput.c
+++ b/nuttx/net/uip/uip-tcpinput.c
@@ -98,8 +98,8 @@ void uip_tcpinput(struct uip_driver_s *dev)
{
struct uip_conn *conn = NULL;
uint16 tmp16;
+ uint16 flags;
uint8 opt;
- uint8 flags;
uint8 result;
int len;
int i;
diff --git a/nuttx/net/uip/uip-tcpsend.c b/nuttx/net/uip/uip-tcpsend.c
index b68788b93..17cc6fc92 100644
--- a/nuttx/net/uip/uip-tcpsend.c
+++ b/nuttx/net/uip/uip-tcpsend.c
@@ -228,7 +228,7 @@ static void uip_tcpsendcommon(struct uip_driver_s *dev, struct uip_conn *conn)
*
****************************************************************************/
-void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags, uint16 len)
+void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn, uint16 flags, uint16 len)
{
BUF->flags = flags;
dev->d_len = len;
diff --git a/nuttx/net/uip/uip-udpcallback.c b/nuttx/net/uip/uip-udpcallback.c
index ae5187913..6c7fecef3 100644
--- a/nuttx/net/uip/uip-udpcallback.c
+++ b/nuttx/net/uip/uip-udpcallback.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip-udpcallback.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>
*
*
@@ -74,9 +74,9 @@
****************************************************************************/
void uip_udpcallback(struct uip_driver_s *dev, struct uip_udp_conn *conn,
- uint8 flags)
+ uint16 flags)
{
- nvdbg("flags: %02x\n", flags);
+ nvdbg("flags: %04x\n", flags);
/* Some sanity checking */
@@ -84,7 +84,7 @@ void uip_udpcallback(struct uip_driver_s *dev, struct uip_udp_conn *conn,
{
/* Perform the callback */
- conn->event(dev, conn, flags);
+ flags = uip_callbackexecute(dev, conn, flags, conn->list);
}
}