summaryrefslogtreecommitdiff
path: root/nuttx/net/arp
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net/arp')
-rw-r--r--nuttx/net/arp/arp_inout.c (renamed from nuttx/net/arp/uip_arp.c)28
-rw-r--r--nuttx/net/arp/arp_table.c (renamed from nuttx/net/arp/uip_arptab.c)22
-rw-r--r--nuttx/net/arp/arp_timer.c134
3 files changed, 159 insertions, 25 deletions
diff --git a/nuttx/net/arp/uip_arp.c b/nuttx/net/arp/arp_inout.c
index a58a1560a..78bebae6d 100644
--- a/nuttx/net/arp/uip_arp.c
+++ b/nuttx/net/arp/arp_inout.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * net/arp/uip_arp.c
+ * net/arp/arm_inout.c
* Implementation of the ARP Address Resolution Protocol.
*
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Based on uIP which also has a BSD style license:
@@ -65,7 +65,7 @@
#include <net/ethernet.h>
#include <nuttx/net/uip/uipopt.h>
#include <nuttx/net/uip/uip-arch.h>
-#include <nuttx/net/uip/uip-arp.h>
+#include <nuttx/net/arp.h>
#ifdef CONFIG_NET_ARP
@@ -155,7 +155,7 @@ static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
****************************************************************************/
#if defined(CONFIG_NET_DUMPARP) && defined(CONFIG_DEBUG)
-static void uip_arp_dump(struct arp_hdr_s *arp)
+static void arp_dump(struct arp_hdr_s *arp)
{
nlldbg(" HW type: %04x Protocol: %04x\n",
arp->ah_hwtype, arp->ah_protocol);\
@@ -173,7 +173,7 @@ static void uip_arp_dump(struct arp_hdr_s *arp)
arp->ah_dipaddr[1] & 0xff, arp->ah_dipaddr[1] >> 8);
}
#else
-# define uip_arp_dump(arp)
+# define arp_dump(arp)
#endif
/****************************************************************************
@@ -192,7 +192,7 @@ static void uip_arp_dump(struct arp_hdr_s *arp)
*/
#ifdef CONFIG_NET_ARP_IPIN
-void uip_arp_ipin(struct uip_driver_s *dev)
+void arp_ipin(struct uip_driver_s *dev)
{
in_addr_t srcipaddr;
@@ -203,7 +203,7 @@ void uip_arp_ipin(struct uip_driver_s *dev)
srcipaddr = uip_ip4addr_conv(IPBUF->eh_srcipaddr);
if (uip_ipaddr_maskcmp(srcipaddr, dev->d_ipaddr, dev->d_netmask))
{
- uip_arp_update(IPBUF->eh_srcipaddr, ETHBUF->src);
+ arp_update(IPBUF->eh_srcipaddr, ETHBUF->src);
}
}
#endif /* CONFIG_NET_ARP_IPIN */
@@ -229,7 +229,7 @@ void uip_arp_ipin(struct uip_driver_s *dev)
* variable d_len.
*/
-void uip_arp_arpin(struct uip_driver_s *dev)
+void arp_arpin(struct uip_driver_s *dev)
{
struct arp_hdr_s *parp = ARPBUF;
in_addr_t ipaddr;
@@ -260,7 +260,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
* with this host in the future.
*/
- uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
+ arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
parp->ah_opcode = HTONS(ARP_REPLY);
memcpy(parp->ah_dhwaddr, parp->ah_shwaddr, ETHER_ADDR_LEN);
@@ -271,7 +271,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
parp->ah_dipaddr[0] = parp->ah_sipaddr[0];
parp->ah_dipaddr[1] = parp->ah_sipaddr[1];
uiphdr_ipaddr_copy(parp->ah_sipaddr, &dev->d_ipaddr);
- uip_arp_dump(parp);
+ arp_dump(parp);
peth->type = HTONS(UIP_ETHTYPE_ARP);
dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
@@ -287,7 +287,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr))
{
- uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
+ arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
}
break;
}
@@ -318,7 +318,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
* buffer, and the length of the packet is in the field d_len.
*/
-void uip_arp_out(struct uip_driver_s *dev)
+void arp_out(struct uip_driver_s *dev)
{
const struct arp_entry *tabptr = NULL;
struct arp_hdr_s *parp = ARPBUF;
@@ -399,7 +399,7 @@ void uip_arp_out(struct uip_driver_s *dev)
/* Check if we already have this destination address in the ARP table */
- tabptr = uip_arp_find(ipaddr);
+ tabptr = arp_find(ipaddr);
if (!tabptr)
{
nllvdbg("ARP request for IP %04lx\n", (long)ipaddr);
@@ -421,7 +421,7 @@ void uip_arp_out(struct uip_driver_s *dev)
parp->ah_protocol = HTONS(UIP_ETHTYPE_IP);
parp->ah_hwlen = ETHER_ADDR_LEN;
parp->ah_protolen = 4;
- uip_arp_dump(parp);
+ arp_dump(parp);
peth->type = HTONS(UIP_ETHTYPE_ARP);
dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
diff --git a/nuttx/net/arp/uip_arptab.c b/nuttx/net/arp/arp_table.c
index 96a0f19b5..b4d7ac684 100644
--- a/nuttx/net/arp/uip_arptab.c
+++ b/nuttx/net/arp/arp_table.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * net/arp/uip_arptab.c
+ * net/arp/arp_table.c
* Implementation of the ARP Address Resolution Protocol.
*
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Based originally on uIP which also has a BSD style license:
@@ -55,7 +55,7 @@
#include <net/ethernet.h>
#include <nuttx/net/uip/uipopt.h>
#include <nuttx/net/uip/uip-arch.h>
-#include <nuttx/net/uip/uip-arp.h>
+#include <nuttx/net/arp.h>
#ifdef CONFIG_NET_ARP
@@ -85,7 +85,7 @@ static uint8_t g_arptime;
****************************************************************************/
/****************************************************************************
- * Name: uip_arp_init
+ * Name: arp_init
*
* Description:
* Initialize the ARP module. This function must be called before any of
@@ -93,7 +93,7 @@ static uint8_t g_arptime;
*
****************************************************************************/
-void uip_arp_init(void)
+void arp_init(void)
{
int i;
for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
@@ -103,7 +103,7 @@ void uip_arp_init(void)
}
/****************************************************************************
- * Name: uip_arp_timer
+ * Name: arp_timer
*
* Description:
* This function performs periodic timer processing in the ARP module
@@ -113,7 +113,7 @@ void uip_arp_init(void)
*
****************************************************************************/
-void uip_arp_timer(void)
+void arp_timer(void)
{
struct arp_entry *tabptr;
int i;
@@ -130,7 +130,7 @@ void uip_arp_timer(void)
}
/****************************************************************************
- * Name: uip_arp_update
+ * Name: arp_update
*
* Description:
* Add the IP/HW address mapping to the ARP table -OR- change the IP
@@ -145,7 +145,7 @@ void uip_arp_timer(void)
*
****************************************************************************/
-void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
+void arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
{
struct arp_entry *tabptr = NULL;
in_addr_t ipaddr = uip_ip4addr_conv(pipaddr);
@@ -225,7 +225,7 @@ void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
}
/****************************************************************************
- * Name: uip_arp_find
+ * Name: arp_find
*
* Description:
* Find the ARP entry corresponding to this IP address.
@@ -239,7 +239,7 @@ void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
*
****************************************************************************/
-struct arp_entry *uip_arp_find(in_addr_t ipaddr)
+struct arp_entry *arp_find(in_addr_t ipaddr)
{
struct arp_entry *tabptr;
int i;
diff --git a/nuttx/net/arp/arp_timer.c b/nuttx/net/arp/arp_timer.c
new file mode 100644
index 000000000..d6f105ac1
--- /dev/null
+++ b/nuttx/net/arp/arp_timer.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * net/arp/arp_timer.c
+ *
+ * Copyright (C) 2007-2009, 2011, 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <stdint.h>
+#include <time.h>
+#include <wdog.h>
+#include <debug.h>
+
+#include <nuttx/net/uip/uipopt.h>
+#include <nuttx/net/arp.h>
+
+#include "net_internal.h"
+
+#ifdef CONFIG_NET_ARP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* ARP timer interval = 10 seconds. CLK_TCK is the number of clock ticks
+ * per second
+ */
+
+#define ARPTIMER_WDINTERVAL (10*CLK_TCK)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static WDOG_ID g_arptimer; /* ARP timer */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: arptimer_poll
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void arptimer_poll(int argc, uint32_t arg, ...)
+{
+ /* Call the ARP timer function every 10 seconds. */
+
+ arp_timer();
+
+ /* Setup the watchdog timer again */
+
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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)
+{
+ /* Create and start the ARP timer */
+
+ g_arptimer = wd_create();
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+#endif /* CONFIG_NET_ARP */
+#endif /* CONFIG_NET */