summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/fs/fs_ioctl.c4
-rw-r--r--nuttx/include/net/ioctls.h5
-rwxr-xr-xnuttx/include/net/uip/igmp.h86
-rwxr-xr-xnuttx/include/net/uip/ipmsfilter.h101
-rwxr-xr-xnuttx/include/net/uip/uip-igmp.h6
-rw-r--r--nuttx/include/netinet/in.h7
-rw-r--r--nuttx/include/nuttx/net.h5
-rwxr-xr-xnuttx/include/sys/sockio.h120
-rw-r--r--nuttx/net/netdev_ioctl.c208
-rwxr-xr-xnuttx/net/uip/uip_igmpgroup.c9
-rwxr-xr-xnuttx/net/uip/uip_igmpjoin.c12
-rwxr-xr-xnuttx/net/uip/uip_igmpleave.c10
-rw-r--r--nuttx/net/uip/uip_internal.h6
-rw-r--r--nuttx/netutils/uiplib/Make.defs6
-rwxr-xr-xnuttx/netutils/uiplib/uip_ipmsfilter.c113
15 files changed, 544 insertions, 154 deletions
diff --git a/nuttx/fs/fs_ioctl.c b/nuttx/fs/fs_ioctl.c
index 350feff00..79362c34f 100644
--- a/nuttx/fs/fs_ioctl.c
+++ b/nuttx/fs/fs_ioctl.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_ioctl.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -103,7 +103,7 @@ int ioctl(int fd, int req, unsigned long arg)
#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
if ((unsigned int)fd < (CONFIG_NFILE_DESCRIPTORS+CONFIG_NSOCKET_DESCRIPTORS))
{
- return netdev_ioctl(fd, req, (struct ifreq*)arg);
+ return netdev_ioctl(fd, req, arg);
}
else
#endif
diff --git a/nuttx/include/net/ioctls.h b/nuttx/include/net/ioctls.h
index 2395c1787..7bb6c18b3 100644
--- a/nuttx/include/net/ioctls.h
+++ b/nuttx/include/net/ioctls.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/net/ioctls.h
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,6 +68,9 @@
#define SIOCDIFADDR _SIOC(0x000c) /* Delete IP address */
#define SIOCGIFCOUNT _SIOC(0x000d) /* Get number of devices */
+#define SIOCGIPMSFILTER _SIOC(0x000e) /* Retrieve source filter addresses */
+#define SIOCSIPMSFILTER _SIOC(0x000f) /* Set source filter content */
+
/****************************************************************************
* Type Definitions
****************************************************************************/
diff --git a/nuttx/include/net/uip/igmp.h b/nuttx/include/net/uip/igmp.h
deleted file mode 100755
index 8b28b2fed..000000000
--- a/nuttx/include/net/uip/igmp.h
+++ /dev/null
@@ -1,86 +0,0 @@
-/****************************************************************************
- * net/uip/igmp.h
- * User interface to IGMP
- *
- * 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.
- *
- ****************************************************************************/
-
-#ifndef __NET_UIP_IGMP_H
-#define __NET_UIP_IGMP_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <netinet/in.h>
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#ifdef CONFIG_NET_IPv6
-# error "IGMP for IPv6 not supported"
-#endif
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-EXTERN void igmp_joingroup(const FAR struct in_addr *grpaddr);
-EXTERN void igmp_leavegroup(const FAR struct in_addr *grpaddr);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* CONFIG_NET_IGMP */
-#endif /* __NET_UIP_IGMP_H */
diff --git a/nuttx/include/net/uip/ipmsfilter.h b/nuttx/include/net/uip/ipmsfilter.h
new file mode 100755
index 000000000..df792d50b
--- /dev/null
+++ b/nuttx/include/net/uip/ipmsfilter.h
@@ -0,0 +1,101 @@
+/****************************************************************************
+ * net/uip/ipmsfilter.h
+ * User interface to add/remove IP multicast address
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_UIP_IPMSFILTER_H
+#define __NET_UIP_IPMSFILTER_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <netinet/in.h>
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+# error "IGMP for IPv6 not supported"
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ipmsfilter
+ *
+ * Description:
+ * Add or remove an IP address from a multicast filter set.
+ * (See netutils/uiplib/uip_ipmsfilter.c)
+ *
+ * Parameters:
+ * ifname The name of the interface to use, size must less than IMSFNAMSIZ
+ * multiaddr Multicast group address to add/remove
+ * fmode MCAST_INCLUDE: Add multicast address
+ * MCAST_EXCLUDE: Remove multicast address
+ *
+ * Return:
+ * 0 on sucess; Negated errno on failure
+ *
+ ****************************************************************************/
+
+EXTERN int ipmsfilter(FAR const char *ifname,
+ FAR const struct in_addr *multiaddr,
+ uint32_t fmode);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* CONFIG_NET_IGMP */
+#endif /* __NET_UIP_IPMSFILTER_H */
diff --git a/nuttx/include/net/uip/uip-igmp.h b/nuttx/include/net/uip/uip-igmp.h
index 00c017372..e57d8b438 100755
--- a/nuttx/include/net/uip/uip-igmp.h
+++ b/nuttx/include/net/uip/uip-igmp.h
@@ -225,8 +225,8 @@ extern "C" {
#define EXTERN extern
#endif
-extern uip_ipaddr_t g_allsystems;
-extern uip_ipaddr_t g_allrouters;
+EXTERN uip_ipaddr_t g_allsystems;
+EXTERN uip_ipaddr_t g_allrouters;
/****************************************************************************
* Public Function Prototypes
@@ -242,6 +242,8 @@ extern uip_ipaddr_t g_allrouters;
****************************************************************************/
EXTERN void uip_igmpdevinit(struct uip_driver_s *dev);
+EXTERN int igmp_joingroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr);
+EXTERN int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/netinet/in.h b/nuttx/include/netinet/in.h
index 9c38b229b..2b92bba7f 100644
--- a/nuttx/include/netinet/in.h
+++ b/nuttx/include/netinet/in.h
@@ -1,7 +1,7 @@
/****************************************************************************
* netinet/in.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -54,6 +54,11 @@
#define IPPROTO_TCP 1
#define IPPROTO_UDP 2
+/* Values used with SIOCSIFMCFILTER and SIOCGIFMCFILTER ioctl's */
+
+#define MCAST_EXCLUDE 0
+#define MCAST_INCLUDE 1
+
/* Special values of in_addr_t */
#define INADDR_ANY ((in_addr_t)0x00000000) /* Address to accept any incoming messages */
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index 7258b9984..d9b4e42b3 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -1,7 +1,7 @@
/****************************************************************************
* nuttx/net.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -153,8 +153,7 @@ EXTERN int net_close(int sockfd);
* to this function.
*/
-struct ifreq; /* Forward reference -- see net/ioctls.h */
-EXTERN int netdev_ioctl(int sockfd, int cmd, struct ifreq *req);
+EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
/* net_poll.c ****************************************************************/
/* The standard poll() operation redirects operations on socket descriptors
diff --git a/nuttx/include/sys/sockio.h b/nuttx/include/sys/sockio.h
new file mode 100755
index 000000000..a63833756
--- /dev/null
+++ b/nuttx/include/sys/sockio.h
@@ -0,0 +1,120 @@
+/****************************************************************************
+ * include/sys/sockio.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 __SYS_SOCKIO_H
+#define __SYS_SOCKIO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Get NuttX configuration and NuttX-specific network IOCTL definitions */
+
+#include <nuttx/config.h>
+#include <nuttx/ioctl.h>
+#include <net/ioctls.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#define IMSFNAMSIZ 8
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+ /* RFC3678: IPv4 Options
+ *
+ * o ioctl() SIOCGIPMSFILTER: to retrieve the list of source addresses
+ * that comprise the source filter along with the current filter mode.
+ *
+ * o ioctl() SIOCSIPMSFILTER: to set or modify the source filter content
+ * (e.g., unicast source address list) or mode (exclude or include).
+ *
+ * Ioctl option Argument type
+ * ----------------------------- ----------------------
+ * SIOCGIPMSFILTER struct ip_msfilter
+ * SIOCSIPMSFILTER struct ip_msfilter
+ *
+ * The imsf_fmode mode is a 32-bit integer that identifies the filter
+ * mode. The value of this field must be either MCAST_INCLUDE or
+ * MCAST_EXCLUDE, which are likewise defined in <netinet/in.h>.
+ */
+
+#if 0 /* REVISIT: Current NuttX implementation is non-standard.
+ * Lookup is by device name, not IP address.
+ */
+
+struct ip_msfilter
+{
+ struct in_addr imsf_multiaddr; /* IP multicast address of group */
+ struct in_addr imsf_interface; /* Local IP address of interface */
+ uint32_t imsf_fmode; /* Filter mode */
+#ifdef CONFIG_NET_IGMPv3
+ uint32_t imsf_numsrc; /* number of sources in src_list */
+ struct in_addr imsf_slist[1]; /* start of source list */
+#endif
+};
+
+#else
+
+struct ip_msfilter
+{
+ char imsf_name[IMSFNAMSIZ]; /* Network device name, e.g., "eth0" */
+ struct in_addr imsf_multiaddr; /* IP multicast address of group */
+ uint32_t imsf_fmode; /* Filter mode */
+};
+
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __SYS_SOCKIO_H */
diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c
index 228ead30c..b5828ed3f 100644
--- a/nuttx/net/netdev_ioctl.c
+++ b/nuttx/net/netdev_ioctl.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/netdev_ioctl.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,6 +44,7 @@
#include <sys/ioctl.h>
#include <string.h>
+#include <assert.h>
#include <errno.h>
#include <debug.h>
@@ -54,6 +55,11 @@
#include <net/uip/uip-arch.h>
#include <net/uip/uip.h>
+#ifdef CONFIG_NET_IGMP
+# include "sys/sockio.h"
+# include "net/uip/uip-igmp.h"
+#endif
+
#include "net_internal.h"
/****************************************************************************
@@ -130,57 +136,27 @@ static inline void ioctl_ifdown(FAR struct uip_driver_s *dev)
}
/****************************************************************************
- * Global Functions
- ****************************************************************************/
-
-/****************************************************************************
* Name: netdev_ioctl
*
* Description:
* Perform network device specific operations.
*
* Parameters:
- * sockfd Socket descriptor of device
+ * psock Socket structure
+ * dev Ethernet driver device structure
* cmd The ioctl command
* req The argument of the ioctl cmd
*
* Return:
* >=0 on success (positive non-zero values are cmd-specific)
- * -1 on failure withi errno set properly:
- *
- * EBADF
- * 'sockfd' is not a valid descriptor.
- * EFAULT
- * 'req' references an inaccessible memory area.
- * EINVAL
- * 'cmd' or 'req' is not valid.
- * ENOTTY
- * 'sockfd' is not associated with a network device.
- * ENOTTY
- * The specified request does not apply to the kind of object that the
- * descriptor 'sockfd' references.
+ * Negated errno returned on failure.
*
****************************************************************************/
-int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
+static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req)
{
- FAR struct socket *psock = sockfd_socket(sockfd);
FAR struct uip_driver_s *dev;
- int err;
-
- if (!_SIOCVALID(cmd) || !req)
- {
- err = EINVAL;
- goto errout;
- }
-
- /* Verify that the sockfd corresponds to valid, allocated socket */
-
- if (!psock || psock->s_crefs <= 0)
- {
- err = EBADF;
- goto errout;
- }
+ int ret = OK;
/* Find the network device associated with the device name
* in the request data.
@@ -189,7 +165,7 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
dev = netdev_findbyname(req->ifr_name);
if (!dev)
{
- err = EINVAL;
+ ret = -EINVAL;
goto errout;
}
@@ -244,13 +220,13 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
case SIOCGIFCOUNT: /* Get number of devices */
req->ifr_count = netdev_count();
- err = ENOSYS;
- break;
+ ret = -ENOSYS;
+ break;
case SIOCGIFBRDADDR: /* Get broadcast IP address */
case SIOCSIFBRDADDR: /* Set broadcast IP address */
- err = ENOSYS;
- goto errout;
+ ret = -ENOSYS;
+ break;
#ifdef CONFIG_NET_ARPIOCTLS
case SIOCSARP: /* Set a ARP mapping */
@@ -260,14 +236,156 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
#endif
default:
- err = EINVAL;
- goto errout;
+ ret = -EINVAL;
+ break;;
+ }
+
+errout:
+ return ret;
+}
+
+/****************************************************************************
+ * Name: netdev_imsfioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * psock Socket structure
+ * dev Ethernet driver device structure
+ * cmd The ioctl command
+ * imsf The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * Negated errno returned on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int netdev_imsfioctl(FAR struct socket *psock, int cmd, struct ip_msfilter *imsf)
+{
+ FAR struct uip_driver_s *dev;
+ int ret = OK;
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ dev = netdev_findbyname(imsf->imsf_name);
+ if (!dev)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCSIPMSFILTER: /* Set source filter content */
+ {
+ if (imsf->imsf_fmode == MCAST_INCLUDE)
+ {
+ ret = igmp_joingroup(dev, &imsf->imsf_multiaddr);
+ }
+ else
+ {
+ DEBUGASSERT(imsf->imsf_fmode == MCAST_EXCLUDE);
+ ret = igmp_leavegroup(dev, &imsf->imsf_multiaddr);
+ }
+ }
+ break;
+
+ case SIOCGIPMSFILTER: /* Retrieve source filter addresses */
+ default:
+ ret = -EINVAL;
+ break;
+ }
+
+errout:
+ return ret;
+}
+#endif
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: netdev_ioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of device
+ * cmd The ioctl command
+ * req The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * On a failure, -1 is returned with errno set appropriately
+ *
+ * EBADF
+ * 'sockfd' is not a valid descriptor.
+ * EFAULT
+ * 'req' references an inaccessible memory area.
+ * EINVAL
+ * 'cmd' or 'req' is not valid.
+ * ENOTTY
+ * 'sockfd' is not associated with a network device.
+ * ENOTTY
+ * The specified request does not apply to the kind of object that the
+ * descriptor 'sockfd' references.
+ *
+ ****************************************************************************/
+
+int netdev_ioctl(int sockfd, int cmd, unsigned long arg)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ int ret;
+
+ /* Check if this is a valid command. In all cases, arg is a pointer that has
+ * been cast to unsigned long. Verify that the value of the to-be-pointer is
+ * non-NULL.
+ */
+
+ if (!_SIOCVALID(cmd) || !arg)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ ret = -EBADF;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq*)arg);
+#ifdef CONFIG_NET_IGMP
+ if (ret == -EINVAL)
+ {
+ ret = netdev_imsfioctl(psock, cmd, (FAR struct ip_msfilter*)arg);
+ }
+#endif
+
+ /* Check for success or failure */
+
+ if (ret >= 0)
+ {
+ return ret;
}
- return OK;
+/* On failure, set the errno and return -1 */
errout:
- errno = err;
+ errno = -ret;
return ERROR;
}
diff --git a/nuttx/net/uip/uip_igmpgroup.c b/nuttx/net/uip/uip_igmpgroup.c
index 9a75fd8d0..d0fa820a3 100755
--- a/nuttx/net/uip/uip_igmpgroup.c
+++ b/nuttx/net/uip/uip_igmpgroup.c
@@ -169,7 +169,8 @@ void uip_grpinit(void)
*
****************************************************************************/
-FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *addr)
+FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
{
FAR struct igmp_group_s *group;
irqstate_t flags;
@@ -216,7 +217,8 @@ FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev, FAR uip_ipad
*
****************************************************************************/
-FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *addr)
+FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
{
FAR struct igmp_group_s *group;
irqstate_t flags;
@@ -249,7 +251,8 @@ FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev, FAR uip_ipadd
*
****************************************************************************/
-FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *addr)
+FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
+ FAR const uip_ipaddr_t *addr)
{
FAR struct igmp_group_s *group = uip_grpfind(dev, addr);
if (!group)
diff --git a/nuttx/net/uip/uip_igmpjoin.c b/nuttx/net/uip/uip_igmpjoin.c
index b644cad10..cf37ea1c0 100755
--- a/nuttx/net/uip/uip_igmpjoin.c
+++ b/nuttx/net/uip/uip_igmpjoin.c
@@ -120,19 +120,21 @@
*
****************************************************************************/
-void igmp_joingroup(struct uip_driver_s *dev, uip_ipaddr_t *grpaddr)
+int igmp_joingroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
{
struct igmp_group_s *group;
+ DEBUGASSERT(dev && grpaddr);
+
/* Check if a this address is already in the group */
- group = uip_grpfind(dev, grpaddr);
+ group = uip_grpfind(dev, &grpaddr->s_addr);
if (!group)
{
/* No... allocate a new entry */
nvdbg("Join to new group\n");
- group = uip_grpalloc(dev, grpaddr);
+ group = uip_grpalloc(dev, &grpaddr->s_addr);
IGMP_STATINCR(uip_stat.igmp.joins);
/* Send the Membership Report */
@@ -146,8 +148,10 @@ 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_addmcastmac(dev, grpaddr);
+ uip_addmcastmac(dev, &grpaddr->s_addr);
+ return OK;
}
+ return -EEXIST;
}
#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpleave.c b/nuttx/net/uip/uip_igmpleave.c
index a482c5c4a..ac1cc81d5 100755
--- a/nuttx/net/uip/uip_igmpleave.c
+++ b/nuttx/net/uip/uip_igmpleave.c
@@ -127,14 +127,16 @@
*
****************************************************************************/
-void igmp_leavegroup(struct uip_driver_s *dev, uip_ipaddr_t *grpaddr)
+int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
{
struct igmp_group_s *group;
irqstate_t flags;
+ DEBUGASSERT(dev && grpaddr);
+
/* Find the entry corresponding to the address leaving the group */
- group = uip_grpfind(dev, grpaddr);
+ group = uip_grpfind(dev, &grpaddr->s_addr);
if (group)
{
/* Cancel the timer and discard any queued Membership Reports. Canceling
@@ -166,8 +168,10 @@ 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_removemcastmac(dev, grpaddr);
+ uip_removemcastmac(dev, &grpaddr->s_addr);
+ return OK;
}
+ return -ENOENT;
}
#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_internal.h b/nuttx/net/uip/uip_internal.h
index 02f2d50ec..aab7408da 100644
--- a/nuttx/net/uip/uip_internal.h
+++ b/nuttx/net/uip/uip_internal.h
@@ -222,11 +222,11 @@ EXTERN void uip_igmpinput(struct uip_driver_s *dev);
EXTERN void uip_grpinit(void);
EXTERN FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
- FAR uip_ipaddr_t *addr);
+ FAR const uip_ipaddr_t *addr);
EXTERN FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
- FAR uip_ipaddr_t *addr);
+ FAR const uip_ipaddr_t *addr);
EXTERN FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
- FAR uip_ipaddr_t *addr);
+ FAR const uip_ipaddr_t *addr);
EXTERN void uip_grpfree(FAR struct uip_driver_s *dev,
FAR struct igmp_group_s *group);
diff --git a/nuttx/netutils/uiplib/Make.defs b/nuttx/netutils/uiplib/Make.defs
index 4b02092bd..0feddc03d 100644
--- a/nuttx/netutils/uiplib/Make.defs
+++ b/nuttx/netutils/uiplib/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# Make.defs
#
-# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007, 2010 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -37,3 +37,7 @@ UIPLIB_ASRCS =
UIPLIB_CSRCS = uiplib.c uip_setmacaddr.c uip_getmacaddr.c uip_sethostaddr.c \
uip_gethostaddr.c uip_setdraddr.c uip_setnetmask.c uip_parsehttpurl.c \
uip_server.c
+ifeq ($(CONFIG_NET_IGMP),y)
+UIPLIB_CSRCS += uip_ipmsfilter.c
+endif
+
diff --git a/nuttx/netutils/uiplib/uip_ipmsfilter.c b/nuttx/netutils/uiplib/uip_ipmsfilter.c
new file mode 100755
index 000000000..28ed2fd2d
--- /dev/null
+++ b/nuttx/netutils/uiplib/uip_ipmsfilter.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * netutils/uiplib/uip_setmultiaddr.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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>
+
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <unistd.h>
+#include <string.h>
+#include <errno.h>
+
+#include <netinet/in.h>
+#include <sys/sockio.h>
+
+#include <net/uip/uip-lib.h>
+#include <net/uip/ipmsfilter.h>
+
+#ifdef CONFIG_NET_IGMP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ipmsfilter
+ *
+ * Description:
+ * Add or remove an IP address from a multicast filter set.
+ *
+ * Parameters:
+ * ifname The name of the interface to use, size must less than IMSFNAMSIZ
+ * multiaddr Multicast group address to add/remove (network byte order)
+ * fmode MCAST_INCLUDE: Add multicast address
+ * MCAST_EXCLUDE: Remove multicast address
+ *
+ * Return:
+ * 0 on sucess; Negated errno on failure
+ *
+ ****************************************************************************/
+
+int ipmsfilter(FAR const char *ifname, FAR const struct in_addr *multiaddr,
+ uint32_t fmode)
+{
+ int ret = ERROR;
+ if (ifname && multiaddr)
+ {
+ /* Get a socket (only so that we get access to the INET subsystem) */
+
+ int sockfd = socket(PF_INET, UIPLIB_SOCK_IOCTL, 0);
+ if (sockfd >= 0)
+ {
+ struct ip_msfilter imsf;
+
+ /* Put the driver name into the request */
+
+ strncpy(imsf.imsf_name, ifname, IMSFNAMSIZ);
+
+ /* Put the new address into the request */
+
+ imsf.imsf_multiaddr.s_addr = multiaddr->s_addr;
+
+ /* Perforom the ioctl to set the MAC address */
+
+ imsf.imsf_fmode = fmode;
+ ret = ioctl(sockfd, SIOCSIPMSFILTER, (unsigned long)&imsf);
+ close(sockfd);
+ }
+ }
+ return ret;
+}
+
+#endif /* CONFIG_NET_IGM */