summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-02-02 10:49:50 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-02-02 10:49:50 -0600
commit8c9f78485dbed47c7b82dd3ee1e6ed91c86708bf (patch)
tree3506c3afc2d1f9c496288daec884e1f24afd0b61
parent4c66b1b62effabcb8409c4f6a51397b76943516c (diff)
downloadpx4-nuttx-8c9f78485dbed47c7b82dd3ee1e6ed91c86708bf.tar.gz
px4-nuttx-8c9f78485dbed47c7b82dd3ee1e6ed91c86708bf.tar.bz2
px4-nuttx-8c9f78485dbed47c7b82dd3ee1e6ed91c86708bf.zip
IPv6: Remove an unusd file (kruft from original IPv6 develoment); Add inital hooks to support automatic Neighbor Solitication
-rw-r--r--nuttx/net/arp/arp.h8
-rw-r--r--nuttx/net/devif/devif.h6
-rw-r--r--nuttx/net/devif/devif_poll.c6
-rw-r--r--nuttx/net/icmpv6/Kconfig9
-rw-r--r--nuttx/net/icmpv6/Make.defs14
-rw-r--r--nuttx/net/icmpv6/icmpv6.h44
-rw-r--r--nuttx/net/icmpv6/icmpv6_input.c33
-rw-r--r--nuttx/net/icmpv6/icmpv6_ping.c5
-rw-r--r--nuttx/net/icmpv6/icmpv6_poll.c4
-rw-r--r--nuttx/net/icmpv6/icmpv6_send.c145
10 files changed, 89 insertions, 185 deletions
diff --git a/nuttx/net/arp/arp.h b/nuttx/net/arp/arp.h
index 941e1fc96..f731f1cde 100644
--- a/nuttx/net/arp/arp.h
+++ b/nuttx/net/arp/arp.h
@@ -247,11 +247,11 @@ void arp_format(FAR struct net_driver_s *dev, in_addr_t ipaddr);
* Function: arp_send
*
* Description:
- * The arp_send() call may be to send an ARP request to resolve an IP
- * address. This function first checks if the IP address is already in
- * ARP table. If so, then it returns success immediately.
+ * The arp_send() call may be to send an ARP request to resolve an IPv4
+ * address. This function first checks if the IPv4 address is already in
+ * the ARP table. If so, then it returns success immediately.
*
- * If the requested IP address in not in the ARP table, then this function
+ * If the requested IPv4 address in not in the ARP table, then this function
* will send an ARP request, delay, then check if the IP address is now in
* the ARP table. It will repeat this sequence until either (1) the IP
* address mapping is now in the ARP table, or (2) a configurable number
diff --git a/nuttx/net/devif/devif.h b/nuttx/net/devif/devif.h
index ca40f1336..75885b1c5 100644
--- a/nuttx/net/devif/devif.h
+++ b/nuttx/net/devif/devif.h
@@ -113,6 +113,11 @@
* OUT: Cleared (only) by the socket layer logic to indicate
* that the reply was processed, suppressing further
* attempts to process the reply.
+ *
+ * ICMPv6_ADVERTISE IN: An ICMPv6 Neighbor Advertisement has been received.
+ * Used to support ICMPv6 Neighbor Discovery Protocol.
+ * OUT: Cleared (only) by the socket layer logic to indicate
+ * that the reply was processed.
*/
#define TCP_ACKDATA (1 << 0)
@@ -135,6 +140,7 @@
#define TCP_TIMEDOUT (1 << 9)
#define ICMP_ECHOREPLY (1 << 10)
#define ICMPv6_ECHOREPLY ICMP_ECHOREPLY
+#define ICMPv6_ADVERTISE (1 << 11)
#define TCP_CONN_EVENTS (TCP_CLOSE | TCP_ABORT | TCP_CONNECTED | TCP_TIMEDOUT)
diff --git a/nuttx/net/devif/devif_poll.c b/nuttx/net/devif/devif_poll.c
index c942ea266..35c419914 100644
--- a/nuttx/net/devif/devif_poll.c
+++ b/nuttx/net/devif/devif_poll.c
@@ -129,7 +129,7 @@ static inline int devif_poll_icmp(FAR struct net_driver_s *dev,
*
****************************************************************************/
-#if defined(CONFIG_NET_ICMPv6) && defined(CONFIG_NET_ICMPv6_PING)
+#if defined(CONFIG_NET_ICMPv6_PING) || defined(CONFIG_NET_NET_ICMPv6_NEIGHBOR)
static inline int devif_poll_icmpv6(FAR struct net_driver_s *dev,
devif_poll_callback_t callback)
{
@@ -141,7 +141,7 @@ static inline int devif_poll_icmpv6(FAR struct net_driver_s *dev,
return callback(dev);
}
-#endif /* CONFIG_NET_ICMPv6 && CONFIG_NET_ICMPv6_PING */
+#endif /* CONFIG_NET_ICMPv6_PING || CONFIG_NET_NET_ICMPv6_NEIGHBOR*/
/****************************************************************************
* Function: devif_poll_igmp
@@ -374,7 +374,7 @@ int devif_poll(FAR struct net_driver_s *dev, devif_poll_callback_t callback)
if (!bstop)
#endif
-#if defined(CONFIG_NET_ICMPv6) && defined(CONFIG_NET_ICMPv6_PING)
+#if defined(CONFIG_NET_ICMPv6_PING) || defined(CONFIG_NET_NET_ICMPv6_NEIGHBOR)
{
/* Traverse all of the tasks waiting to send an ICMPv6 ECHO request. */
diff --git a/nuttx/net/icmpv6/Kconfig b/nuttx/net/icmpv6/Kconfig
index 89c03c36c..1a6120ac1 100644
--- a/nuttx/net/icmpv6/Kconfig
+++ b/nuttx/net/icmpv6/Kconfig
@@ -23,6 +23,15 @@ config NET_ICMPv6_PING
Provide interfaces to support application level support for
for sending ECHO (ping) requests and associating ECHO replies.
+config NET_ICMPv6_NEIGHBOR
+ bool "Solicit destination addresses"
+ default n
+ depends on EXPERIMENTAL
+ ---help---
+ Enable logic to send ICMPv6 neighbor solicitation requests if
+ the target IPv6 address mapping does not appear in the Neighbor
+ table.
+
endif # NET_ICMPv6
endmenu # ICMPv6 Networking Support
endif # NET_IPv6
diff --git a/nuttx/net/icmpv6/Make.defs b/nuttx/net/icmpv6/Make.defs
index e25d5706a..0a4e20c3d 100644
--- a/nuttx/net/icmpv6/Make.defs
+++ b/nuttx/net/icmpv6/Make.defs
@@ -40,7 +40,19 @@ ifeq ($(CONFIG_NET_ICMPv6),y)
NET_CSRCS += icmpv6_input.c icmpv6_solicit.c
ifeq ($(CONFIG_NET_ICMPv6_PING),y)
-NET_CSRCS += icmpv6_ping.c icmpv6_poll.c icmpv6_send.c
+NET_CSRCS += icmpv6_ping.c
+endif
+
+ifeq ($(CONFIG_NET_NET_ICMPv6_NEIGHBOR),y)
+NET_CSRCS += icmpv6_neighbor.c
+endif
+
+ifeq ($(CONFIG_NET_ICMPv6_PING),y)
+NET_CSRCS += icmpv6_poll.c
+else
+ifeq ($(CONFIG_NET_NET_ICMPv6_NEIGHBOR),y)
+NET_CSRCS += icmpv6_poll.c
+endif
endif
# Include ICMPv6 build support
diff --git a/nuttx/net/icmpv6/icmpv6.h b/nuttx/net/icmpv6/icmpv6.h
index 082374023..a96263ce3 100644
--- a/nuttx/net/icmpv6/icmpv6.h
+++ b/nuttx/net/icmpv6/icmpv6.h
@@ -93,31 +93,47 @@ extern "C"
void icmpv6_input(FAR struct net_driver_s *dev);
/****************************************************************************
- * Name: icmpv6_poll
+ * Name: icmpv6_neighbor
*
* Description:
- * Poll a UDP "connection" structure for availability of TX data
+ * The icmpv6_solicit() call may be to send an ICMPv6 Neighbor
+ * Solicitation to resolve an IPv6 address. This function first checks if
+ * the IPv6 address is already in the Neighbor Table. If so, then it
+ * returns success immediately.
+ *
+ * If the requested IPv6 address in not in the Neighbor Table, then this
+ * function will send the Neighbor Solicitation, delay, then check if the
+ * IP address is now in the Neighbor able. It will repeat this sequence
+ * until either (1) the IPv6 address mapping is now in the Neibhbor table,
+ * or (2) a configurable number of timeouts occur without receiving the
+ * ICMPv6 Neighbor Advertisement.
*
* Parameters:
- * dev - The device driver structure to use in the send operation
+ * ipaddr The IPv6 address to be queried.
*
- * Return:
- * None
+ * Returned Value:
+ * Zero (OK) is returned on success and the IP address mapping can now be
+ * found in the ARP table. On error a negated errno value is returned:
+ *
+ * -ETIMEDOUT: The number or retry counts has been exceed.
+ * -EHOSTUNREACH: Could not find a route to the host
*
* Assumptions:
- * Called from the interrupt level or with interrupts disabled.
+ * This function is called from the normal tasking context.
*
****************************************************************************/
-#ifdef CONFIG_NET_ICMPv6_PING
-void icmpv6_poll(FAR struct net_driver_s *dev);
-#endif /* CONFIG_NET_ICMPv6_PING */
+#ifdef CONFIG_NET_NET_ICMPv6_NEIGHBOR
+int icmpv6_neighbor(net_ipv6addr_t ipaddr);
+#else
+# define icmpv6_neighbor(i) (0)
+#endif
/****************************************************************************
- * Name: icmpv6_send
+ * Name: icmpv6_poll
*
* Description:
- * Setup to send an ICMPv6 packet
+ * Poll a UDP "connection" structure for availability of TX data
*
* Parameters:
* dev - The device driver structure to use in the send operation
@@ -130,9 +146,9 @@ void icmpv6_poll(FAR struct net_driver_s *dev);
*
****************************************************************************/
-#ifdef CONFIG_NET_ICMPv6_PING
-void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipv6addr_t *destaddr);
-#endif /* CONFIG_NET_ICMPv6_PING */
+#if defined(CONFIG_NET_ICMPv6_PING) || defined(CONFIG_NET_NET_ICMPv6_NEIGHBOR)
+void icmpv6_poll(FAR struct net_driver_s *dev);
+#endif
/****************************************************************************
* Name: icmpv6_solicit
diff --git a/nuttx/net/icmpv6/icmpv6_input.c b/nuttx/net/icmpv6/icmpv6_input.c
index 99ec16783..28bb210c3 100644
--- a/nuttx/net/icmpv6/icmpv6_input.c
+++ b/nuttx/net/icmpv6/icmpv6_input.c
@@ -77,20 +77,16 @@
((struct icmpv6_neighbor_advertise_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
+ * Public Data
****************************************************************************/
#ifdef CONFIG_NET_ICMPv6_PING
FAR struct devif_callback_s *g_icmpv6_echocallback = NULL;
#endif
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
+#ifdef CONFIG_NET_ICMPv6_NEIGHBOR
+FAR struct devif_callback_s *g_icmpv6_neighborcallback = NULL;
+#endif
/****************************************************************************
* Public Functions
@@ -262,6 +258,20 @@ void icmpv6_input(FAR struct net_driver_s *dev)
neighbor_add(icmp->srcipaddr,
(FAR struct neighbor_addr_s *)adv->tgtlladdr);
+#ifdef CONFIG_NET_ICMPv6_NEIGHBOR
+ /* Is there logic waiting for the Neighbor Advertisement? */
+
+ if (g_icmpv6_neighborcallback)
+ {
+ /* Dispatch the Neighbor Advertisement reply to the
+ * waiting thread.
+ */
+
+ (void)devif_callback_execute(dev, icmp, ICMPv6_ADVERTISE,
+ g_icmpv6_neighborcallback);
+ }
+#endif
+
/* We consumed the packet but we don't send anything in
* response.
*/
@@ -297,12 +307,9 @@ void icmpv6_input(FAR struct net_driver_s *dev)
{
uint16_t flags = ICMPv6_ECHOREPLY;
- if (g_icmpv6_echocallback)
- {
- /* Dispatch the ECHO reply to the waiting thread */
+ /* Dispatch the ECHO reply to the waiting thread */
- flags = devif_callback_execute(dev, icmp, flags, g_icmpv6_echocallback);
- }
+ flags = devif_callback_execute(dev, icmp, flags, g_icmpv6_echocallback);
/* If the ECHO reply was not handled, then drop the packet */
diff --git a/nuttx/net/icmpv6/icmpv6_ping.c b/nuttx/net/icmpv6/icmpv6_ping.c
index 183c5ef7c..fb000978a 100644
--- a/nuttx/net/icmpv6/icmpv6_ping.c
+++ b/nuttx/net/icmpv6/icmpv6_ping.c
@@ -38,8 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMPv6) && \
- defined(CONFIG_NET_ICMPv6_PING)
+#ifdef CONFIG_NET_ICMPv6_PING
#include <sys/types.h>
#include <stdint.h>
@@ -483,4 +482,4 @@ int icmpv6_ping(net_ipv6addr_t addr, uint16_t id, uint16_t seqno,
}
}
-#endif /* CONFIG_NET_ICMPv6 && CONFIG_NET_ICMPv6_PING ... */
+#endif /* CONFIG_NET_ICMPv6_PING */
diff --git a/nuttx/net/icmpv6/icmpv6_poll.c b/nuttx/net/icmpv6/icmpv6_poll.c
index c8d31f937..3a3c75df1 100644
--- a/nuttx/net/icmpv6/icmpv6_poll.c
+++ b/nuttx/net/icmpv6/icmpv6_poll.c
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMPv6) && defined(CONFIG_NET_ICMPv6_PING)
+#if defined(CONFIG_NET_ICMPv6_PING) || defined(CONFIG_NET_NET_ICMPv6_NEIGHBOR)
#include <debug.h>
@@ -99,4 +99,4 @@ void icmpv6_poll(FAR struct net_driver_s *dev)
(void)devif_callback_execute(dev, NULL, ICMPv6_POLL, g_icmpv6_echocallback);
}
-#endif /* CONFIG_NET && CONFIG_NET_ICMPv6 && CONFIG_NET_ICMPv6_PING */
+#endif /* CONFIG_NET_ICMPv6_PING || CONFIG_NET_NET_ICMPv6_NEIGHBOR */
diff --git a/nuttx/net/icmpv6/icmpv6_send.c b/nuttx/net/icmpv6/icmpv6_send.c
deleted file mode 100644
index 1f39e7614..000000000
--- a/nuttx/net/icmpv6/icmpv6_send.c
+++ /dev/null
@@ -1,145 +0,0 @@
-/****************************************************************************
- * net/icmpv6/icmpv6_send.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>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMPv6) && defined(CONFIG_NET_ICMPv6_PING)
-
-#include <string.h>
-#include <debug.h>
-
-#include <arpa/inet.h>
-
-#include <nuttx/net/netconfig.h>
-#include <nuttx/net/netdev.h>
-#include <nuttx/net/netstats.h>
-#include <nuttx/net/ip.h>
-#include <nuttx/net/icmpv6.h>
-
-#include "devif/devif.h"
-#include "utils/utils.h"
-#include "icmpv6/icmpv6.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define ICMPv6BUF ((struct icmpv6_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: icmpv6_send
- *
- * Description:
- * Setup to send an ICMPv6 packet
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipv6addr_t *destaddr)
-{
- FAR struct icmpv6_iphdr_s *icmp = ICMPv6BUF;
-
- if (dev->d_sndlen > 0)
- {
- /* The total length to send is the size of the application data plus
- * the IP and ICMPv6 headers (and, eventually, the Ethernet header)
- */
-
- dev->d_len = dev->d_sndlen + IPICMPv6_HDRLEN;
-
- /* The total size of the data (for ICMPv6 checksum calculation) includes
- * the size of the ICMPv6 header
- */
-
- dev->d_sndlen += ICMPv6_HDRLEN;
-
- /* Initialize the IP header. Note that for IPv6, the IP length field
- * does not include the IPv6 IP header length.
- */
-
- icmp->vtc = 0x60;
- icmp->tcf = 0x00;
- icmp->flow = 0x00;
- icmp->len[0] = (dev->d_sndlen >> 8);
- icmp->len[1] = (dev->d_sndlen & 0xff);
- icmp->proto = IP_PROTO_ICMP6;
- icmp->ttl = IP_TTL;
-
- net_ipv6addr_copy(icmp->srcipaddr, dev->d_ipv6addr);
- net_ipv6addr_copy(icmp->destipaddr, destaddr);
-
- /* Calculate the ICMPv6 checksum. */
-
- icmp->chksum = 0;
- icmp->chksum = ~icmpv6_chksum(dev);
-
- nllvdbg("Outgoing ICMPv6 packet length: %d (%d)\n",
- dev->d_len, (icmp->len[0] << 8) | icmp->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- g_netstats.icmpv6.sent++;
- g_netstats.ipv6.sent++;
-#endif
- }
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_ICMPv6 && CONFIG_NET_ICMPv6_PING */