summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-07-11 15:17:11 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-07-11 15:17:11 +0000
commit7a7b211c40caa734799e2973b62d6f582071a051 (patch)
tree3b9f2a939d846761f4d35034eec43749dd313732 /nuttx/net
parent045b0affc951ce0a37ddfe3dae1b212fcd87bd81 (diff)
downloadpx4-nuttx-7a7b211c40caa734799e2973b62d6f582071a051.tar.gz
px4-nuttx-7a7b211c40caa734799e2973b62d6f582071a051.tar.bz2
px4-nuttx-7a7b211c40caa734799e2973b62d6f582071a051.zip
Add support for multicast MAC addresses
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2784 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip_arp.c4
-rwxr-xr-xnuttx/net/uip/uip_igmpinit.c4
-rwxr-xr-xnuttx/net/uip/uip_igmpjoin.c2
-rwxr-xr-xnuttx/net/uip/uip_igmpleave.c2
-rw-r--r--nuttx/net/uip/uip_input.c2
-rw-r--r--nuttx/net/uip/uip_internal.h5
-rwxr-xr-xnuttx/net/uip/uip_mcastmac.c132
8 files changed, 143 insertions, 10 deletions
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index f113ec3a7..ec0b06fb8 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -82,7 +82,7 @@ endif
ifeq ($(CONFIG_NET_IGMP),y)
UIP_CSRCS += uip_igmpinit.c uip_igmpgroup.c uip_igmpinput.c uip_igmpjoin.c \
- uip_igmpleave.c uip_igmpmsg.c uip_igmptimer.c
+ uip_igmpleave.c uip_igmpmsg.c uip_igmptimer.c uip_mcastmac.c
endif
endif
diff --git a/nuttx/net/uip/uip_arp.c b/nuttx/net/uip/uip_arp.c
index 6073f252c..b0e3e3fe7 100644
--- a/nuttx/net/uip/uip_arp.c
+++ b/nuttx/net/uip/uip_arp.c
@@ -140,7 +140,7 @@ static const uint16_t g_broadcast_ipaddr[2] = {0xffff, 0xffff};
* The following is the first three octects of the IGMP address:
*/
-#if defined(CONFIG_NET_MULTICAST) && !defined(CONFIG_NET_IPv6)
+#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
#endif
@@ -306,7 +306,7 @@ void uip_arp_out(struct uip_driver_s *dev)
{
memcpy(peth->dest, g_broadcast_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
}
-#if defined(CONFIG_NET_MULTICAST) && !defined(CONFIG_NET_IPv6)
+#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
/* Check if the destination address is a multicast address
*
* - IPv4: multicast addresses lie in the class D group -- The address range
diff --git a/nuttx/net/uip/uip_igmpinit.c b/nuttx/net/uip/uip_igmpinit.c
index 5c1dbdc68..c3c379904 100755
--- a/nuttx/net/uip/uip_igmpinit.c
+++ b/nuttx/net/uip/uip_igmpinit.c
@@ -119,8 +119,8 @@ void uip_igmpdevinit(struct uip_driver_s *dev)
/* Allow the IGMP messages at the MAC level */
- uip_igmpmac(dev, &g_allrouters, true);
- uip_igmpmac(dev, &g_allsystems, true);
+ uip_addmcastmac(dev, &g_allrouters);
+ uip_addmcastmac(dev, &g_allsystems);
}
#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpjoin.c b/nuttx/net/uip/uip_igmpjoin.c
index 3f0224a92..b644cad10 100755
--- a/nuttx/net/uip/uip_igmpjoin.c
+++ b/nuttx/net/uip/uip_igmpjoin.c
@@ -146,7 +146,7 @@ void igmp_joingroup(struct uip_driver_s *dev, uip_ipaddr_t *grpaddr)
/* Add the group (MAC) address to the ether drivers MAC filter list */
- uip_igmpmac(dev, grpaddr, true);
+ uip_addmcastmac(dev, grpaddr);
}
}
diff --git a/nuttx/net/uip/uip_igmpleave.c b/nuttx/net/uip/uip_igmpleave.c
index a220662fd..a482c5c4a 100755
--- a/nuttx/net/uip/uip_igmpleave.c
+++ b/nuttx/net/uip/uip_igmpleave.c
@@ -166,7 +166,7 @@ void igmp_leavegroup(struct uip_driver_s *dev, uip_ipaddr_t *grpaddr)
/* And remove the group address from the ethernet drivers MAC filter set */
- uip_igmpmac(dev, grpaddr, false);
+ uip_removemcastmac(dev, grpaddr);
}
}
diff --git a/nuttx/net/uip/uip_input.c b/nuttx/net/uip/uip_input.c
index 6a8963f38..05fc358be 100644
--- a/nuttx/net/uip/uip_input.c
+++ b/nuttx/net/uip/uip_input.c
@@ -434,7 +434,7 @@ void uip_input(struct uip_driver_s *dev)
}
}
- /* Check if the pack is destined for out IP address */
+ /* Check if the packet is destined for out IP address */
else
#endif
{
diff --git a/nuttx/net/uip/uip_internal.h b/nuttx/net/uip/uip_internal.h
index 49ab4ea24..cfa9da85d 100644
--- a/nuttx/net/uip/uip_internal.h
+++ b/nuttx/net/uip/uip_internal.h
@@ -250,9 +250,10 @@ EXTERN void uip_igmpstartticks(FAR struct igmp_group_s *group, int ticks);
EXTERN void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs);
EXTERN bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks);
-/* Defined in TBD ************************************************************/
+/* Defined in uip_mcastmac ***************************************************/
-EXTERN void uip_igmpmac(struct uip_driver_s *dev, uip_ipaddr_t *ip, bool on);
+EXTERN void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
+EXTERN void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_mcastmac.c b/nuttx/net/uip/uip_mcastmac.c
new file mode 100755
index 000000000..be0e21513
--- /dev/null
+++ b/nuttx/net/uip/uip_mcastmac.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * net/uip/uip_mcastmac.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
+ * lwIP TCP/IP stack by Steve Reynolds:
+ *
+ * Copyright (c) 2002 CITEL Technologies Ltd.
+ * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <assert.h>
+#include <debug.h>
+
+#include <net/uip/uipopt.h>
+#include <net/uip/uip.h>
+
+#include "uip_internal.h"
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_mcastmac
+ *
+ * Description:
+ * Given an IP address (in network order), create a IGMP multicast MAC
+ * address.
+ *
+ ****************************************************************************/
+
+static void uip_mcastmac(uip_ipaddr_t *ip, FAR uint8_t *mac)
+{
+ /* This mapping is from the IETF IN RFC 1700 */
+
+ mac[0] = 0x01;
+ mac[1] = 0x00;
+ mac[2] = 0x5e;
+ mac[3] = ip4_addr2(*ip) & 0x7f;
+ mac[4] = ip4_addr3(*ip);
+ mac[5] = ip4_addr4(*ip);
+
+ nvdbg("IP: %04x -> MAC: %02%02%02%02%02%02\n",
+ *ip, mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_addmcastmac
+ *
+ * Description:
+ * Add an IGMP MAC address to the device's MAC filter table.
+ *
+ ****************************************************************************/
+
+void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
+{
+ uint8_t mcastmac[6];
+
+ nvdbg("Adding: IP %04x\n");
+ if (dev->d_addmac)
+ {
+ uip_mcastmac(ip, mcastmac);
+ dev->d_addmac(dev, mcastmac);
+ }
+}
+
+/****************************************************************************
+ * Name: uip_removemcastmac
+ *
+ * Description:
+ * Remove an IGMP MAC address from the device's MAC filter table.
+ *
+ ****************************************************************************/
+
+void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
+{
+ uint8_t mcastmac[6];
+
+ nvdbg("Removing: IP %04x\n");
+ if (dev->d_rmmac)
+ {
+ uip_mcastmac(ip, mcastmac);
+ dev->d_rmmac(dev, mcastmac);
+ }
+}
+
+#endif /* CONFIG_NET_IGMP */