summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-22 14:42:52 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-22 14:42:52 +0000
commit7d4b2f6253d8ac898def6839b2ccc2ae61e24135 (patch)
tree36587b181e76fc8790f7472f64316c9bb620a31e /nuttx/net
parent2ad451b8005afc667718569077c816195f8bd9ec (diff)
downloadpx4-nuttx-7d4b2f6253d8ac898def6839b2ccc2ae61e24135.tar.gz
px4-nuttx-7d4b2f6253d8ac898def6839b2ccc2ae61e24135.tar.bz2
px4-nuttx-7d4b2f6253d8ac898def6839b2ccc2ae61e24135.zip
Add TX data notification
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@397 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile3
-rw-r--r--nuttx/net/net-internal.h17
-rw-r--r--nuttx/net/netdev-findbyaddr.c128
-rw-r--r--nuttx/net/netdev-findbyname.c (renamed from nuttx/net/netdev-find.c)9
-rw-r--r--nuttx/net/netdev-ioctl.c2
-rw-r--r--nuttx/net/netdev-txnotify.c106
-rw-r--r--nuttx/net/send.c24
-rw-r--r--nuttx/net/sendto.c4
-rw-r--r--nuttx/net/uip/uip-initialize.c17
-rw-r--r--nuttx/net/uip/uip-input.c4
-rw-r--r--nuttx/net/uip/uip-internal.h4
-rw-r--r--nuttx/net/uip/uip-tcpconn.c3
-rw-r--r--nuttx/net/uip/uip-tcpinput.c26
-rw-r--r--nuttx/net/uip/uip-udpconn.c6
14 files changed, 306 insertions, 47 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index cf6f35081..e429d6236 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -51,7 +51,8 @@ endif
endif
NETDEV_ASRCS =
-NETDEV_CSRCS = netdev-register.c netdev-ioctl.c netdev-find.c netdev-count.c
+NETDEV_CSRCS = netdev-register.c netdev-ioctl.c netdev-txnotify.c \
+ netdev-findbyname.c netdev-findbyaddr.c netdev-count.c
include uip/Make.defs
endif
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index 2354e54c1..1b57162a6 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -45,6 +45,7 @@
#include <time.h>
#include <nuttx/net.h>
+#include <net/uip/uip.h>
#include "net-internal.h"
@@ -164,10 +165,22 @@ EXTERN void netdev_semtake(void);
# define netdev_semgive() sem_post(&g_netdev_sem)
#endif
-/* net-find.c ****************************************************************/
+/* net-findbyname.c **********************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
-EXTERN FAR struct uip_driver_s *netdev_find(const char *ifname);
+EXTERN FAR struct uip_driver_s *netdev_findbyname(const char *ifname);
+#endif
+
+/* net-findbyaddr.c **********************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN FAR struct uip_driver_s *netdev_findbyaddr(uip_ipaddr_t *raddr);
+#endif
+
+/* net-txnotify.c ************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN void netdev_txnotify(uip_ipaddr_t *raddr);
#endif
/* net-count.c ***************************************************************/
diff --git a/nuttx/net/netdev-findbyaddr.c b/nuttx/net/netdev-findbyaddr.c
new file mode 100644
index 000000000..c751960bf
--- /dev/null
+++ b/nuttx/net/netdev-findbyaddr.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ * net/netdev-findbyaddr.c
+ *
+ * Copyright (C) 2007 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) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/uip/uip-arch.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_maskcmp
+ ****************************************************************************/
+
+static inline boolean netdev_maskcmp(uip_ipaddr_t *ipaddr, uip_ipaddr_t *raddr,
+ uip_ipaddr_t *netmask)
+{
+#ifndef CONFIG_NET_IPv6
+ return (*ipaddr & *netmask) == (*raddr & *netmask);
+#else
+# warning "Not implemented for IPv6"
+#endif
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_findbyaddr
+ *
+ * Description:
+ * Find a previously registered network device by matching a remote address
+ * with the subnet served by the device
+ *
+ * Parameters:
+ * raddr - Pointer to the remote address of a connection
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+FAR struct uip_driver_s *netdev_findbyaddr(uip_ipaddr_t *raddr)
+{
+ struct uip_driver_s *dev;
+
+ if (raddr)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (netdev_maskcmp(&dev->d_ipaddr, raddr, &dev->d_netmask))
+ {
+ netdev_semgive();
+ return dev;
+ }
+ }
+ netdev_semgive();
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev-find.c b/nuttx/net/netdev-findbyname.c
index a975569d2..6c3d59ae3 100644
--- a/nuttx/net/netdev-find.c
+++ b/nuttx/net/netdev-findbyname.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * net/netdev-find.c
+ * net/netdev-findbyname.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -73,10 +73,11 @@
****************************************************************************/
/****************************************************************************
- * Function: netdev_find
+ * Function: netdev_findbyname
*
* Description:
- * Find a previously registered network device
+ * Find a previously registered network device using its assigned
+ * network interface name
*
* Parameters:
* ifname The interface name of the device of interest
@@ -89,7 +90,7 @@
*
****************************************************************************/
-FAR struct uip_driver_s *netdev_find(const char *ifname)
+FAR struct uip_driver_s *netdev_findbyname(const char *ifname)
{
struct uip_driver_s *dev;
if (ifname)
diff --git a/nuttx/net/netdev-ioctl.c b/nuttx/net/netdev-ioctl.c
index e13a22170..9adc2ae0a 100644
--- a/nuttx/net/netdev-ioctl.c
+++ b/nuttx/net/netdev-ioctl.c
@@ -177,7 +177,7 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
* in the request data.
*/
- dev = netdev_find(req->ifr_name);
+ dev = netdev_findbyname(req->ifr_name);
if (!dev)
{
err = EINVAL;
diff --git a/nuttx/net/netdev-txnotify.c b/nuttx/net/netdev-txnotify.c
new file mode 100644
index 000000000..91a225eff
--- /dev/null
+++ b/nuttx/net/netdev-txnotify.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * net/netdev-txnotify.c
+ *
+ * Copyright (C) 2007 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) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/uip/uip-arch.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_txnotify
+ *
+ * Description:
+ * Notify the device driver that new TX data is available.
+ *
+ * Parameters:
+ * raddr - Pointer to the remote address to send the data
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+void netdev_txnotify(uip_ipaddr_t *raddr)
+{
+ /* Find the device driver that serves the subnet of the remote address */
+
+ struct uip_driver_s *dev = netdev_findbyaddr(raddr);
+ if (dev && dev->d_txavail)
+ {
+ /* Notify the device driver that new TX data is available. */
+
+ (void)dev->d_txavail(dev);
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index c758b8eba..29633b380 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -304,19 +304,23 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
conn->data_private = (void*)&state;
conn->data_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 */
- ret = sem_wait(&state. snd_sem);
+ netdev_txnotify(&conn->ripaddr);
- /* Make sure that no further interrupts are processed */
+ /* 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.
+ */
- conn->data_private = NULL;
- conn->data_event = NULL;
- }
+ ret = sem_wait(&state. snd_sem);
+
+ /* Make sure that no further interrupts are processed */
+
+ conn->data_private = NULL;
+ conn->data_event = NULL;
+ }
sem_destroy(&state. snd_sem);
irqrestore(save);
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index d18ea8e3d..bbcf65b80 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -283,6 +283,10 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
uip_udpenable(psock->s_conn);
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&udp_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
diff --git a/nuttx/net/uip/uip-initialize.c b/nuttx/net/uip/uip-initialize.c
index 2e00c5d9c..a3338d082 100644
--- a/nuttx/net/uip/uip-initialize.c
+++ b/nuttx/net/uip/uip-initialize.c
@@ -56,10 +56,7 @@
* Public Variables
****************************************************************************/
-#if UIP_URGDATA > 0
-void *uip_urgdata; /* urgent data (out-of-band data), if present. */
-uint16 uip_urglen; /* Length of (received) urgent data */
-#endif
+/* IP/TCP/UDP/ICMP statistics for all network interfaces */
#ifdef CONFIG_NET_STATISTICS
struct uip_stats uip_stat;
@@ -69,16 +66,16 @@ struct uip_stats uip_stat;
uint16 g_ipid;
-const uip_ipaddr_t all_ones_addr =
+const uip_ipaddr_t g_alloneaddr =
#ifdef CONFIG_NET_IPv6
- {0xffff,0xffff,0xffff,0xffff,0xffff,0xffff,0xffff,0xffff};
-#else /* CONFIG_NET_IPv6 */
+ {0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff};
+#else
{0xffffffff};
-#endif /* CONFIG_NET_IPv6 */
+#endif
-const uip_ipaddr_t all_zeroes_addr =
+const uip_ipaddr_t g_allzeroaddr =
#ifdef CONFIG_NET_IPv6
- {0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000};
+ {0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000};
#else
{0x00000000};
#endif
diff --git a/nuttx/net/uip/uip-input.c b/nuttx/net/uip/uip-input.c
index 71f9b8b9a..b8d8ebb7e 100644
--- a/nuttx/net/uip/uip-input.c
+++ b/nuttx/net/uip/uip-input.c
@@ -385,7 +385,7 @@ void uip_input(struct uip_driver_s *dev)
}
#endif /* CONFIG_NET_IPv6 */
- if (uip_ipaddr_cmp(dev->d_ipaddr, all_zeroes_addr))
+ if (uip_ipaddr_cmp(dev->d_ipaddr, g_allzeroaddr))
{
/* If we are configured to use ping IP address configuration and
* hasn't been assigned an IP address yet, we accept all ICMP
@@ -413,7 +413,7 @@ void uip_input(struct uip_driver_s *dev)
*/
#ifdef CONFIG_NET_BROADCAST
- if (BUF->proto == UIP_PROTO_UDP && uip_ipaddr_cmp(BUF->destipaddr, all_ones_addr)
+ if (BUF->proto == UIP_PROTO_UDP && uip_ipaddr_cmp(BUF->destipaddr, g_alloneaddr)
{
uip_udpinput(dev);
return;
diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h
index c358d431f..ccc1c86bd 100644
--- a/nuttx/net/uip/uip-internal.h
+++ b/nuttx/net/uip/uip-internal.h
@@ -94,8 +94,8 @@
* Public Data
****************************************************************************/
-extern const uip_ipaddr_t all_ones_addr;
-extern const uip_ipaddr_t all_zeroes_addr;
+extern const uip_ipaddr_t g_alloneaddr;
+extern const uip_ipaddr_t g_allzeroaddr;
/* Increasing number used for the IP ID field. */
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 96849d926..eb84d8f31 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -545,11 +545,14 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
*/
conn->lport = addr->sin_port;
+
+#if 0 /* Not used */
#ifdef CONFIG_NET_IPv6
uip_ipaddr_copy(conn->lipaddr, addr->sin6_addr.in6_u.u6_addr16);
#else
uip_ipaddr_copy(conn->lipaddr, addr->sin_addr.s_addr);
#endif
+#endif
return OK;
}
diff --git a/nuttx/net/uip/uip-tcpinput.c b/nuttx/net/uip/uip-tcpinput.c
index 1a74d5f81..ba11fcb81 100644
--- a/nuttx/net/uip/uip-tcpinput.c
+++ b/nuttx/net/uip/uip-tcpinput.c
@@ -547,32 +547,34 @@ found:
}
/* Check the URG flag. If this is set, the segment carries urgent
- data that we must pass to the application. */
+ * data that we must pass to the application.
+ */
+
if ((BUF->flags & TCP_URG) != 0)
{
-#if UIP_URGDATA > 0
- uip_urglen = (BUF->urgp[0] << 8) | BUF->urgp[1];
- if (uip_urglen > dev->d_len)
+#ifdef CONFIG_NET_TCPURGDATA
+ dev->d_urglen = (BUF->urgp[0] << 8) | BUF->urgp[1];
+ if (dev->d_urglen > dev->d_len)
{
/* There is more urgent data in the next segment to come. */
- uip_urglen = dev->d_len;
+ dev->d_urglen = dev->d_len;
}
- uip_incr32(conn->rcv_nxt, uip_urglen);
- dev->d_len -= uip_urglen;
- uip_urgdata = dev->d_appdata;
- dev->d_appdata += uip_urglen;
+ uip_incr32(conn->rcv_nxt, dev->d_urglen);
+ dev->d_len -= dev->d_urglen;
+ dev->d_urgdata = dev->d_appdata;
+ dev->d_appdata += dev->d_urglen;
}
else
{
- uip_urglen = 0;
-#else /* UIP_URGDATA > 0 */
+ dev->d_urglen = 0;
+#else /* CONFIG_NET_TCPURGDATA */
dev->d_appdata =
((uint8*)dev->d_appdata) + ((BUF->urgp[0] << 8) | BUF->urgp[1]);
dev->d_len -=
(BUF->urgp[0] << 8) | BUF->urgp[1];
-#endif /* UIP_URGDATA > 0 */
+#endif /* CONFIG_NET_TCPURGDATA */
}
/* If d_len > 0 we have TCP data in the packet, and we flag this
diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c
index b904aaac5..e8116d71a 100644
--- a/nuttx/net/uip/uip-udpconn.c
+++ b/nuttx/net/uip/uip-udpconn.c
@@ -247,8 +247,8 @@ struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf)
if (conn->lport != 0 && buf->destport == conn->lport &&
(conn->rport == 0 || buf->srcport == conn->rport) &&
- (uip_ipaddr_cmp(conn->ripaddr, all_zeroes_addr) ||
- uip_ipaddr_cmp(conn->ripaddr, all_ones_addr) ||
+ (uip_ipaddr_cmp(conn->ripaddr, g_allzeroaddr) ||
+ uip_ipaddr_cmp(conn->ripaddr, g_alloneaddr) ||
uiphdr_ipaddr_cmp(buf->srcipaddr, &conn->ripaddr)))
{
/* Matching connection found.. return a reference to it */
@@ -385,7 +385,7 @@ int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
else
{
conn->rport = 0;
- uip_ipaddr_copy(conn->ripaddr, all_zeroes_addr);
+ uip_ipaddr_copy(conn->ripaddr, g_allzeroaddr);
}
conn->ttl = UIP_TTL;