From 6f33910a3b092e057e3e066603837784cd41b4e2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 21 Mar 2009 16:00:20 +0000 Subject: Expose more ARP APIs git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1633 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/include/net/uip/uip-arp.h | 223 ++++++++++++++++++++++++++++------- nuttx/include/netinet/arp.h | 110 +++++++++++++++++ nuttx/include/netinet/ether.h | 8 +- nuttx/include/netinet/ip6.h | 4 +- nuttx/include/nuttx/ioctl.h | 8 +- nuttx/net/netdev_ioctl.c | 7 ++ nuttx/net/uip/Make.defs | 6 +- nuttx/net/uip/uip_arp.c | 149 ++--------------------- nuttx/net/uip/uip_arptab.c | 253 ++++++++++++++++++++++++++++++++++++++++ 9 files changed, 573 insertions(+), 195 deletions(-) create mode 100644 nuttx/include/netinet/arp.h create mode 100644 nuttx/net/uip/uip_arptab.c diff --git a/nuttx/include/net/uip/uip-arp.h b/nuttx/include/net/uip/uip-arp.h index 52f742508..134293ece 100644 --- a/nuttx/include/net/uip/uip-arp.h +++ b/nuttx/include/net/uip/uip-arp.h @@ -1,13 +1,20 @@ -/* uip-arp.h +/**************************************************************************** + * include/net/uip/uip-arch.h * Macros and definitions for the ARP module. - * Author: Adam Dunkels * - * Copyright (c) 2001-2003, Adam Dunkels. - * All rights reserved. + * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Derived from uIP with has a similar BSD-styple license: + * + * Author: Adam Dunkels + * Copyright (c) 2001-2003, Adam Dunkels. + * All rights reserved. * * 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 @@ -29,16 +36,35 @@ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * - */ + ****************************************************************************/ #ifndef __UIP_ARP_H__ #define __UIP_ARP_H__ +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include #include #include #include #include +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Recognized values of the type bytes in the Ethernet header */ + +#define UIP_ETHTYPE_ARP 0x0806 +#define UIP_ETHTYPE_IP 0x0800 +#define UIP_ETHTYPE_IP6 0x86dd + +/**************************************************************************** + * Public Types + ****************************************************************************/ + /* The Ethernet header -- 14 bytes. The first two fields are type 'struct * ether_addr but are represented as a simple byte array here because * some compilers refuse to pack 6 byte structures. @@ -51,55 +77,164 @@ struct uip_eth_hdr uint16 type; /* Type code (2 bytes) */ }; -/* Recognized values of the type bytes in the Ethernet header */ +/* One entry in the ARP table (volatile!) */ -#define UIP_ETHTYPE_ARP 0x0806 -#define UIP_ETHTYPE_IP 0x0800 -#define UIP_ETHTYPE_IP6 0x86dd +struct arp_entry +{ + in_addr_t at_ipaddr; /* IP address */ + struct ether_addr at_ethaddr; /* Hardware address */ + uint8 at_time; +}; -/* The uip_arp_init() function must be called before any of the other - * ARP functions. - */ +/**************************************************************************** + * Public Data + ****************************************************************************/ -void uip_arp_init(void); +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif -/* The uip_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. - */ +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_arp_init + * + * Description: + * Initialize the ARP module. This function must be called before any of + * the other ARP functions. + * + ****************************************************************************/ + +EXTERN void uip_arp_init(void); + +/**************************************************************************** + * Name: uip_arp_init + * + * Description: + * The uip_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. + * + ****************************************************************************/ #define uip_arp_ipin() -/* The uip_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 - * uip_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. - */ +/**************************************************************************** + * Name: uip_arp_arpin + * + * Description: + * The uip_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 + * uip_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. + * + ****************************************************************************/ -void uip_arp_arpin(struct uip_driver_s *dev); - -/* The uip_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. - */ +EXTERN void uip_arp_arpin(struct uip_driver_s *dev); -void uip_arp_out(struct uip_driver_s *dev); +/**************************************************************************** + * Name: uip_arp_arpin + * + * Description: + * The uip_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. + * + ****************************************************************************/ -/* The uip_arp_timer() function should be called every ten seconds. It - * is responsible for flushing old entries in the ARP table. - */ +EXTERN void uip_arp_out(struct uip_driver_s *dev); + +/**************************************************************************** + * Name: uip_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. + * + ****************************************************************************/ + +EXTERN void uip_arp_timer(void); + +/**************************************************************************** + * Name: uip_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[2] in network order + * ethaddr - Refers to a HW address uint8[IFHWADDRLEN] + * + * Assumptions + * Interrupts are disabled + * + ****************************************************************************/ + +EXTERN void uip_arp_update(uint16 *pipaddr, uint8 *ethaddr); + +/**************************************************************************** + * Name: uip_arp_find + * + * Description: + * Find the ARP entry corresponding to this IP address. + * + * Input parameters: + * ipaddr - Refers to an IP address in network order + * + * Assumptions + * Interrupts are disabled; Returned value will become unstable when + * interrupts are re-enabled or if any other uIP APIs are called. + * + ****************************************************************************/ + +EXTERN struct arp_entry *uip_arp_find(in_addr_t ipaddr); -void uip_arp_timer(void); + +/**************************************************************************** + * Name: uip_arp_delete + * + * Description: + * Remove an IP association from the ARP table + * + * Input parameters: + * ipaddr - Refers to an IP address in network order + * + * Assumptions + * Interrupts are disabled + * + ****************************************************************************/ + +#define uip_arp_delete(ipaddr) \ +{ \ + struct arp_entry *tabptr = uip_arp_find(ipaddr); \ + if (tabptr) \ + { \ + tabptr->at_ipaddr = 0; \ + } \ +} + +#undef EXTERN +#ifdef __cplusplus +} +#endif #endif /* __UIP_ARP_H__ */ diff --git a/nuttx/include/netinet/arp.h b/nuttx/include/netinet/arp.h new file mode 100644 index 000000000..908f5790a --- /dev/null +++ b/nuttx/include/netinet/arp.h @@ -0,0 +1,110 @@ +/**************************************************************************** + * netinet/arp.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 __NETINET_ARP_H +#define __NETINET_ARP_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Public Definitions + ****************************************************************************/ + +/* Three ioctls are available on all PF_INET sockets, but only if the NuttX + * configuration CONFIG_NET_ARPIOCTLS is defined. Each ioctl takes a pointer + * to a 'struct arpreq' as its parameter. + */ + +#define SIOCSARP _ARPIOC(1) /* Set a ARP mapping */ +#define SIOCDARP _ARPIOC(2) /* Delete an ARP mapping */ +#define SIOCGARP _ARPIOC(3) /* Get an ARP mapping */ + +/* Values for the FLAGS field in struct arpreq */ + +#define ATF_COM 0x01 /* Lookup complete */ +#define ATF_PERM 0x02 /* Permanent entry */ +#define ATF_PUBL 0x04 /* Publish entry */ +#define ATF_USETRAILERS 0x10 /* Trailers requested */ +#define ATF_NETMASK 0x20 /* Use a netmask */ +#define ATF_DONTPUB 0x40 /* Don't answer */ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/* All ARP ioctls take a pointer to a struct arpreq as their parameter: */ + +struct arpreq +{ + struct sockaddr arp_pa; /* Protocol address */ + struct sockaddr arp_ha; /* Hardware address */ + struct sockaddr arp_netmask; /* Netmask of protocol address */ + ubyte arp_flags; /* Flags */ + ubyte arp_dev[IFNAMSIZ+1]; /* Device name (zero terminated)*/ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/* If CONFIG_NET_ARPIOCTLS is defined then the semi-standard ioctl commands + * described above are supported. If not, you can call the uIP ARP interfaces + * directly in a very non-standard way. See include/net/uip/uip-arp.h for + * prototypes. + */ + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __NETINET_ARP_H */ diff --git a/nuttx/include/netinet/ether.h b/nuttx/include/netinet/ether.h index 335fd56bf..3cd2d3ad4 100644 --- a/nuttx/include/netinet/ether.h +++ b/nuttx/include/netinet/ether.h @@ -1,7 +1,7 @@ /**************************************************************************** * netinet/ether.h * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. - * 3. Neither the name Gregory Nutt nor the names of its contributors may be + * 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. * @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __NETINET_ETHER_H -#define __NETINET_ETHER_H +#ifndef __NETINET_ETHER_H +#define __NETINET_ETHER_H /**************************************************************************** * Included Files diff --git a/nuttx/include/netinet/ip6.h b/nuttx/include/netinet/ip6.h index cc6a5295c..c8c0e22e3 100644 --- a/nuttx/include/netinet/ip6.h +++ b/nuttx/include/netinet/ip6.h @@ -1,7 +1,7 @@ /**************************************************************************** * netinet/ip6.h * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. - * 3. Neither the name Gregory Nutt nor the names of its contributors may be + * 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. * diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h index 49d9ca48e..7d35548b2 100644 --- a/nuttx/include/nuttx/ioctl.h +++ b/nuttx/include/nuttx/ioctl.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/ioctl.h * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -56,6 +56,7 @@ #define _DIOCBASE (0x8800) /* Character driver ioctl commands */ #define _BIOCBASE (0x8900) /* Block driver ioctl commands */ #define _SIOCBASE (0x8a00) /* Socket ioctl commandss */ +#define _ARPBASE (0x8b00) /* ARP ioctl commandss */ /* Macros used to manage ioctl commands */ @@ -100,6 +101,11 @@ * return (void*) base address * of device memory */ +/* NuttX ARP driver ioctl definitions (see netinet/arp.h) */ + +#define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPBASE) +#define _ARPIOC(nr) _IOC(_ARPBASE,nr) + /**************************************************************************** * Public Type Definitions ****************************************************************************/ diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c index 950d4e21d..f690b335e 100644 --- a/nuttx/net/netdev_ioctl.c +++ b/nuttx/net/netdev_ioctl.c @@ -253,6 +253,13 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req) err = ENOSYS; goto errout; +#ifdef CONFIG_NET_ARPIOCTLS + case SIOCSARP: /* Set a ARP mapping */ + case SIOCDARP: /* Delete an ARP mapping */ + case SIOCGARP: /* Get an ARP mapping */ +# error "IOCTL Commands not implemented" +#endif + default: err = EINVAL; goto errout; diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs index 234e6a9bc..e67c73243 100644 --- a/nuttx/net/uip/Make.defs +++ b/nuttx/net/uip/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # Make.defs # -# Copyright (C) 2007 Gregory Nutt. All rights reserved. +# Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -40,8 +40,8 @@ ifeq ($(CONFIG_NET),y) # Common IP source files -UIP_CSRCS += uip_initialize.c uip_setipid.c uip_arp.c uip_input.c uip_send.c \ - uip_poll.c uip_chksum.c uip_callback.c +UIP_CSRCS += uip_initialize.c uip_setipid.c uip_arp.c uip_arptab.c uip_input.c \ + uip_send.c uip_poll.c uip_chksum.c uip_callback.c ifeq ($(CONFIG_NET_IPv6),y) UIP_CSRCS += uip_neighbor.c diff --git a/nuttx/net/uip/uip_arp.c b/nuttx/net/uip/uip_arp.c index 47ac8ba7f..2f2c729d3 100644 --- a/nuttx/net/uip/uip_arp.c +++ b/nuttx/net/uip/uip_arp.c @@ -115,13 +115,6 @@ struct ethip_hdr uint16 eh_ipoption[2]; /* (optional) */ }; -struct arp_entry -{ - in_addr_t at_ipaddr; - struct ether_addr at_ethaddr; - uint8 at_time; -}; - /**************************************************************************** * Private Data ****************************************************************************/ @@ -152,11 +145,6 @@ static const uint16 g_broadcast_ipaddr[2] = {0xffff, 0xffff}; static const ubyte g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e}; #endif -/* The table of known address mappings */ - -static struct arp_entry g_arptable[CONFIG_NET_ARPTAB_SIZE]; -static uint8 g_arptime; - /**************************************************************************** * Private Functions ****************************************************************************/ @@ -183,122 +171,10 @@ static void uip_arp_dump(struct arp_hdr *arp) # define uip_arp_dump(arp) #endif -static void uip_arp_update(uint16 *pipaddr, uint8 *ethaddr) -{ - struct arp_entry *tabptr = NULL; - in_addr_t ipaddr = uip_ip4addr_conv(pipaddr); - int i; - - /* Walk through the ARP mapping table and try to find an entry to - * update. If none is found, the IP -> MAC address mapping is - * inserted in the ARP table. - */ - - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - tabptr = &g_arptable[i]; - - /* Only check those entries that are actually in use. */ - - if (tabptr->at_ipaddr != 0) - { - /* Check if the source IP address of the incoming packet matches - * the IP address in this ARP table entry. - */ - - if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) - { - /* An old entry found, update this and return. */ - memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN); - tabptr->at_time = g_arptime; - - return; - } - } - } - - /* If we get here, no existing ARP table entry was found, so we - create one. */ - - /* First, we try to find an unused entry in the ARP table. */ - - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - tabptr = &g_arptable[i]; - if (tabptr->at_ipaddr == 0) - { - break; - } - } - - /* If no unused entry is found, we try to find the oldest entry and - * throw it away. - */ - - if (i == CONFIG_NET_ARPTAB_SIZE) - { - uint8 tmpage = 0; - int j = 0; - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - tabptr = &g_arptable[i]; - if (g_arptime - tabptr->at_time > tmpage) - { - tmpage = g_arptime - tabptr->at_time; - j = i; - } - } - i = j; - tabptr = &g_arptable[i]; - } - - /* Now, i is the ARP table entry which we will fill with the new - * information. - */ - - tabptr->at_ipaddr = ipaddr; - memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN); - tabptr->at_time = g_arptime; -} - /**************************************************************************** * Public Functions ****************************************************************************/ -/* Initialize the ARP module. */ - -void uip_arp_init(void) -{ - int i; - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - memset(&g_arptable[i].at_ipaddr, 0, sizeof(in_addr_t)); - } -} - -/* Periodic ARP processing function. - * - * 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. - */ - -void uip_arp_timer(void) -{ - struct arp_entry *tabptr; - int i; - - ++g_arptime; - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - tabptr = &g_arptable[i]; - if (tabptr->at_ipaddr != 0 && g_arptime - tabptr->at_time >= UIP_ARP_MAXAGE) - { - tabptr->at_ipaddr = 0; - } - } -} - /* ARP processing for incoming ARP packets. * * This function should be called by the device driver when an ARP @@ -410,13 +286,12 @@ void uip_arp_arpin(struct uip_driver_s *dev) void uip_arp_out(struct uip_driver_s *dev) { - struct arp_entry *tabptr = NULL; - struct arp_hdr *parp = ARPBUF; - struct uip_eth_hdr *peth = ETHBUF; - struct ethip_hdr *pip = IPBUF; - in_addr_t ipaddr; - in_addr_t destipaddr; - int i; + const struct arp_entry *tabptr = NULL; + struct arp_hdr *parp = ARPBUF; + struct uip_eth_hdr *peth = ETHBUF; + struct ethip_hdr *pip = IPBUF; + in_addr_t ipaddr; + in_addr_t destipaddr; /* Find the destination IP address in the ARP table and construct * the Ethernet header. If the destination IP addres isn't on the @@ -478,16 +353,8 @@ void uip_arp_out(struct uip_driver_s *dev) /* Check if we already have this destination address in the ARP table */ - for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) - { - tabptr = &g_arptable[i]; - if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) - { - break; - } - } - - if (i == CONFIG_NET_ARPTAB_SIZE) + tabptr = uip_arp_find(ipaddr); + if (!tabptr) { nvdbg("ARP request for IP %04lx\n", (long)ipaddr); diff --git a/nuttx/net/uip/uip_arptab.c b/nuttx/net/uip/uip_arptab.c new file mode 100644 index 000000000..9c0ad6c4d --- /dev/null +++ b/nuttx/net/uip/uip_arptab.c @@ -0,0 +1,253 @@ +/**************************************************************************** + * net/uip/uip_arptab.c + * Implementation of the ARP Address Resolution Protocol. + * + * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Based originally on uIP which also has a BSD style license: + * + * Author: Adam Dunkels + * Copyright (c) 2001-2003, Adam Dunkels. + * All rights reserved. + * + * 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. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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 +#ifdef CONFIG_NET + +#include +#include + +#include +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* The table of known address mappings */ + +static struct arp_entry g_arptable[CONFIG_NET_ARPTAB_SIZE]; +static uint8 g_arptime; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_arp_init + * + * Description: + * Initialize the ARP module. This function must be called before any of + * the other ARP functions. + * + ****************************************************************************/ + +void uip_arp_init(void) +{ + int i; + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + memset(&g_arptable[i].at_ipaddr, 0, sizeof(in_addr_t)); + } +} + +/**************************************************************************** + * Name: uip_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 uip_arp_timer(void) +{ + struct arp_entry *tabptr; + int i; + + ++g_arptime; + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + tabptr = &g_arptable[i]; + if (tabptr->at_ipaddr != 0 && g_arptime - tabptr->at_time >= UIP_ARP_MAXAGE) + { + tabptr->at_ipaddr = 0; + } + } +} + +/**************************************************************************** + * Name: uip_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[2] + * ethaddr - Refers to a HW address uint8[IFHWADDRLEN] + * + * Assumptions + * Interrupts are disabled + * + ****************************************************************************/ + +void uip_arp_update(uint16 *pipaddr, uint8 *ethaddr) +{ + struct arp_entry *tabptr = NULL; + in_addr_t ipaddr = uip_ip4addr_conv(pipaddr); + int i; + + /* Walk through the ARP mapping table and try to find an entry to + * update. If none is found, the IP -> MAC address mapping is + * inserted in the ARP table. + */ + + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + tabptr = &g_arptable[i]; + + /* Only check those entries that are actually in use. */ + + if (tabptr->at_ipaddr != 0) + { + /* Check if the source IP address of the incoming packet matches + * the IP address in this ARP table entry. + */ + + if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) + { + /* An old entry found, update this and return. */ + + memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN); + tabptr->at_time = g_arptime; + return; + } + } + } + + /* If we get here, no existing ARP table entry was found, so we create one. */ + + /* First, we try to find an unused entry in the ARP table. */ + + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + tabptr = &g_arptable[i]; + if (tabptr->at_ipaddr == 0) + { + break; + } + } + + /* If no unused entry is found, we try to find the oldest entry and + * throw it away. + */ + + if (i == CONFIG_NET_ARPTAB_SIZE) + { + uint8 tmpage = 0; + int j = 0; + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + tabptr = &g_arptable[i]; + if (g_arptime - tabptr->at_time > tmpage) + { + tmpage = g_arptime - tabptr->at_time; + j = i; + } + } + i = j; + tabptr = &g_arptable[i]; + } + + /* Now, i is the ARP table entry which we will fill with the new + * information. + */ + + tabptr->at_ipaddr = ipaddr; + memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN); + tabptr->at_time = g_arptime; +} + +/**************************************************************************** + * Name: uip_arp_find + * + * Description: + * Find the ARP entry corresponding to this IP address. + * + * Input parameters: + * ipaddr - Refers to an IP addressin network order + * + * Assumptions + * Interrupts are disabled; Returned value will become unstable when + * interrupts are re-enabled or if any other uIP APIs are called. + * + ****************************************************************************/ + +struct arp_entry *uip_arp_find(in_addr_t ipaddr) +{ + struct arp_entry *tabptr; + int i; + + for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i) + { + tabptr = &g_arptable[i]; + if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) + { + return tabptr; + } + } + return NULL; +} + +#endif /* CONFIG_NET */ -- cgit v1.2.3