summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-15 15:55:52 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-15 15:55:52 -0600
commit363051f66bbd5a817e2f644cc2a5c11579f7a2f3 (patch)
tree615ec2f981bd39dca91f1be0453d9605dad41769
parent425b313cb3bc53c5cc49f98ad8236ea6675ad9df (diff)
downloadpx4-nuttx-363051f66bbd5a817e2f644cc2a5c11579f7a2f3.tar.gz
px4-nuttx-363051f66bbd5a817e2f644cc2a5c11579f7a2f3.tar.bz2
px4-nuttx-363051f66bbd5a817e2f644cc2a5c11579f7a2f3.zip
Clean a few more IPv6 compilation issues; Add implementation of net_ipv6_maskcmp()
-rw-r--r--nuttx/include/nuttx/net/ip.h11
-rw-r--r--nuttx/include/nuttx/net/tcp.h2
-rw-r--r--nuttx/include/nuttx/net/udp.h2
-rw-r--r--nuttx/net/devif/ipv6_input.c2
-rw-r--r--nuttx/net/tcp/tcp_poll.c10
-rw-r--r--nuttx/net/udp/udp_poll.c10
-rw-r--r--nuttx/net/utils/Make.defs8
-rw-r--r--nuttx/net/utils/net_ipv6_maskcmp.c111
8 files changed, 146 insertions, 10 deletions
diff --git a/nuttx/include/nuttx/net/ip.h b/nuttx/include/nuttx/net/ip.h
index eb28fa1c7..5e573f2d6 100644
--- a/nuttx/include/nuttx/net/ip.h
+++ b/nuttx/include/nuttx/net/ip.h
@@ -279,9 +279,9 @@ struct net_ipv6hdr_s
*
* Example:
*
- * net_ipaddr_t ipaddr1;
- * net_ipaddr_t ipaddr2;
- * net_ipaddr_t mask;
+ * in_addr_t ipaddr1;
+ * in_addr_t ipaddr2;
+ * in_addr_t mask;
*
* net_ipaddr(&mask, 255,255,255,0);
* net_ipaddr(&ipaddr1, 192,16,1,2);
@@ -304,8 +304,9 @@ struct net_ipv6hdr_s
# define net_ipaddr_maskcmp(a,b,m) net_ipv4addr_maskcmp(a,b,m)
#else
-bool net_ipv6addr_maskcmp(net_ipaddr_t addr1, net_ipaddr_t addr2,
- net_ipaddr_t mask);
+bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1,
+ const net_ipv6addr_t addr2,
+ const net_ipv6addr_t mask);
# define net_ipaddr_maskcmp(a,b,m) net_ipv6addr_maskcmp(a,b,m)
#endif
diff --git a/nuttx/include/nuttx/net/tcp.h b/nuttx/include/nuttx/net/tcp.h
index db5ef37da..8a33f81cd 100644
--- a/nuttx/include/nuttx/net/tcp.h
+++ b/nuttx/include/nuttx/net/tcp.h
@@ -103,7 +103,7 @@
# define IPv4TCP_HDRLEN (TCP_HDRLEN + IPv4_HDRLEN) /* Size of IPv4 + TCP header */
#endif
-#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
# define IPv6TCP_HDRLEN (TCP_HDRLEN + IPv6_HDRLEN) /* Size of IPv4 + TCP header */
#endif
diff --git a/nuttx/include/nuttx/net/udp.h b/nuttx/include/nuttx/net/udp.h
index b8c1c9b0e..4b2d305d6 100644
--- a/nuttx/include/nuttx/net/udp.h
+++ b/nuttx/include/nuttx/net/udp.h
@@ -69,7 +69,7 @@
#endif
#ifdef CONFIG_NET_IPv6
-# define IPv6UDP_HDRLEN (UDP_HDRLEN + IPv4_HDRLEN) /* Size of IPv6 + UDP headers */
+# define IPv6UDP_HDRLEN (UDP_HDRLEN + IPv6_HDRLEN) /* Size of IPv6 + UDP headers */
#endif
/****************************************************************************
diff --git a/nuttx/net/devif/ipv6_input.c b/nuttx/net/devif/ipv6_input.c
index 9f95efffa..f98ef48a9 100644
--- a/nuttx/net/devif/ipv6_input.c
+++ b/nuttx/net/devif/ipv6_input.c
@@ -198,7 +198,7 @@ int ipv6_input(FAR struct net_driver_s *dev)
if (pbuf->proto == IP_PROTO_UDP &&
net_ipv6addr_cmp(pbuf->destipaddr, g_alloneaddr))
{
- return udp_input(dev);
+ return udp_ipv6_input(dev);
}
/* In most other cases, the device must be assigned a non-zero IP
diff --git a/nuttx/net/tcp/tcp_poll.c b/nuttx/net/tcp/tcp_poll.c
index 2d05e452c..0f6175638 100644
--- a/nuttx/net/tcp/tcp_poll.c
+++ b/nuttx/net/tcp/tcp_poll.c
@@ -101,10 +101,18 @@ void tcp_poll(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn)
if ((conn->tcpstateflags & TCP_STATE_MASK) == TCP_ESTABLISHED)
{
- /* Set up for the callback */
+ /* Set up for the callback. We can't know in advance if the application
+ * is going to send a IPv4 or an IPv6 packet, so this setup may not
+ * actually be used.
+ */
+#if defined(CONFIG_NET_IPv4)
dev->d_snddata = &dev->d_buf[IPv4TCP_HDRLEN + NET_LL_HDRLEN(dev)];
dev->d_appdata = &dev->d_buf[IPv4TCP_HDRLEN + NET_LL_HDRLEN(dev)];
+#else /* if defined(CONFIG_NET_IPv6) */
+ dev->d_snddata = &dev->d_buf[IPv6TCP_HDRLEN + NET_LL_HDRLEN(dev)];
+ dev->d_appdata = &dev->d_buf[IPv6TCP_HDRLEN + NET_LL_HDRLEN(dev)];
+#endif
dev->d_len = 0;
dev->d_sndlen = 0;
diff --git a/nuttx/net/udp/udp_poll.c b/nuttx/net/udp/udp_poll.c
index d19f72a76..43ea3e8cc 100644
--- a/nuttx/net/udp/udp_poll.c
+++ b/nuttx/net/udp/udp_poll.c
@@ -98,10 +98,18 @@ void udp_poll(FAR struct net_driver_s *dev, FAR struct udp_conn_s *conn)
if (conn->lport != 0)
{
- /* Set-up for the application callback */
+ /* Set up for the callback. We can't know in advance if the application
+ * is going to send a IPv4 or an IPv6 packet, so this setup may not
+ * actually be used.
+ */
+#if defined(CONFIG_NET_IPv4)
dev->d_appdata = &dev->d_buf[NET_LL_HDRLEN(dev) + IPv4UDP_HDRLEN];
dev->d_snddata = &dev->d_buf[NET_LL_HDRLEN(dev) + IPv4UDP_HDRLEN];
+#else /* if defined(CONFIG_NET_IPv6) */
+ dev->d_appdata = &dev->d_buf[NET_LL_HDRLEN(dev) + IPv6UDP_HDRLEN];
+ dev->d_snddata = &dev->d_buf[NET_LL_HDRLEN(dev) + IPv6UDP_HDRLEN];
+#endif
dev->d_len = 0;
dev->d_sndlen = 0;
diff --git a/nuttx/net/utils/Make.defs b/nuttx/net/utils/Make.defs
index c8bf78e6b..39d2bbf21 100644
--- a/nuttx/net/utils/Make.defs
+++ b/nuttx/net/utils/Make.defs
@@ -33,9 +33,17 @@
#
############################################################################
+# Common utilities
+
NET_CSRCS += net_dsec2tick.c net_dsec2timeval.c net_timeval2dsec.c
NET_CSRCS += net_chksum.c
+# IPv6 utilities
+
+ifeq ($(CONFIG_NET_IPv6),y)
+NET_CSRCS += net_ipv6_maskcmp.c
+endif
+
# Non-interrupt level support required?
ifeq ($(CONFIG_NET_NOINTS),y)
diff --git a/nuttx/net/utils/net_ipv6_maskcmp.c b/nuttx/net/utils/net_ipv6_maskcmp.c
new file mode 100644
index 000000000..897f56dcf
--- /dev/null
+++ b/nuttx/net/utils/net_ipv6_maskcmp.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ * net/utils/net_ipv6_maskcmp.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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>
+
+#include <nuttx/clock.h>
+#include <nuttx/net/ip.h>
+
+#include "utils/utils.h"
+
+#ifdef CONFIG_NET_IPv6
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_timeval2dsec
+ *
+ * Description:
+ * Compare two IP addresses under a netmask. The mask is used to mask
+ * out the bits that are to be compared: Buts within the mask much
+ * match exactly; bits outside if the mask are ignored.
+ *
+ * Example:
+ *
+ * net_ipv6addr_t ipaddr1;
+ * net_ipv6addr_t ipaddr2;
+ * net_ipv6addr_t mask;
+ *
+ * net_ipv6addr(&mask, 255,255,255,0);
+ * net_ipv6addr(&ipaddr1, 192,16,1,2);
+ * net_iv6paddr(&ipaddr2, 192,16,1,3);
+ * if (net_ipv6addr_maskcmp(ipaddr1, ipaddr2, &mask))
+ * {
+ * printf("They are the same");
+ * }
+ *
+ * Parameters:
+ * addr1 - The first IP address.
+ * addr2 - The second IP address.
+ * mask - The netmask.
+ *
+ * Returned Value:
+ * True if the address under the mask are equal
+ *
+ ****************************************************************************/
+
+bool net_ipv6addr_maskcmp(const net_ipv6addr_t addr1,
+ const net_ipv6addr_t addr2,
+ const net_ipv6addr_t mask)
+{
+ int i;
+
+ /* Start from the "bottom" where the addresses will most likely differ */
+
+ for (i = 7; i >= 0; i--)
+ {
+ /* Same? */
+
+ if ((addr1[i] & mask[i]) != (addr2[i] & mask[i]))
+ {
+ /* No.. the addresses are different */
+
+ return false;
+ }
+ }
+
+ /* The addresses are the same */
+
+ return true;
+}
+
+#endif /* CONFIG_NET_IPv6 */
+