summaryrefslogtreecommitdiff
path: root/nuttx/net/neighbor
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-20 12:31:56 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-20 12:31:56 -0600
commitea61ca860ff132a95330b55a8f71fcc9709b7c52 (patch)
treeabb4b654c6fccd0fd3c28ad87da60175ebcb6464 /nuttx/net/neighbor
parent47b69ccc38c31de68db1a5abf144e5887893516e (diff)
downloadpx4-nuttx-ea61ca860ff132a95330b55a8f71fcc9709b7c52.tar.gz
px4-nuttx-ea61ca860ff132a95330b55a8f71fcc9709b7c52.tar.bz2
px4-nuttx-ea61ca860ff132a95330b55a8f71fcc9709b7c52.zip
Networking: Clean up IPv6 Neighbor Table logic
Diffstat (limited to 'nuttx/net/neighbor')
-rw-r--r--nuttx/net/neighbor/Kconfig4
-rw-r--r--nuttx/net/neighbor/Make.defs3
-rw-r--r--nuttx/net/neighbor/neighbor.c196
-rw-r--r--nuttx/net/neighbor/neighbor.h153
-rw-r--r--nuttx/net/neighbor/neighbor_add.c117
-rw-r--r--nuttx/net/neighbor/neighbor_findentry.c83
-rw-r--r--nuttx/net/neighbor/neighbor_initialize.c93
-rw-r--r--nuttx/net/neighbor/neighbor_lookup.c91
-rw-r--r--nuttx/net/neighbor/neighbor_periodic.c107
-rw-r--r--nuttx/net/neighbor/neighbor_update.c77
10 files changed, 714 insertions, 210 deletions
diff --git a/nuttx/net/neighbor/Kconfig b/nuttx/net/neighbor/Kconfig
index 148438fbe..88cea4a1a 100644
--- a/nuttx/net/neighbor/Kconfig
+++ b/nuttx/net/neighbor/Kconfig
@@ -5,10 +5,10 @@
if NET_IPv6
-config NET_IPV6_NCONF_ENTRIES
+config NET_IPv6_NCONF_ENTRIES
int "Number of IPv6 neighbors"
default 8
-#config NET_IPV6_NEIGHBOR_ADDRTYPE
+#config NET_IPv6_NEIGHBOR_ADDRTYPE
endif # NET_IPv6
diff --git a/nuttx/net/neighbor/Make.defs b/nuttx/net/neighbor/Make.defs
index ee77ad29d..19cbb13e1 100644
--- a/nuttx/net/neighbor/Make.defs
+++ b/nuttx/net/neighbor/Make.defs
@@ -37,7 +37,8 @@
ifeq ($(CONFIG_NET_IPv6),y)
-NET_CSRCS += neighbor.c
+NET_CSRCS += neighbor_initialize.c neighbor_add.c neighbor_lookup.c
+NET_CSRCS += neighbor_update.c neighbor_periodic.c neighbor_findentry.c
# Include utility build support
diff --git a/nuttx/net/neighbor/neighbor.c b/nuttx/net/neighbor/neighbor.c
deleted file mode 100644
index 37a2460a1..000000000
--- a/nuttx/net/neighbor/neighbor.c
+++ /dev/null
@@ -1,196 +0,0 @@
-/****************************************************************************
- * net/neighbor/neighbor.c
- * Database of link-local neighbors, used by IPv6 code and to be used by
- * a future ARP code rewrite.
- *
- * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
- * reserved.
- * Author: Adam Dunkels <adam@sics.se>
- *
- * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 <string.h>
-#include <debug.h>
-
-#include <nuttx/net/ip.h>
-
-#include "neighbor/neighbor.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define MAX_TIME 128
-
-#ifdef CONFIG_NET_IPV6_NCONF_ENTRIES
-# define ENTRIES CONFIG_NET_IPV6_NCONF_ENTRIES
-#else /* CONFIG_NET_IPV6_NCONF_ENTRIES */
-# define ENTRIES 8
-#endif /* CONFIG_NET_IPV6_NCONF_ENTRIES */
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-struct neighbor_entry
-{
- net_ipv6addr_t ipaddr;
- struct net_neighbor_addr_s addr;
- uint8_t time;
-};
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static struct neighbor_entry entries[ENTRIES];
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-static struct neighbor_entry *find_entry(net_ipv6addr_t ipaddr)
-{
- int i;
-
- for (i = 0; i < ENTRIES; ++i)
- {
- if (net_ipv6addr_cmp(entries[i].ipaddr, ipaddr))
- {
- return &entries[i];
- }
- }
-
- return NULL;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-void net_neighbor_init(void)
-{
- int i;
-
- for (i = 0; i < ENTRIES; ++i)
- {
- entries[i].time = MAX_TIME;
- }
-}
-
-void net_neighbor_periodic(void)
-{
- int i;
-
- for (i = 0; i < ENTRIES; ++i)
- {
- if (entries[i].time < MAX_TIME)
- {
- entries[i].time++;
- }
- }
-}
-
-void net_neighbor_add(net_ipv6addr_t ipaddr, struct net_neighbor_addr_s *addr)
-{
- uint8_t oldest_time;
- int oldest;
- int i;
-
- nlldbg("Add neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
- addr->addr.ether_addr_octet[0], addr->addr.ether_addr_octet[1],
- addr->addr.ether_addr_octet[2], addr->addr.ether_addr_octet[3],
- addr->addr.ether_addr_octet[4], addr->addr.ether_addr_octet[5]);
-
- /* Find the first unused entry or the oldest used entry. */
-
- oldest_time = 0;
- oldest = 0;
-
- for (i = 0; i < ENTRIES; ++i)
- {
- if (entries[i].time == MAX_TIME)
- {
- oldest = i;
- break;
- }
- if (net_ipv6addr_cmp(entries[i].ipaddr, addr))
- {
- oldest = i;
- break;
- }
- if (entries[i].time > oldest_time)
- {
- oldest = i;
- oldest_time = entries[i].time;
- }
- }
-
- /* Use the oldest or first free entry (either pointed to by the
- * "oldest" variable).
- */
-
- entries[oldest].time = 0;
- net_ipv6addr_copy(entries[oldest].ipaddr, ipaddr);
- memcpy(&entries[oldest].addr, addr, sizeof(struct net_neighbor_addr_s));
-}
-
-void net_neighbor_update(net_ipv6addr_t ipaddr)
-{
- struct neighbor_entry *e;
-
- e = find_entry(ipaddr);
- if (e != NULL)
- {
- e->time = 0;
- }
-}
-
-struct net_neighbor_addr_s *net_neighbor_lookup(net_ipv6addr_t ipaddr)
-{
- struct neighbor_entry *e;
-
- e = find_entry(ipaddr);
- if (e != NULL)
- {
- nlldbg("Lookup neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
- e->addr.addr.ether_addr_octet[0], e->addr.addr.ether_addr_octet[1],
- e->addr.addr.ether_addr_octet[2], e->addr.addr.ether_addr_octet[3],
- e->addr.addr.ether_addr_octet[4], e->addr.addr.ether_addr_octet[5]);
-
- return &e->addr;
- }
-
- return NULL;
-}
diff --git a/nuttx/net/neighbor/neighbor.h b/nuttx/net/neighbor/neighbor.h
index db43fecfa..ffc003827 100644
--- a/nuttx/net/neighbor/neighbor.h
+++ b/nuttx/net/neighbor/neighbor.h
@@ -3,10 +3,10 @@
* Header file for database of link-local neighbors, used by IPv6 code and
* to be used by future ARP code.
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
- * A direct leverage of logic from uIP which also has b BSD style license
+ * A leverage of logic from uIP which also has a BSD style license
*
* Author: Adam Dunkels <adam@sics.se>
* Copyright (c) 2006, Swedish Institute of Computer Science.
@@ -54,31 +54,162 @@
#ifdef CONFIG_NET_IPv6
/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifndef CONFIG_NET_IPv6_NCONF_ENTRIES
+# define CONFIG_NET_IPv6_NCONF_ENTRIES 8
+#endif
+
+#define NEIGHBOR_MAXTIME 128
+
+/****************************************************************************
* Public Types
****************************************************************************/
+/* Describes the link layer address */
-struct net_neighbor_addr_s
+struct neighbor_addr_s
{
-#if CONFIG_NET_IPV6_NEIGHBOR_ADDRTYPE
- CONFIG_NET_IPV6_NEIGHBOR_ADDRTYPE addr;
+#if CONFIG_NET_IPv6_NEIGHBOR_ADDRTYPE
+ CONFIG_NET_IPv6_NEIGHBOR_ADDRTYPE na_addr;
#else
- struct ether_addr addr;
+ struct ether_addr na_addr;
#endif
};
+/* This structure describes on entry in the neighbor table. This is intended
+ * for internal use within the Neighbor implementation.
+ */
+
+struct neighbor_entry
+{
+ net_ipv6addr_t ne_ipaddr; /* IPv6 address of the Neighbor */
+ struct neighbor_addr_s ne_addr; /* Link layer address of the Neighbor */
+ uint8_t ne_time; /* For aging, units of half seconds */
+};
+
/****************************************************************************
* Public Data
****************************************************************************/
+/* This is the Neighbor table. The network should be locked when accessing
+ * this table.
+ */
+
+extern struct neighbor_entry g_neighbors[CONFIG_NET_IPv6_NCONF_ENTRIES];
+
+/* This is the time, in clock ticks, of the last poll */
+
+extern uint32_t g_neighbor_polltime;
+
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
-void net_neighbor_init(void);
-void net_neighbor_add(net_ipv6addr_t ipaddr, struct net_neighbor_addr_s *addr);
-void net_neighbor_update(net_ipv6addr_t ipaddr);
-struct net_neighbor_addr_s *net_neighbor_lookup(net_ipv6addr_t ipaddr);
-void net_neighbor_periodic(void);
+/****************************************************************************
+ * Name: neighbor_initialize
+ *
+ * Description:
+ * Initialize Neighbor table support
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_initialize(void);
+
+/****************************************************************************
+ * Name: neighbor_findentry
+ *
+ * Description:
+ * Find an entry in the Neighbor Table. This interface is internal to
+ * the neighbor implementation; Consider using neighbor_lookup() instead;
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address to use in the lookup;
+ *
+ * Returned Value:
+ * The Neighbor Table entry corresponding to the IPv6 address; NULL is
+ * returned if there is no matching entry in the Neighbor Table.
+ *
+ ****************************************************************************/
+
+FAR struct neighbor_entry *neighbor_findentry(net_ipv6addr_t ipaddr);
+
+/****************************************************************************
+ * Name: neighbor_add
+ *
+ * Description:
+ * Add the new address association to the Neighbor Table (if it is not
+ * already there).
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address of the mapping.
+ * addr - The link layer address of the mapping
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_add(FAR net_ipv6addr_t ipaddr, FAR struct neighbor_addr_s *addr);
+
+/****************************************************************************
+ * Name: neighbor_lookup
+ *
+ * Description:
+ * Find an entry in the Neighbor Table and return its link layer address.
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address to use in the lookup;
+ *
+ * Returned Value:
+ * A read-only reference to the link layer address in the Neighbor Table is
+ * returned on success. NULL is returned if there is no matching entry in
+ * the Neighbor Table.
+ *
+ ****************************************************************************/
+
+FAR const struct neighbor_addr_s *neighbor_lookup(net_ipv6addr_t ipaddr);
+
+/****************************************************************************
+ * Name: neighbor_update
+ *
+ * Description:
+ * Reset time on the Neighbor Table entry associated with the IPv6 address.
+ * This makes the associated entry the most recently used and not a
+ * candidate for removal.
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address of the entry to be updated
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_update(net_ipv6addr_t ipaddr);
+
+/****************************************************************************
+ * Name: neighbor_periodic
+ *
+ * Description:
+ * Called from the timer poll logic in order to perform agin operations on
+ * entries in the Neighbor Table
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_periodic(void);
#endif /* CONFIG_NET_IPv6 */
#endif /* __NET_NEIGHBOR_NEIGHBOR_H */
diff --git a/nuttx/net/neighbor/neighbor_add.c b/nuttx/net/neighbor/neighbor_add.c
new file mode 100644
index 000000000..02cf8f6f9
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_add.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ * net/neighbor/neighbor_add.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 <string.h>
+#include <debug.h>
+
+#include <nuttx/net/ip.h>
+
+#include "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_add
+ *
+ * Description:
+ * Add the new address association to the Neighbor Table (if it is not
+ * already there).
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address of the mapping.
+ * addr - The link layer address of the mapping
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_add(FAR net_ipv6addr_t ipaddr, FAR struct neighbor_addr_s *addr)
+{
+ uint8_t oldest_time;
+ int oldest_ndx;
+ int i;
+
+ nlldbg("Add neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ addr->na_addr.ether_addr_octet[0], addr->na_addr.ether_addr_octet[1],
+ addr->na_addr.ether_addr_octet[2], addr->na_addr.ether_addr_octet[3],
+ addr->na_addr.ether_addr_octet[4], addr->na_addr.ether_addr_octet[5]);
+
+ /* Find the first unused entry or the oldest used entry. */
+
+ oldest_time = 0;
+ oldest_ndx = 0;
+
+ for (i = 0; i < CONFIG_NET_IPv6_NCONF_ENTRIES; ++i)
+ {
+ if (g_neighbors[i].ne_time == NEIGHBOR_MAXTIME)
+ {
+ oldest_ndx = i;
+ break;
+ }
+
+ if (net_ipv6addr_cmp(g_neighbors[i].ne_ipaddr, addr))
+ {
+ oldest_ndx = i;
+ break;
+ }
+
+ if (g_neighbors[i].ne_time > oldest_time)
+ {
+ oldest_ndx = i;
+ oldest_time = g_neighbors[i].ne_time;
+ }
+ }
+
+ /* Use the oldest or first free entry (either pointed to by the
+ * "oldest_ndx" variable).
+ */
+
+ g_neighbors[oldest_ndx].ne_time = 0;
+ net_ipv6addr_copy(g_neighbors[oldest_ndx].ne_ipaddr, ipaddr);
+ memcpy(&g_neighbors[oldest_ndx].ne_addr, addr, sizeof(struct neighbor_addr_s));
+}
diff --git a/nuttx/net/neighbor/neighbor_findentry.c b/nuttx/net/neighbor/neighbor_findentry.c
new file mode 100644
index 000000000..30b13038c
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_findentry.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * net/neighbor/neighbor_findentry.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 <string.h>
+
+#include "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_findentry
+ *
+ * Description:
+ * Find an entry in the Neighbor Table. This interface is internal to
+ * the neighbor implementation; Consider using neighbor_lookup() instead;
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address to use in the lookup;
+ *
+ * Returned Value:
+ * The Neighbor Table entry corresponding to the IPv6 address; NULL is
+ * returned if there is no matching entry in the Neighbor Table.
+ *
+ ****************************************************************************/
+
+FAR struct neighbor_entry *neighbor_findentry(net_ipv6addr_t ipaddr)
+{
+ int i;
+
+ for (i = 0; i < CONFIG_NET_IPv6_NCONF_ENTRIES; ++i)
+ {
+ if (net_ipv6addr_cmp(g_neighbors[i].ne_ipaddr, ipaddr))
+ {
+ return &g_neighbors[i];
+ }
+ }
+
+ return NULL;
+}
diff --git a/nuttx/net/neighbor/neighbor_initialize.c b/nuttx/net/neighbor/neighbor_initialize.c
new file mode 100644
index 000000000..fd8b36d36
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_initialize.c
@@ -0,0 +1,93 @@
+/****************************************************************************
+ * net/neighbor/neighbor_initialize.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* This is the Neighbor table. The network should be locked when accessing
+ * this table.
+ */
+
+struct neighbor_entry g_neighbors[CONFIG_NET_IPv6_NCONF_ENTRIES];
+
+/* This is the time, in clock ticks, of the last poll */
+
+uint32_t g_neighbor_polltime;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_initialize
+ *
+ * Description:
+ * Initialize Neighbor table support
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_initialize(void)
+{
+ int i;
+
+ for (i = 0; i < CONFIG_NET_IPv6_NCONF_ENTRIES; ++i)
+ {
+ g_neighbors[i].ne_time = NEIGHBOR_MAXTIME;
+ }
+
+ /* Initialize the time of the last poll */
+
+ g_neighbor_polltime = clock_systimer();
+}
diff --git a/nuttx/net/neighbor/neighbor_lookup.c b/nuttx/net/neighbor/neighbor_lookup.c
new file mode 100644
index 000000000..4c7d9b04a
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_lookup.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * net/neighbor/neighbor.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 <debug.h>
+
+#include <nuttx/net/ip.h>
+
+#include "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_lookup
+ *
+ * Description:
+ * Find an entry in the Neighbor Table and return its link layer address.
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address to use in the lookup;
+ *
+ * Returned Value:
+ * A read-only reference to the link layer address in the Neighbor Table is
+ * returned on success. NULL is returned if there is no matching entry in
+ * the Neighbor Table.
+ *
+ ****************************************************************************/
+
+FAR const struct neighbor_addr_s *neighbor_lookup(net_ipv6addr_t ipaddr)
+{
+ FAR struct neighbor_entry *neighbor;
+
+ neighbor = neighbor_findentry(ipaddr);
+ if (neighbor != NULL)
+ {
+ nlldbg("Lookup neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ neighbor->ne_addr.na_addr.ether_addr_octet[0],
+ neighbor->ne_addr.na_addr.ether_addr_octet[1],
+ neighbor->ne_addr.na_addr.ether_addr_octet[2],
+ neighbor->ne_addr.na_addr.ether_addr_octet[3],
+ neighbor->ne_addr.na_addr.ether_addr_octet[4],
+ neighbor->ne_addr.na_addr.ether_addr_octet[5]);
+
+ return &neighbor->ne_addr;
+ }
+
+ return NULL;
+}
diff --git a/nuttx/net/neighbor/neighbor_periodic.c b/nuttx/net/neighbor/neighbor_periodic.c
new file mode 100644
index 000000000..2a9f0d99f
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_periodic.c
@@ -0,0 +1,107 @@
+/****************************************************************************
+ * net/neighbor/neighbor_periodic.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#define USEC_PER_HSEC 500000
+#define TICK_PER_HSEC (USEC_PER_HSEC / USEC_PER_TICK) /* Truncates! */
+#define TICK2HSEC(tick) (((tick)+(TICK_PER_HSEC/2))/TICK_PER_HSEC) /* Rounds */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_periodic
+ *
+ * Description:
+ * Called from the timer poll logic in order to perform agin operations on
+ * entries in the Neighbor Table
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_periodic(void)
+{
+ uint32_t now;
+ uint32_t ticks;
+ uint32_t hsecs;
+ int i;
+
+ /* Get the elapsed time in units of half seconds */
+
+ now = clock_systimer();
+ ticks = now - g_neighbor_polltime;
+ hsecs = TICK2HSEC(ticks);
+
+ /* Reset the time of the last poll */
+
+ g_neighbor_polltime = now;
+
+ /* Add the elapsed half seconds from each activate entry in the
+ * Neighbor table.
+ */
+
+ for (i = 0; i < CONFIG_NET_IPv6_NCONF_ENTRIES; ++i)
+ {
+ uint32_t newtime = g_neighbors[i].ne_time + hsecs;
+ if (newtime > NEIGHBOR_MAXTIME)
+ {
+ newtime = NEIGHBOR_MAXTIME;
+ }
+
+ g_neighbors[i].ne_time = newtime;
+ }
+}
diff --git a/nuttx/net/neighbor/neighbor_update.c b/nuttx/net/neighbor/neighbor_update.c
new file mode 100644
index 000000000..e0d44e253
--- /dev/null
+++ b/nuttx/net/neighbor/neighbor_update.c
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * net/neighbor/neighbor_update.c
+ *
+ * Copyright (C) 2007-2009, 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * A leverage of logic from uIP which also has a BSD style license
+ *
+ * Copyright (c) 2006, Swedish Institute of Computer Science. All rights
+ * reserved.
+ * Author: Adam Dunkels <adam@sics.se>
+ *
+ * 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 of the Institute 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 INSTITUTE 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 INSTITUTE 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 "neighbor/neighbor.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: neighbor_update
+ *
+ * Description:
+ * Reset time on the Neighbor Table entry associated with the IPv6 address.
+ * This makes the associated entry the most recently used and not a
+ * candidate for removal.
+ *
+ * Input Parameters:
+ * ipaddr - The IPv6 address of the entry to be updated
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void neighbor_update(net_ipv6addr_t ipaddr)
+{
+ struct neighbor_entry *neighbor;
+
+ neighbor = neighbor_findentry(ipaddr);
+ if (neighbor != NULL)
+ {
+ neighbor->ne_time = 0;
+ }
+}