summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-07-06 11:05:28 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-07-06 11:05:28 -0600
commitf750736df35456e25d3768c1afda76bcd7c29d7d (patch)
tree8f54da5c27af7e36052c2d80dc328e9d5b38956d /nuttx
parent3e3ae07e84fbc82059071eeed6a7fac9045d7849 (diff)
downloadpx4-nuttx-f750736df35456e25d3768c1afda76bcd7c29d7d.tar.gz
px4-nuttx-f750736df35456e25d3768c1afda76bcd7c29d7d.tar.bz2
px4-nuttx-f750736df35456e25d3768c1afda76bcd7c29d7d.zip
NET: Move private definitions from include/nuttx/net/arp.h to net/arp/arp.h
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/include/nuttx/net/arp.h159
-rw-r--r--nuttx/include/nuttx/net/icmp.h27
-rw-r--r--nuttx/net/arp/arp.h104
-rw-r--r--nuttx/net/arp/arp_inout.c123
-rw-r--r--nuttx/net/arp/arp_table.c18
-rw-r--r--nuttx/net/arp/arp_timer.c11
-rw-r--r--nuttx/net/devif/devif.h1
-rw-r--r--nuttx/net/ipv6/ipv6.h2
-rw-r--r--nuttx/net/net_initialize.c8
-rw-r--r--nuttx/net/pkt/pkt_input.c1
-rw-r--r--nuttx/net/pkt/pkt_send.c1
-rw-r--r--nuttx/net/socket/net_sendfile.c2
-rw-r--r--nuttx/net/tcp/tcp_send_buffered.c2
-rw-r--r--nuttx/net/tcp/tcp_send_unbuffered.c2
14 files changed, 291 insertions, 170 deletions
diff --git a/nuttx/include/nuttx/net/arp.h b/nuttx/include/nuttx/net/arp.h
index 7c19039dd..35b8b4a5c 100644
--- a/nuttx/include/nuttx/net/arp.h
+++ b/nuttx/include/nuttx/net/arp.h
@@ -112,25 +112,17 @@ extern "C"
#ifdef CONFIG_NET_ARP
/****************************************************************************
- * Name: arp_init
- *
- * Description:
- * Initialize the ARP module. This function must be called before any of
- * the other ARP functions.
- *
- ****************************************************************************/
-
-void arp_init(void);
-
-/****************************************************************************
* Name: arp_ipin
*
* Description:
- * The arp_ipin() function should be called whenever an IP packet
- * arrives from the Ethernet. This function refreshes the ARP table or
- * inserts a new mapping if none exists. The function assumes that an
- * IP packet with an Ethernet header is present in the d_buf buffer
- * and that the length of the packet is in the d_len field.
+ * The arp_ipin() function should be called by Ethernet device drivers
+ * whenever an IP packet arrives from the network. The function will
+ * check if the address is in the ARP cache, and if so the ARP cache entry
+ * will be refreshed. If no ARP cache entry was found, a new one is created.
+ *
+ * This function expects that an IP packet with an Ethernet header is
+ * present in the d_buf buffer and that the length of the packet is in the
+ * d_len field.
*
****************************************************************************/
@@ -144,86 +136,55 @@ void arp_ipin(struct net_driver_s *dev);
* Name: arp_arpin
*
* Description:
- * The arp_arpin() should be called when an ARP packet is received
- * by the Ethernet driver. This function also assumes that the
- * Ethernet frame is present in the d_buf buffer. When the
- * arp_arpin() function returns, the contents of the d_buf
- * buffer should be sent out on the Ethernet if the d_len field
- * is > 0.
+ * This function should be called by the Ethernet device driver when an ARP
+ * packet has been received. The function will act differently
+ * depending on the ARP packet type: if it is a reply for a request
+ * that we previously sent out, the ARP cache will be filled in with
+ * the values from the ARP reply. If the incoming ARP packet is an ARP
+ * request for our IP address, an ARP reply packet is created and put
+ * into the d_buf[] buffer.
+ *
+ * On entry, this function expects that an ARP packet with a prepended
+ * Ethernet header is present in the d_buf[] buffer and that the length of
+ * the packet is set in the d_len field.
+ *
+ * When the function returns, the value of the field d_len indicates whether
+ * the device driver should send out the ARP reply packet or not. If d_len
+ * is zero, no packet should be sent; If d_len is non-zero, it contains the
+ * length of the outbound packet that is present in the d_buf[] buffer.
*
****************************************************************************/
void arp_arpin(struct net_driver_s *dev);
/****************************************************************************
- * Name: arp_arpin
- *
- * Description:
- * The arp_out() function should be called when an IP packet
- * should be sent out on the Ethernet. This function creates an
- * Ethernet header before the IP header in the d_buf buffer. The
- * Ethernet header will have the correct Ethernet MAC destination
- * address filled in if an ARP table entry for the destination IP
- * address (or the IP address of the default router) is present. If no
- * such table entry is found, the IP packet is overwritten with an ARP
- * request and we rely on TCP to retransmit the packet that was
- * overwritten. In any case, the d_len field holds the length of
- * the Ethernet frame that should be transmitted.
- *
- ****************************************************************************/
-
-void arp_out(struct net_driver_s *dev);
-
-/****************************************************************************
- * Function: arp_timer_init
- *
- * Description:
- * Initialized the 10 second timer that is need by uIP to age ARP
- * associations
- *
- * Parameters:
- * None
- *
- * Returned Value:
- * None
- *
- * Assumptions:
- * Called once at system initialization time
- *
- ****************************************************************************/
-
-void arp_timer_init(void);
-
-/****************************************************************************
- * Name: arp_timer
- *
- * Description:
- * This function performs periodic timer processing in the ARP module
- * and should be called at regular intervals. The recommended interval
- * is 10 seconds between the calls. It is responsible for flushing old
- * entries in the ARP table.
- *
- ****************************************************************************/
-
-void arp_timer(void);
-
-/****************************************************************************
- * Name: arp_update
+ * Name: arp_out
*
* Description:
- * Add the IP/HW address mapping to the ARP table -OR- change the IP
- * address of an existing association.
- *
- * Input parameters:
- * pipaddr - Refers to an IP address uint16_t[2] in network order
- * ethaddr - Refers to a HW address uint8_t[IFHWADDRLEN]
- *
- * Assumptions
- * Interrupts are disabled
+ * This function should be called before sending out an IP packet. The
+ * function checks the destination IP address of the IP packet to see
+ * what Ethernet MAC address that should be used as a destination MAC
+ * address on the Ethernet.
+ *
+ * If the destination IP address is in the local network (determined
+ * by logical ANDing of netmask and our IP address), the function
+ * checks the ARP cache to see if an entry for the destination IP
+ * address is found. If so, an Ethernet header is pre-pended at the
+ * beginning of the packet and the function returns.
+ *
+ * If no ARP cache entry is found for the destination IP address, the
+ * packet in the d_buf[] is replaced by an ARP request packet for the
+ * IP address. The IP packet is dropped and it is assumed that the
+ * higher level protocols (e.g., TCP) eventually will retransmit the
+ * dropped packet.
+ *
+ * Upon return in either the case, a packet to be sent is present in the
+ * d_buf[] buffer and the d_len field holds the length of the Ethernet
+ * frame that should be transmitted.
*
****************************************************************************/
-void arp_update(FAR uint16_t *pipaddr, FAR uint8_t *ethaddr);
+void arp_out(FAR struct net_driver_s *dev);
/****************************************************************************
* Name: arp_find
@@ -240,7 +201,7 @@ void arp_update(FAR uint16_t *pipaddr, FAR uint8_t *ethaddr);
*
****************************************************************************/
-struct arp_entry *arp_find(in_addr_t ipaddr);
+FAR struct arp_entry *arp_find(in_addr_t ipaddr);
/****************************************************************************
* Name: arp_delete
@@ -252,7 +213,8 @@ struct arp_entry *arp_find(in_addr_t ipaddr);
* ipaddr - Refers to an IP address in network order
*
* Assumptions
- * Interrupts are disabled
+ * Interrupts are disabled to assure exclusive access to the ARP table
+ * (and because arp_find() is called).
*
****************************************************************************/
@@ -265,19 +227,34 @@ struct arp_entry *arp_find(in_addr_t ipaddr);
} \
}
+/****************************************************************************
+ * Name: arp_update
+ *
+ * Description:
+ * Add the IP/HW address mapping to the ARP table -OR- change the IP
+ * address of an existing association.
+ *
+ * Input parameters:
+ * pipaddr - Refers to an IP address uint16_t[2] in network order
+ * ethaddr - Refers to a HW address uint8_t[IFHWADDRLEN]
+ *
+ * Assumptions
+ * Interrupts are disabled to assure exclusive access to the ARP table.
+ *
+ ****************************************************************************/
+
+void arp_update(FAR uint16_t *pipaddr, FAR uint8_t *ethaddr);
+
#else /* CONFIG_NET_ARP */
/* If ARP is disabled, stub out all ARP interfaces */
-# define arp_init()
# define arp_ipin(dev)
# define arp_arpin(dev)
# define arp_out(dev)
-# define arp_timer()
-# define arp_update(pipaddr,ethaddr)
# define arp_find(ipaddr) NULL
# define arp_delete(ipaddr)
-# define arp_timer_init(void);
+# define arp_update(pipaddr,ethaddr)
#endif /* CONFIG_NET_ARP */
diff --git a/nuttx/include/nuttx/net/icmp.h b/nuttx/include/nuttx/net/icmp.h
index 722121b3a..0d5799b7f 100644
--- a/nuttx/include/nuttx/net/icmp.h
+++ b/nuttx/include/nuttx/net/icmp.h
@@ -205,6 +205,33 @@ extern "C"
* Public Function Prototypes
****************************************************************************/
+/****************************************************************************
+ * Name: imcp_ping
+ *
+ * Description:
+ * Send a ECHO request and wait for the ECHO response
+ *
+ * Parameters:
+ * addr - The IP address of the peer to send the ICMP ECHO request to
+ * in network order.
+ * id - The ID to use in the ICMP ECHO request. This number should be
+ * unique; only ECHO responses with this matching ID will be
+ * processed (host order)
+ * seqno - The sequence number used in the ICMP ECHO request. NOT used
+ * to match responses (host order)
+ * dsecs - Wait up to this many deci-seconds for the ECHO response to be
+ * returned (host order).
+ *
+ * Return:
+ * seqno of received ICMP ECHO with matching ID (may be different
+ * from the seqno argument (may be a delayed response from an earlier
+ * ping with the same ID). Or a negated errno on any failure.
+ *
+ * Assumptions:
+ * Called from the user level with interrupts enabled.
+ *
+ ****************************************************************************/
+
int icmp_ping(net_ipaddr_t addr, uint16_t id, uint16_t seqno, uint16_t datalen,
int dsecs);
diff --git a/nuttx/net/arp/arp.h b/nuttx/net/arp/arp.h
new file mode 100644
index 000000000..698be4345
--- /dev/null
+++ b/nuttx/net/arp/arp.h
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * net/arp/arp.h
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+#ifndef __NET_ARP_ARP_H
+#define __NET_ARP_ARP_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+ #ifdef CONFIG_NET_ARP
+/****************************************************************************
+ * Name: arp_reset
+ *
+ * Description:
+ * Re-initialize the ARP table.
+ *
+ ****************************************************************************/
+
+void arp_reset(void);
+
+/****************************************************************************
+ * Function: arp_timer_initialize
+ *
+ * Description:
+ * Initialized the 10 second timer that is need by the ARP logic in order
+ * to age ARP address associations
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called once at system initialization time
+ *
+ ****************************************************************************/
+
+void arp_timer_initialize(void);
+
+/****************************************************************************
+ * Name: arp_timer
+ *
+ * Description:
+ * This function performs periodic timer processing in the ARP module
+ * and should be called at regular intervals. The recommended interval
+ * is 10 seconds between the calls. It is responsible for flushing old
+ * entries in the ARP table.
+ *
+ ****************************************************************************/
+
+void arp_timer(void);
+
+#else /* CONFIG_NET_ARP */
+
+/* If ARP is disabled, stub out all ARP interfaces */
+
+# define arp_reset()
+# define arp_timer_initialize(void)
+# define arp_timer()
+
+#endif /* CONFIG_NET_ARP */
+#endif /* __UIP-NEIGHBOR_H__ */
diff --git a/nuttx/net/arp/arp_inout.c b/nuttx/net/arp/arp_inout.c
index 98d199f10..821a8780d 100644
--- a/nuttx/net/arp/arp_inout.c
+++ b/nuttx/net/arp/arp_inout.c
@@ -71,6 +71,7 @@
#include "netdev/netdev.h"
#include "route/route.h"
+#include "arp/arp.h"
#ifdef CONFIG_NET_ARP
@@ -160,7 +161,7 @@ static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
****************************************************************************/
#if defined(CONFIG_NET_DUMPARP) && defined(CONFIG_DEBUG)
-static void arp_dump(struct arp_hdr_s *arp)
+static void arp_dump(FAR struct arp_hdr_s *arp)
{
nlldbg(" HW type: %04x Protocol: %04x\n",
arp->ah_hwtype, arp->ah_protocol);\
@@ -185,19 +186,23 @@ static void arp_dump(struct arp_hdr_s *arp)
* Public Functions
****************************************************************************/
-/* ARP processing for incoming IP packets
+/****************************************************************************
+ * Name: arp_ipin
*
- * This function should be called by the device driver when an IP packet has
- * been received. The function will check if the address is in the ARP cache,
- * and if so the ARP cache entry will be refreshed. If no ARP cache entry was
- * found, a new one is created.
+ * Description:
+ * The arp_ipin() function should be called by Ethernet device drivers
+ * whenever an IP packet arrives from the network. The function will
+ * check if the address is in the ARP cache, and if so the ARP cache entry
+ * will be refreshed. If no ARP cache entry was found, a new one is created.
*
- * This function expects an IP packet with a prepended Ethernet header in the
- * d_buf[] buffer, and the length of the packet in the variable d_len.
- */
+ * This function expects that an IP packet with an Ethernet header is
+ * present in the d_buf buffer and that the length of the packet is in the
+ * d_len field.
+ *
+ ****************************************************************************/
#ifdef CONFIG_NET_ARP_IPIN
-void arp_ipin(struct net_driver_s *dev)
+void arp_ipin(FAR struct net_driver_s *dev)
{
in_addr_t srcipaddr;
@@ -213,30 +218,32 @@ void arp_ipin(struct net_driver_s *dev)
}
#endif /* CONFIG_NET_ARP_IPIN */
-/* ARP processing for incoming ARP packets.
+/****************************************************************************
+ * Name: arp_arpin
*
- * This function should be called by the device driver when an ARP
- * packet has been received. The function will act differently
- * depending on the ARP packet type: if it is a reply for a request
- * that we previously sent out, the ARP cache will be filled in with
- * the values from the ARP reply. If the incoming ARP packet is an ARP
- * request for our IP address, an ARP reply packet is created and put
- * into the d_buf[] buffer.
+ * Description:
+ * This function should be called by the Ethernet device driver when an ARP
+ * packet has been received. The function will act differently
+ * depending on the ARP packet type: if it is a reply for a request
+ * that we previously sent out, the ARP cache will be filled in with
+ * the values from the ARP reply. If the incoming ARP packet is an ARP
+ * request for our IP address, an ARP reply packet is created and put
+ * into the d_buf[] buffer.
*
- * When the function returns, the value of the field d_len
- * indicates whether the device driver should send out a packet or
- * not. If d_len is zero, no packet should be sent. If d_len is
- * non-zero, it contains the length of the outbound packet that is
- * present in the d_buf[] buffer.
+ * On entry, this function expects that an ARP packet with a prepended
+ * Ethernet header is present in the d_buf[] buffer and that the length of
+ * the packet is set in the d_len field.
*
- * This function expects an ARP packet with a prepended Ethernet
- * header in the d_buf[] buffer, and the length of the packet in the
- * variable d_len.
- */
+ * When the function returns, the value of the field d_len indicates whether
+ * the device driver should send out the ARP reply packet or not. If d_len
+ * is zero, no packet should be sent; If d_len is non-zero, it contains the
+ * length of the outbound packet that is present in the d_buf[] buffer.
+ *
+ ****************************************************************************/
-void arp_arpin(struct net_driver_s *dev)
+void arp_arpin(FAR struct net_driver_s *dev)
{
- struct arp_hdr_s *parp = ARPBUF;
+ FAR struct arp_hdr_s *parp = ARPBUF;
in_addr_t ipaddr;
if (dev->d_len < (sizeof(struct arp_hdr_s) + NET_LL_HDRLEN))
@@ -298,39 +305,41 @@ void arp_arpin(struct net_driver_s *dev)
}
}
-/* Prepend Ethernet header to an outbound IP packet and see if we need
- * to send out an ARP request.
+/****************************************************************************
+ * Name: arp_out
*
- * This function should be called before sending out an IP packet. The
- * function checks the destination IP address of the IP packet to see
- * what Ethernet MAC address that should be used as a destination MAC
- * address on the Ethernet.
+ * Description:
+ * This function should be called before sending out an IP packet. The
+ * function checks the destination IP address of the IP packet to see
+ * what Ethernet MAC address that should be used as a destination MAC
+ * address on the Ethernet.
*
- * If the destination IP address is in the local network (determined
- * by logical ANDing of netmask and our IP address), the function
- * checks the ARP cache to see if an entry for the destination IP
- * address is found. If so, an Ethernet header is prepended and the
- * function returns. If no ARP cache entry is found for the
- * destination IP address, the packet in the d_buf[] is replaced by
- * an ARP request packet for the IP address. The IP packet is dropped
- * and it is assumed that they higher level protocols (e.g., TCP)
- * eventually will retransmit the dropped packet.
+ * If the destination IP address is in the local network (determined
+ * by logical ANDing of netmask and our IP address), the function
+ * checks the ARP cache to see if an entry for the destination IP
+ * address is found. If so, an Ethernet header is pre-pended at the
+ * beginning of the packet and the function returns.
*
- * If the destination IP address is not on the local network, the IP
- * address of the default router is used instead.
+ * If no ARP cache entry is found for the destination IP address, the
+ * packet in the d_buf[] is replaced by an ARP request packet for the
+ * IP address. The IP packet is dropped and it is assumed that the
+ * higher level protocols (e.g., TCP) eventually will retransmit the
+ * dropped packet.
*
- * When the function returns, a packet is present in the d_buf[]
- * buffer, and the length of the packet is in the field d_len.
- */
+ * Upon return in either the case, a packet to be sent is present in the
+ * d_buf[] buffer and the d_len field holds the length of the Ethernet
+ * frame that should be transmitted.
+ *
+ ****************************************************************************/
-void arp_out(struct net_driver_s *dev)
+void arp_out(FAR struct net_driver_s *dev)
{
- const struct arp_entry *tabptr = NULL;
- struct arp_hdr_s *parp = ARPBUF;
- struct eth_hdr_s *peth = ETHBUF;
- struct arp_iphdr_s *pip = IPBUF;
- in_addr_t ipaddr;
- in_addr_t destipaddr;
+ FAR const struct arp_entry *tabptr = NULL;
+ FAR struct arp_hdr_s *parp = ARPBUF;
+ FAR struct eth_hdr_s *peth = ETHBUF;
+ FAR struct arp_iphdr_s *pip = IPBUF;
+ in_addr_t ipaddr;
+ in_addr_t destipaddr;
#ifdef CONFIG_NET_PKT
/* Skip sending ARP requests when the frame to be transmitted was
@@ -376,7 +385,7 @@ void arp_out(struct net_driver_s *dev)
* last three bytes of the IP address.
*/
- const uint8_t *ip = ((uint8_t*)pip->eh_destipaddr) + 1;
+ FAR const uint8_t *ip = ((uint8_t*)pip->eh_destipaddr) + 1;
memcpy(peth->dest, g_multicast_ethaddr, 3);
memcpy(&peth->dest[3], ip, 3);
}
diff --git a/nuttx/net/arp/arp_table.c b/nuttx/net/arp/arp_table.c
index ffe2ec214..d0439b56b 100644
--- a/nuttx/net/arp/arp_table.c
+++ b/nuttx/net/arp/arp_table.c
@@ -58,6 +58,8 @@
#include <nuttx/net/arp.h>
#include <nuttx/net/ip.h>
+#include <arp/arp.h>
+
#ifdef CONFIG_NET_ARP
/****************************************************************************
@@ -86,17 +88,17 @@ static uint8_t g_arptime;
****************************************************************************/
/****************************************************************************
- * Name: arp_init
+ * Name: arp_reset
*
* Description:
- * Initialize the ARP module. This function must be called before any of
- * the other ARP functions.
+ * Re-initialize the ARP table.
*
****************************************************************************/
-void arp_init(void)
+void arp_reset(void)
{
int i;
+
for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
{
memset(&g_arptable[i].at_ipaddr, 0, sizeof(in_addr_t));
@@ -116,7 +118,7 @@ void arp_init(void)
void arp_timer(void)
{
- struct arp_entry *tabptr;
+ FAR struct arp_entry *tabptr;
int i;
++g_arptime;
@@ -146,7 +148,7 @@ void arp_timer(void)
*
****************************************************************************/
-void arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
+void arp_update(FAR uint16_t *pipaddr, FAR uint8_t *ethaddr)
{
struct arp_entry *tabptr = NULL;
in_addr_t ipaddr = net_ip4addr_conv32(pipaddr);
@@ -240,9 +242,9 @@ void arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
*
****************************************************************************/
-struct arp_entry *arp_find(in_addr_t ipaddr)
+FAR struct arp_entry *arp_find(in_addr_t ipaddr)
{
- struct arp_entry *tabptr;
+ FAR struct arp_entry *tabptr;
int i;
for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
diff --git a/nuttx/net/arp/arp_timer.c b/nuttx/net/arp/arp_timer.c
index 75119a3e2..146abbfb9 100644
--- a/nuttx/net/arp/arp_timer.c
+++ b/nuttx/net/arp/arp_timer.c
@@ -46,7 +46,8 @@
#include <debug.h>
#include <nuttx/net/netconfig.h>
-#include <nuttx/net/arp.h>
+
+#include <arp/arp.h>
#ifdef CONFIG_NET_ARP
@@ -103,11 +104,11 @@ static void arptimer_poll(int argc, uint32_t arg, ...)
****************************************************************************/
/****************************************************************************
- * Function: arp_timer_init
+ * Function: arp_timer_initialize
*
* Description:
- * Initialized the 10 second timer that is need by uIP to age ARP
- * associations
+ * Initialized the 10 second timer that is need by the ARP logic in order
+ * to age ARP address associations
*
* Parameters:
* None
@@ -120,7 +121,7 @@ static void arptimer_poll(int argc, uint32_t arg, ...)
*
****************************************************************************/
-void arp_timer_init(void)
+void arp_timer_initialize(void)
{
/* Create and start the ARP timer */
diff --git a/nuttx/net/devif/devif.h b/nuttx/net/devif/devif.h
index a66bcd6c0..e2d153cc6 100644
--- a/nuttx/net/devif/devif.h
+++ b/nuttx/net/devif/devif.h
@@ -51,7 +51,6 @@
#include <errno.h>
#include <arch/irq.h>
-#include <nuttx/net/arp.h>
#include <nuttx/net/ip.h>
/****************************************************************************
diff --git a/nuttx/net/ipv6/ipv6.h b/nuttx/net/ipv6/ipv6.h
index 41004505d..ab2103c19 100644
--- a/nuttx/net/ipv6/ipv6.h
+++ b/nuttx/net/ipv6/ipv6.h
@@ -74,4 +74,4 @@ void net_neighbor_update(net_ipaddr_t ipaddr);
struct net_neighbor_addr_s *net_neighbor_lookup(net_ipaddr_t ipaddr);
void net_neighbor_periodic(void);
-#endif /* __UIP-NEIGHBOR_H__ */
+#endif /* __NET_IPV6_IPV6_H */
diff --git a/nuttx/net/net_initialize.c b/nuttx/net/net_initialize.c
index c57b7b623..93afeeb99 100644
--- a/nuttx/net/net_initialize.c
+++ b/nuttx/net/net_initialize.c
@@ -44,11 +44,11 @@
#include <nuttx/net/iob.h>
#include <nuttx/net/net.h>
-#include <nuttx/net/arp.h>
#include "socket/socket.h"
#include "devif/devif.h"
#include "netdev/netdev.h"
+#include "arp/arp.h"
#include "tcp/tcp.h"
#include "udp/udp.h"
#include "pkt/pkt.h"
@@ -88,6 +88,10 @@ void net_initialize(void)
net_lockinitialize();
+ /* Clear the ARP table */
+
+ arp_reset();
+
/* Initialize I/O buffering */
#ifdef CONFIG_NET_IOB
@@ -146,7 +150,7 @@ void net_initialize(void)
/* Initialize the periodic ARP timer */
- arp_timer_init();
+ arp_timer_initialize();
}
#endif /* CONFIG_NET */
diff --git a/nuttx/net/pkt/pkt_input.c b/nuttx/net/pkt/pkt_input.c
index c1aa03a86..cdaebb66c 100644
--- a/nuttx/net/pkt/pkt_input.c
+++ b/nuttx/net/pkt/pkt_input.c
@@ -48,7 +48,6 @@
#include <debug.h>
#include <nuttx/net/netdev.h>
-#include <nuttx/net/pkt.h>
#include <nuttx/net/arp.h>
#include <nuttx/net/pkt.h>
diff --git a/nuttx/net/pkt/pkt_send.c b/nuttx/net/pkt/pkt_send.c
index 5e548fcef..2420feb17 100644
--- a/nuttx/net/pkt/pkt_send.c
+++ b/nuttx/net/pkt/pkt_send.c
@@ -54,7 +54,6 @@
#include <nuttx/clock.h>
#include <nuttx/net/netdev.h>
#include <nuttx/net/net.h>
-#include <nuttx/net/arp.h>
#include <nuttx/net/ip.h>
#include "netdev/netdev.h"
diff --git a/nuttx/net/socket/net_sendfile.c b/nuttx/net/socket/net_sendfile.c
index dfaf5e61f..0242ac11b 100644
--- a/nuttx/net/socket/net_sendfile.c
+++ b/nuttx/net/socket/net_sendfile.c
@@ -59,8 +59,8 @@
#include <nuttx/clock.h>
#include <nuttx/fs/fs.h>
#include <nuttx/net/net.h>
-#include <nuttx/net/arp.h>
#include <nuttx/net/netdev.h>
+#include <nuttx/net/arp.h>
#include <nuttx/net/tcp.h>
#include "netdev/netdev.h"
diff --git a/nuttx/net/tcp/tcp_send_buffered.c b/nuttx/net/tcp/tcp_send_buffered.c
index c67f51632..3c2348615 100644
--- a/nuttx/net/tcp/tcp_send_buffered.c
+++ b/nuttx/net/tcp/tcp_send_buffered.c
@@ -64,9 +64,9 @@
#include <arch/irq.h>
#include <nuttx/clock.h>
#include <nuttx/net/net.h>
-#include <nuttx/net/arp.h>
#include <nuttx/net/iob.h>
#include <nuttx/net/netdev.h>
+#include <nuttx/net/arp.h>
#include <nuttx/net/tcp.h>
#include "socket/socket.h"
diff --git a/nuttx/net/tcp/tcp_send_unbuffered.c b/nuttx/net/tcp/tcp_send_unbuffered.c
index d0c02fb7d..aaa19c74c 100644
--- a/nuttx/net/tcp/tcp_send_unbuffered.c
+++ b/nuttx/net/tcp/tcp_send_unbuffered.c
@@ -53,8 +53,8 @@
#include <arch/irq.h>
#include <nuttx/clock.h>
#include <nuttx/net/net.h>
-#include <nuttx/net/arp.h>
#include <nuttx/net/netdev.h>
+#include <nuttx/net/arp.h>
#include <nuttx/net/tcp.h>
#include "netdev/netdev.h"