summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-01 15:22:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-01 15:22:54 +0000
commitbe49f2a7430aa0dd9c0c09002af15bb2618cadb0 (patch)
treea4e4aa6be32a7606a0f2a3cfdc429f0543bbe8c2 /nuttx
parent17edc87d5eadbdcd81add3cd4ff8941fee253e14 (diff)
downloadpx4-nuttx-be49f2a7430aa0dd9c0c09002af15bb2618cadb0.tar.gz
px4-nuttx-be49f2a7430aa0dd9c0c09002af15bb2618cadb0.tar.bz2
px4-nuttx-be49f2a7430aa0dd9c0c09002af15bb2618cadb0.zip
Verify UDP support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@859 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/common/up_assert.c4
-rw-r--r--nuttx/include/net/uip/uip.h18
-rw-r--r--nuttx/net/recvfrom.c15
-rw-r--r--nuttx/net/send.c20
-rw-r--r--nuttx/net/sendto.c69
-rw-r--r--nuttx/net/uip/uip-udpcallback.c2
6 files changed, 80 insertions, 48 deletions
diff --git a/nuttx/arch/arm/src/common/up_assert.c b/nuttx/arch/arm/src/common/up_assert.c
index 9ddaf555c..895b1f0f5 100644
--- a/nuttx/arch/arm/src/common/up_assert.c
+++ b/nuttx/arch/arm/src/common/up_assert.c
@@ -189,7 +189,7 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
void up_assert(const ubyte *filename, int lineno)
{
-#if CONFIG_TASK_NAME_SIZE > 0
+#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
_TCB *rtcb = (_TCB*)g_readytorun.head;
#endif
@@ -211,7 +211,7 @@ void up_assert(const ubyte *filename, int lineno)
void up_assert_code(const ubyte *filename, int lineno, int errorcode)
{
-#if CONFIG_TASK_NAME_SIZE > 0
+#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
_TCB *rtcb = (_TCB*)g_readytorun.head;
#endif
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 52e7e98b4..08f2c14a3 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -66,7 +66,7 @@
*
* UIP_ACKDATA IN: Signifies that the outstanding data was acked and
* the application should send out new data instead
- * of retransmitting the last data
+ * of retransmitting the last data (TCP only)
* OUT: Input state must be preserved on output.
* UIP_NEWDATA IN: Set to indicate that the peer has sent us new data.
* OUT: Cleared (only) by the application logic to indicate
@@ -74,9 +74,9 @@
* attempts to process the new data.
* UIP_SNDACK IN: Not used; always zero
* OUT: Set by the application if the new data was consumed
- * and an ACK should be sent in the response.
+ * and an ACK should be sent in the response. (TCP only)
* UIP_REXMIT IN: Tells the application to retransmit the data that
- * was last sent
+ * was last sent. (TCP only)
* OUT: Not used
* UIP_POLL IN: Used for polling the application. This is provided
* periodically from the drivers to support (1) timed
@@ -84,19 +84,19 @@
* data that it wants to send
* OUT: Not used
* UIP_CLOSE IN: The remote host has closed the connection, thus the
- * connection has gone away.
+ * connection has gone away. (TCP only)
* OUT: The application signals that it wants to close the
- * connection
+ * connection. (TCP only)
* UIP_ABORT IN: The remote host has aborted the connection, thus the
- * connection has gone away.
+ * connection has gone away. (TCP only)
* OUT: The application signals that it wants to abort the
- * connection
+ * connection. (TCP only)
* UIP_CONNECTED IN: We have got a connection from a remote host and have
* set up a new connection for it, or an active connection
- * has been successfully established
+ * has been successfully established. (TCP only)
* OUT: Not used
* UIP_TIMEDOUT IN: The connection has been aborted due to too many
- * retransmissions
+ * retransmissions. (TCP only)
* OUT: Not used
*/
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 9b0e31d42..12f50f8c3 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/recvfrom.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>
*
* Redistribution and use in source and binary forms, with or without
@@ -544,7 +544,6 @@ static inline void recvfrom_udpsender(struct uip_driver_s *dev, struct recvfrom_
static uint16 recvfrom_udpinterrupt(struct uip_driver_s *dev, void *pvconn,
void *pvprivate, uint16 flags)
{
- struct uip_udp_conn *conn = (struct uip_udp_conn *)pvconn;
struct recvfrom_s *pstate = (struct recvfrom_s *)pvprivate;
nvdbg("flags: %04x\n", flags);
@@ -764,7 +763,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
FAR struct sockaddr_in *infrom )
#endif
{
- struct uip_udp_conn *udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ struct uip_udp_conn *conn = (struct uip_udp_conn *)psock->s_conn;
struct recvfrom_s state;
irqstate_t save;
int ret;
@@ -781,7 +780,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Setup the UDP remote connection */
- ret = uip_udpconnect(udp_conn, infrom);
+ ret = uip_udpconnect(conn, infrom);
if (ret < 0)
{
irqrestore(save);
@@ -790,7 +789,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Set up the callback in the connection */
- state.rf_cb = uip_udpcallbackalloc(psock->s_conn);
+ state.rf_cb = uip_udpcallbackalloc(conn);
if (state.rf_cb)
{
/* Set up the callback in the connection */
@@ -801,7 +800,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Enable the UDP socket */
- uip_udpenable(udp_conn);
+ uip_udpenable(conn);
/* 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)
@@ -813,8 +812,8 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Make sure that no further interrupts are processed */
- uip_udpdisable(udp_conn);
- uip_udpcallbackfree(psock->s_conn, state.rf_cb);
+ uip_udpdisable(conn);
+ uip_udpcallbackfree(conn, state.rf_cb);
irqrestore(save);
ret = recvfrom_result(ret, &state);
}
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 872adb391..14b9dc8cf 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/send.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>
*
* Redistribution and use in source and binary forms, with or without
@@ -256,9 +256,23 @@ static uint16 send_interrupt(struct uip_driver_s *dev, void *pvconn,
goto end_wait;
}
+ /* Check if the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread.
+ */
+
+#if 0 /* We can't really support multiple senders on the same TCP socket */
+ else if (dev->d_sndlen > 0)
+ {
+ /* Another thread has beat us sending data, wait for the next poll */
+
+ return flags;
+ }
+#endif
+
/* We get here if (1) not all of the data has been ACKed, (2) we have been
- * asked to retransmit data, and (3) the connection is still healthy.
- * We are now free to send more data to receiver.
+ * asked to retransmit data, (3) the connection is still healthy, and (4)
+ * the outgoing packet is available for our use. In this case, we are
+ * now free to send more data to receiver.
*/
if (pstate->snd_sent < pstate->snd_buflen)
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index 89133d200..519510fe6 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/sendto.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>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#include <net/uip/uip-arch.h>
#include "net-internal.h"
+#include "uip/uip-internal.h"
/****************************************************************************
* Definitions
@@ -60,7 +61,7 @@
struct sendto_s
{
- FAR struct uip_callback_s *snd_cb; /* Reference to callback instance */
+ FAR struct uip_callback_s *st_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 */
@@ -79,12 +80,13 @@ struct sendto_s
* send operation when polled by the uIP layer.
*
* Parameters:
- * dev The sructure of the network driver that caused the interrupt
- * private An instance of struct sendto_s cast to void*
- * flags Set of events describing why the callback was invoked
+ * dev The sructure of the network driver that caused the interrupt
+ * conn An instance of the UDP connection structure cast to void *
+ * pvprivate An instance of struct sendto_s cast to void*
+ * flags Set of events describing why the callback was invoked
*
* Returned Value:
- * None
+ * Modified value of the input flags
*
* Assumptions:
* Running at the interrupt level
@@ -92,9 +94,9 @@ struct sendto_s
****************************************************************************/
#ifdef CONFIG_NET_UDP
-void sendto_interrupt(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8 flags)
+uint16 sendto_interrupt(struct uip_driver_s *dev, void *conn, void *pvprivate, uint16 flags)
{
- struct sendto_s *pstate = (struct sendto_s *)conn->private;
+ struct sendto_s *pstate = (struct sendto_s *)pvprivate;
nvdbg("flags: %04x\n", flags);
if (pstate)
@@ -107,9 +109,23 @@ void sendto_interrupt(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8
pstate->st_sndlen = -ENOTCONN;
}
+
+ /* Check if the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread.
+ */
+
+ else if (dev->d_sndlen > 0)
+ {
+ /* Another thread has beat us sending data, wait for the next poll */
+
+ return flags;
+ }
+
+ /* It looks like we are good to send the data */
+
else
{
- /* No.. Copy the user data into d_snddata and send it */
+ /* Copy the user data into d_snddata and send it */
uip_send(dev, pstate->st_buffer, pstate->st_buflen);
pstate->st_sndlen = pstate->st_buflen;
@@ -125,6 +141,8 @@ void sendto_interrupt(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8
sem_post(&pstate->st_sem);
}
+
+ return flags;
}
#endif
@@ -202,6 +220,7 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
{
FAR struct socket *psock;
#ifdef CONFIG_NET_UDP
+ FAR struct uip_udp_conn *conn;
#ifdef CONFIG_NET_IPv6
FAR const struct sockaddr_in6 *into = (const struct sockaddr_in6 *)to;
#else
@@ -277,7 +296,8 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Setup the UDP socket */
- ret = uip_udpconnect(psock->s_conn, into);
+ conn = (struct uip_udp_conn *)psock->s_conn;
+ ret = uip_udpconnect(conn, into);
if (ret < 0)
{
irqrestore(save);
@@ -287,34 +307,33 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Set up the callback in the connection */
- state.st_cb = uip_udpcallbackalloc((struct uip_udp_conn *)psock->s_conn);
+ state.st_cb = uip_udpcallbackalloc(conn);
if (state.st_cb)
{
state.st_cb->flags = UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
- state.st_cb->flags = 0;
state.st_cb->private = (void*)&state;
state.st_cb->event = sendto_interrupt;
- /* Enable the UDP socket */
+ /* Enable the UDP socket */
- uip_udpenable(psock->s_conn);
+ uip_udpenable(conn);
- /* Notify the device driver of the availabilty of TX data */
+ /* Notify the device driver of the availabilty of TX data */
- netdev_txnotify(&udp_conn->ripaddr);
+ netdev_txnotify(&conn->ripaddr);
- /* 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.
- */
+ /* 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.
+ */
- sem_wait(&state.st_sem);
+ sem_wait(&state.st_sem);
- /* Make sure that no further interrupts are processed */
+ /* Make sure that no further interrupts are processed */
- uip_udpdisable(psock->s_conn);
- uip_udpcallbackfree(psock->s_conn, state.st_cb);
+ uip_udpdisable(conn);
+ uip_udpcallbackfree(conn, state.st_cb);
}
irqrestore(save);
diff --git a/nuttx/net/uip/uip-udpcallback.c b/nuttx/net/uip/uip-udpcallback.c
index 6c7fecef3..a3a254fd2 100644
--- a/nuttx/net/uip/uip-udpcallback.c
+++ b/nuttx/net/uip/uip-udpcallback.c
@@ -80,7 +80,7 @@ void uip_udpcallback(struct uip_driver_s *dev, struct uip_udp_conn *conn,
/* Some sanity checking */
- if (conn && conn->event)
+ if (conn)
{
/* Perform the callback */