summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-05 00:13:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-05 00:13:18 +0000
commite72381a2740de4ba67cefdfe61f351a698e9eecf (patch)
tree2ffaeba932bc1b43ddb1cee9dcea072437d3fd5a /nuttx/net
parent65f8e15b78891b15b1caabe45d1163f63fa530e0 (diff)
downloadpx4-nuttx-e72381a2740de4ba67cefdfe61f351a698e9eecf.tar.gz
px4-nuttx-e72381a2740de4ba67cefdfe61f351a698e9eecf.tar.bz2
px4-nuttx-e72381a2740de4ba67cefdfe61f351a698e9eecf.zip
sendto needs to return EINTR error; dccpc uses sendto
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@330 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/recvfrom.c38
-rw-r--r--nuttx/net/uip/uip.c26
2 files changed, 52 insertions, 12 deletions
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 9632b5ca0..ac1f5f2bb 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -72,6 +72,11 @@ void recvfrom_interrupt(void *private)
struct recvfrom_s *pstate = (struct recvfrom_s *)private;
size_t recvlen;
+ /* If new data is available and we are correctly intialized, then complete
+ * the read action. We could also check for POLL events here in order to
+ * implement SO_RECVTIMEO.
+ */
+
if (uip_newdata() && private)
{
/* Get the length of the data to return */
@@ -88,12 +93,14 @@ void recvfrom_interrupt(void *private)
memcpy(pstate->rf_buffer, uip_appdata, recvlen);
- /* Don't allow any furhter call backs. */
+ /* Don't allow any further call backs. */
uip_conn->private = NULL;
uip_conn->callback = NULL;
- /* Wake up the waiting thread */
+ /* Wake up the waiting thread, returning the number of bytes
+ * actually read.
+ */
pstate->rf_buflen = recvlen;
sem_post(&pstate-> rf_sem);
@@ -202,7 +209,7 @@ ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *
save = irqsave();
memset(&state, 0, sizeof(struct recvfrom_s));
- sem_init(&state. rf_sem, 0, 0);
+ (void)sem_init(&state. rf_sem, 0, 0); /* Doesn't really fail */
state. rf_buflen = len;
state. rf_buffer = buf;
@@ -221,10 +228,31 @@ ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *
udp_conn = (struct uip_udp_conn *)psock->s_conn;
udp_conn->private = (void*)&state;
udp_conn->callback = recvfrom_interrupt;
- irqrestore(save);
- sem_wait(&state. rf_sem);
+ /* 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);
+
+ /* 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 ERROR;
+ }
+
return state.rf_buflen;
#warning "Needs to return server address"
#else
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index a8a149be2..2175ebc05 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -154,7 +154,9 @@ const uip_ipaddr_t uip_netmask =
{HTONS((UIP_NETMASK0 << 8) | UIP_NETMASK1),
HTONS((UIP_NETMASK2 << 8) | UIP_NETMASK3)};
#else
-uip_ipaddr_t uip_hostaddr, uip_draddr, uip_netmask;
+uip_ipaddr_t uip_hostaddr;
+uip_ipaddr_t uip_draddr;
+uip_ipaddr_t uip_netmask;
#endif /* UIP_FIXEDADDR */
#ifndef CONFIG_NET_EXTERNAL_BUFFER
@@ -179,12 +181,13 @@ uint16 uip_flags; /* The uip_flags variable is used for communica
struct uip_conn *uip_conn; /* uip_conn always points to the current connection. */
uint16 uip_listenports[UIP_LISTENPORTS];
- /* The uip_listenports list all currently listning ports. */
+ /* The uip_listenports list all currently listening ports. */
#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_conn;
#endif /* CONFIG_NET_UDP */
/* Temporary variables. */
+
uint8 uip_acc32[4];
#if UIP_STATISTICS == 1
@@ -223,7 +226,9 @@ static uint16 ipid; /* Ths ipid variable is an increasing number th
* used for the IP ID field. */
/* Temporary variables. */
-static uint8 c, opt;
+
+static uint8 c;
+static uint8 opt;
static uint16 tmp16;
/****************************************************************************
@@ -1472,14 +1477,16 @@ tcp_send_synack:
if (uip_flags & UIP_ACKDATA)
{
uip_connr->tcpstateflags = UIP_ESTABLISHED;
- uip_flags = UIP_CONNECTED;
- uip_connr->len = 0;
+ uip_flags = UIP_CONNECTED;
+ uip_connr->len = 0;
+
if (uip_len > 0)
{
- uip_flags |= UIP_NEWDATA;
+ uip_flags |= UIP_NEWDATA;
uip_add_rcv_nxt(uip_len);
}
- uip_slen = 0;
+
+ uip_slen = 0;
uip_tcp_callback();
goto appsend;
}
@@ -1535,6 +1542,7 @@ tcp_send_synack:
}
}
}
+
uip_connr->tcpstateflags = UIP_ESTABLISHED;
uip_connr->rcv_nxt[0] = BUF->seqno[0];
uip_connr->rcv_nxt[1] = BUF->seqno[1];
@@ -1575,12 +1583,15 @@ tcp_send_synack:
{
goto drop;
}
+
uip_add_rcv_nxt(1 + uip_len);
uip_flags |= UIP_CLOSE;
+
if (uip_len > 0)
{
uip_flags |= UIP_NEWDATA;
}
+
uip_tcp_callback();
uip_connr->len = 1;
uip_connr->tcpstateflags = UIP_LAST_ACK;
@@ -1781,6 +1792,7 @@ tcp_send_synack:
{
uip_connr->tcpstateflags = UIP_CLOSING;
}
+
uip_add_rcv_nxt(1);
uip_flags = UIP_CLOSE;
uip_tcp_callback();