summaryrefslogtreecommitdiff
path: root/nuttx/net/recvfrom.c
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net/recvfrom.c')
-rw-r--r--nuttx/net/recvfrom.c353
1 files changed, 223 insertions, 130 deletions
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 149abc10b..579013913 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -81,15 +81,14 @@ struct recvfrom_s
****************************************************************************/
/****************************************************************************
- * Function: recvfrom_interrupt
+ * Function: recvfrom_newdata
*
* Description:
- * This function is called from the interrupt level to perform the actual
- * receive operation via by the uIP layer.
+ * Copy the read data from the packet
*
* Parameters:
* dev The sructure of the network driver that caused the interrupt
- * private An instance of struct recvfrom_s cast to void*
+ * pstate recvfrom state structure
*
* Returned Value:
* None
@@ -99,81 +98,140 @@ struct recvfrom_s
*
****************************************************************************/
-static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
+static void recvfrom_newdata(struct uip_driver_s *dev, struct recvfrom_s *pstate)
{
- struct recvfrom_s *pstate = (struct recvfrom_s *)private;
-#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- FAR struct socket *psock;
-#endif
size_t recvlen;
- vdbg("uip_flags: %02x\n", uip_flags);
-
- /* 'private' might be null in some race conditions (?) */
+ /* Get the length of the data to return */
- if (pstate)
+ if (dev->d_len > pstate->rf_buflen)
{
+ recvlen = pstate->rf_buflen;
+ }
+ else
+ {
+ recvlen = dev->d_len;
+ }
+
+ /* Copy the new appdata into the user buffer */
+
+ memcpy(pstate->rf_buffer, dev->d_appdata, recvlen);
+ vdbg("Received %d bytes (of %d)\n", recvlen, dev->d_len);
+
+ /* Update the accumulated size of the data read */
+
+ pstate->rf_recvlen += recvlen;
+ pstate->rf_buffer += recvlen;
+ pstate->rf_buflen -= recvlen;
+}
+
+/****************************************************************************
+ * Function: recvfrom_timeout
+ *
+ * Description:
+ * Check for recvfrom timeout.
+ *
+ * Parameters:
+ * pstate recvfrom state structure
+ *
+ * Returned Value:
+ * TRUE:timeout FALSE:no timeout
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+static int recvfrom_timeout(struct recvfrom_s *pstate)
+{
+ FAR struct socket *psock = 0;
+ socktimeo_t timeo = 0;
+
+ /* If this is a TCP socket that has already received some data,
+ * than we will always use a short timeout.
+ */
+
+ if (pstate->rf_recvlen > 0)
+ {
+ /* Use the short timeout */
+
+ timeo = TCP_TIMEO;
+ }
+
+ /* No.. check for a timeout configured via setsockopts(SO_RCVTIMEO).
+ * If none... we well let the read hang forever.
+ */
+
+ else
+ {
/* Get the socket reference from the private data */
psock = pstate->rf_sock;
-#endif
+ if (psock)
+ {
+ timeo = psock->s_rcvtimeo;
+ }
+ }
- /* If new data is available, then complete the read action. */
+ /* Is there an effective timeout? */
- if (uip_newdata_event())
- {
- /* Get the length of the data to return */
+ if (timeo)
+ {
+ /* Yes.. Check if the timeout has elapsed */
- if (dev->d_len > pstate->rf_buflen)
- {
- recvlen = pstate->rf_buflen;
- }
- else
- {
- recvlen = dev->d_len;
- }
+ return net_timeo(pstate->rf_starttime, timeo);
+ }
- /* Copy the new appdata into the user buffer */
+ /* No timeout */
- memcpy(pstate->rf_buffer, dev->d_appdata, recvlen);
- vdbg("Received %d bytes (of %d)\n", recvlen, dev->d_len);
+ return FALSE;
+}
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
- /* Update the accumulated size of the data read */
+/****************************************************************************
+ * Function: recvfrom_tcpinterrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * TCP receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
- pstate->rf_recvlen += recvlen;
- pstate->rf_buffer += recvlen;
- pstate->rf_buflen -= recvlen;
+static uint8 recvfrom_tcpinterrupt(struct uip_driver_s *dev,
+ struct uip_conn *conn, uint8 flags)
+{
+ struct recvfrom_s *pstate = (struct recvfrom_s *)conn->data_private;
- /* Are we finished? If this is a UDP socket or if the user
- * buffer has been filled, then we are finished.
- */
+ vdbg("flags: %02x\n", flags);
-#ifdef CONFIG_NET_UDP
- if (psock->s_type == SOCK_DGRAM)
- {
- struct uip_udp_conn *udp_conn;
+ /* 'private' might be null in some race conditions (?) */
- vdbg("UDP resume\n");
+ if (pstate)
+ {
+ /* If new data is available, then complete the read action. */
- /* Don't allow any further UDP call backs. */
+ if (uip_newdata_event(flags))
+ {
+ /* Copy the data from the packet */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = NULL;
- udp_conn->event = NULL;
+ recvfrom_newdata(dev, pstate);
- /* Wake up the waiting thread, returning the number of bytes
- * actually read.
- */
+ /* If the user buffer has been filled, then we are finished. */
- sem_post(&pstate->rf_sem);
- }
- else
-#endif
if (pstate->rf_buflen == 0)
{
- struct uip_conn *conn;
-
vdbg("TCP resume\n");
/* The TCP receive buffer is full. Return now, perhaps truncating
@@ -182,7 +240,6 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
* Don't allow any further TCP call backs.
*/
- conn = (struct uip_conn *)psock->s_conn;
conn->data_private = NULL;
conn->data_event = NULL;
@@ -204,26 +261,14 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
/* Check for a loss of connection */
- else if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ else if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
{
vdbg("error\n");
/* Stop further callbacks */
-#ifdef CONFIG_NET_UDP
- if (psock->s_type == SOCK_DGRAM)
- {
- struct uip_udp_conn *udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = NULL;
- udp_conn->event = NULL;
- }
- else
-#endif
- {
- struct uip_conn *conn = (struct uip_conn *)psock->s_conn;
- conn->data_private = NULL;
- conn->data_event = NULL;
- }
+ conn->data_private = NULL;
+ conn->data_event = NULL;
/* Report not connected */
@@ -239,92 +284,140 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
*/
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
- else
+ else if (recvfrom_timeout(pstate))
{
- socktimeo_t timeo;
-
- /* If this is a TCP socket that has already received some data,
- * than we will always use a short timeout.
+ /* Yes.. the timeout has elapsed... do not allow any further
+ * callbacks
*/
- if (pstate->rf_recvlen > 0)
- {
- /* Use the short timeout */
+ vdbg("TCP timeout\n");
- timeo = TCP_TIMEO;
- }
+ conn->data_private = NULL;
+ conn->data_event = NULL;
- /* No.. check for a timeout configured via setsockopts(SO_RCVTIMEO).
- * If none... we well let the read hang forever.
- */
+ /* Report an error only if no data has been received */
- else
+ if (pstate->rf_recvlen == 0)
{
- timeo = psock->s_rcvtimeo;
+ /* Report the timeout error */
+
+ pstate->rf_result = -EAGAIN;
}
- /* Is there an effective timeout? */
+ /* Wake up the waiting thread, returning either the error -EAGAIN
+ * that signals the timeout event or the data received up to
+ * the point tht the timeout occured (no error).
+ */
- if (timeo)
- {
- /* Yes.. Check if the timeout has elapsed */
+ sem_post(&pstate->rf_sem);
+ }
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+ }
+ return 0;
+}
- if (net_timeo(pstate->rf_starttime, timeo))
- {
- /* Yes.. the timeout has elapsed... do not allow any further
- * callbacks
- */
+/****************************************************************************
+ * Function: recvfrom_udpinterrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * UDP receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * conn The connection structure associated with the socket
+ * flags Set of events describing why the callback was invoked
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
#ifdef CONFIG_NET_UDP
- if (psock->s_type == SOCK_DGRAM)
- {
- struct uip_udp_conn *udp_conn;
+static void recvfrom_udpinterrupt(struct uip_driver_s *dev,
+ struct uip_udp_conn *conn, uint8 flags)
+{
+ struct recvfrom_s *pstate = (struct recvfrom_s *)conn->private;
- vdbg("UDP timeout\n");
+ vdbg("flags: %02x\n", flags);
- /* Stop further callbacks */
+ /* 'private' might be null in some race conditions (?) */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = NULL;
- udp_conn->event = NULL;
+ if (pstate)
+ {
+ /* If new data is available, then complete the read action. */
- /* Report a timeout error */
+ if (uip_newdata_event(flags))
+ {
+ /* Copy the data from the packet */
- pstate->rf_result = -EAGAIN;
- }
- else
-#endif
- {
- struct uip_conn *conn;
+ recvfrom_newdata(dev, pstate);
+
+ /* We are finished. */
- vdbg("TCP timeout\n");
+ vdbg("UDP resume\n");
- conn = (struct uip_conn *)psock->s_conn;
- conn->data_private = NULL;
- conn->data_event = NULL;
+ /* Don't allow any further UDP call backs. */
- /* Report an error only if no data has been received */
+ conn->private = NULL;
+ conn->event = NULL;
- if (pstate->rf_recvlen == 0)
- {
- /* Report the timeout error */
+ /* Wake up the waiting thread, returning the number of bytes
+ * actually read.
+ */
- pstate->rf_result = -EAGAIN;
- }
- }
+ sem_post(&pstate->rf_sem);
+ }
- /* Wake up the waiting thread, returning either the error -EAGAIN
- * that signals the timeout event or the data received up to
- * the point tht the timeout occured (no error).
- */
+ /* Check for a loss of connection */
- sem_post(&pstate->rf_sem);
- }
- }
+ else if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ vdbg("error\n");
+
+ /* Stop further callbacks */
+
+ conn->private = NULL;
+ conn->event = NULL;
+
+ /* Report not connected */
+
+ pstate->rf_result = -ENOTCONN;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->rf_sem);
}
-#endif
+
+ /* No data has been received -- this is some other event... probably a
+ * poll -- check for a timeout.
+ */
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+ else if (recvfrom_timeout(pstate))
+ {
+ /* Yes.. the timeout has elapsed... do not allow any further
+ * callbacks
+ */
+
+ vdbg("UDP timeout\n");
+
+ /* Stop further callbacks */
+
+ conn->private = NULL;
+ conn->event = NULL;
+
+ /* Report a timeout error */
+
+ pstate->rf_result = -EAGAIN;
+ }
+#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
}
}
+#endif
/****************************************************************************
* Function: recvfrom_init
@@ -468,7 +561,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
udp_conn = (struct uip_udp_conn *)psock->s_conn;
udp_conn->private = (void*)&state;
- udp_conn->event = recvfrom_interrupt;
+ udp_conn->event = recvfrom_udpinterrupt;
/* Enable the UDP socket */
@@ -549,7 +642,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
conn = (struct uip_conn *)psock->s_conn;
conn->data_private = (void*)&state;
- conn->data_event = recvfrom_interrupt;
+ conn->data_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)