summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-07-11 18:10:22 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-07-11 18:10:22 +0000
commite58cb9f47ccff39c084944ea3e5c1154325b6ef1 (patch)
tree7d8c91af166541c11753f1b8b3ef847edf7c48a8 /nuttx/net
parent701cde95d29fbb7dd75e42b0cd37fc3434c6fd88 (diff)
downloadpx4-nuttx-e58cb9f47ccff39c084944ea3e5c1154325b6ef1.tar.gz
px4-nuttx-e58cb9f47ccff39c084944ea3e5c1154325b6ef1.tar.bz2
px4-nuttx-e58cb9f47ccff39c084944ea3e5c1154325b6ef1.zip
Add IGMP user interface
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2786 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-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
5 files changed, 187 insertions, 58 deletions
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);