summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/include/net/route.h64
-rw-r--r--nuttx/include/nuttx/net/ioctl.h4
-rw-r--r--nuttx/libc/net/Make.defs8
-rw-r--r--nuttx/libc/net/lib_addroute.c90
-rw-r--r--nuttx/libc/net/lib_delroute.c88
-rw-r--r--nuttx/net/Kconfig2
-rw-r--r--nuttx/net/net_addroute.c3
-rw-r--r--nuttx/net/net_delroute.c3
-rw-r--r--nuttx/net/net_findroute.c3
-rw-r--r--nuttx/net/net_foreachroute.c2
-rw-r--r--nuttx/net/net_route.h (renamed from nuttx/include/nuttx/net/route.h)8
-rw-r--r--nuttx/net/netdev_ioctl.c185
13 files changed, 420 insertions, 43 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 27c0dfab8..2abc29b0d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5695,4 +5695,7 @@
the routing table (2013-10-2).
* configs/spark: Add configuratino for the Spark Core. The
initial check-in is basically the Maple Mini board (2013-10-2).
+ * include/net/route.h and libc/net/lib_addroute.c and delroute.c:
+ Add an application interface to manage the routing table
+ (2013-10-2).
diff --git a/nuttx/include/net/route.h b/nuttx/include/net/route.h
index 72a4e64f9..030c5b0ee 100644
--- a/nuttx/include/net/route.h
+++ b/nuttx/include/net/route.h
@@ -56,27 +56,16 @@
* Public Types
****************************************************************************/
-struct ifnet
-{
- uint16_t if_index; /* Interface number */
- uint16_t if_mtu; /* MTU of interface */
- struct sockaddr_in if_addr; /* Address of interface */
- struct sockaddr_in if_netmask; /* Netmask of if_addr */
-};
-
/* This structure describes the route information passed with the SIOCADDRT
* and SIOCDELRT ioctl commands (see include/nuttx/net/ioctl.h).
*/
-struct ortentry
+struct rtentry
{
- uint32_t rt_hash; /* To speed lookups */
- struct sockaddr rt_dst; /* Key */
- struct sockaddr rt_gateway; /* Value */
- uint16_t rt_flags; /* Up/down?, host/net */
- uint16_t rt_refcnt; /* Number of held references */
- uint32_t rt_use; /* Raw number of packets forwarded */
- struct ifnet *rt_ifp; /* The answer: interface to use */
+ uint16_t rt_ifno; /* Interface number, e.g., the 0 in "eth0" */
+ FAR struct sockaddr_storage *rt_target; /* Target address */
+ FAR struct sockaddr_storage *rt_netmask; /* Network mask defining the sub-net */
+ FAR struct sockaddr_storage *rt_gateway; /* Gateway address associated with the hop */
};
/****************************************************************************
@@ -95,6 +84,49 @@ extern "C"
* Public Function Prototypes
****************************************************************************/
+/****************************************************************************
+ * Function: net_addroute
+ *
+ * Description:
+ * Add a new route to the routing table. This is just a convenience
+ * wrapper for the SIOCADDRT ioctl call.
+ *
+ * Parameters:
+ * sockfd - Any socket descriptor
+ * target - Target address (required)
+ * netmask - Network mask defining the sub-net (required)
+ * gateway - Gateway address associated with the hop (optional)
+ * ifno - Interface number, e.g., the 0 in "eth0"
+ *
+ * Returned Value:
+ * OK on success; -1 on failure with the errno variable set appropriately.
+ *
+ ****************************************************************************/
+
+int addroute(int sockfd, FAR struct sockaddr_storage *target,
+ FAR struct sockaddr_storage *netmask,
+ FAR struct sockaddr_storage *gateway, int ifno);
+
+/****************************************************************************
+ * Function: net_delroute
+ *
+ * Description:
+ * Add a new route to the routing table. This is just a convenience
+ * wrapper for the SIOCADDRT ioctl call.
+ *
+ * Parameters:
+ * sockfd - Any socket descriptor
+ * target - Target address (required)
+ * netmask - Network mask defining the sub-net (required)
+ *
+ * Returned Value:
+ * OK on success; -1 on failure with the errno variable set appropriately.
+ *
+ ****************************************************************************/
+
+int delroute(int sockfd, FAR struct sockaddr_storage *target,
+ FAR struct sockaddr_storage *netmask);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/net/ioctl.h b/nuttx/include/nuttx/net/ioctl.h
index 00ea2e7f3..7fbcc3b20 100644
--- a/nuttx/include/nuttx/net/ioctl.h
+++ b/nuttx/include/nuttx/net/ioctl.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/net/ioctl.h
*
- * Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -92,7 +92,7 @@
#define SIOCGIPMSFILTER _SIOC(0x0010) /* Retrieve source filter addresses */
#define SIOCSIPMSFILTER _SIOC(0x0011) /* Set source filter content */
-/* Routing table. Argument is a reference to struct ortentry in
+/* Routing table. Argument is a reference to struct rtentry as defined in
* include/net/route.h
*/
diff --git a/nuttx/libc/net/Make.defs b/nuttx/libc/net/Make.defs
index 9d4e5c06b..7cf402b96 100644
--- a/nuttx/libc/net/Make.defs
+++ b/nuttx/libc/net/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# libc/net/Make.defs
#
-# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -38,6 +38,12 @@
CSRCS += lib_etherntoa.c lib_htons.c lib_htonl.c lib_inetaddr.c
CSRCS += lib_inetntoa.c lib_inetntop.c lib_inetpton.c
+# Routing table support
+
+ifeq ($(CONFIG_NET_ROUTE),y)
+CSRCS += lib_addroute.c lib_delroute.c
+endif
+
# Add the net directory to the build
DEPPATH += --dep-path net
diff --git a/nuttx/libc/net/lib_addroute.c b/nuttx/libc/net/lib_addroute.c
new file mode 100644
index 000000000..47efeba32
--- /dev/null
+++ b/nuttx/libc/net/lib_addroute.c
@@ -0,0 +1,90 @@
+/***************************************************************************
+ * libc/net/lib_addroute.c
+ *
+ * Copyright (C) 2013 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.
+ *
+ ***************************************************************************/
+
+/***************************************************************************
+ * Compilation Switches
+ ***************************************************************************/
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <net/route.h>
+
+/***************************************************************************
+ * Global Functions
+ ***************************************************************************/
+
+/****************************************************************************
+ * Function: net_addroute
+ *
+ * Description:
+ * Add a new route to the routing table. This is just a convenience
+ * wrapper for the SIOCADDRT ioctl call.
+ *
+ * Parameters:
+ * sockfd - Any socket descriptor
+ * target - Target address (required)
+ * netmask - Network mask defining the sub-net (required)
+ * gateway - Gateway address associated with the hop (optional)
+ * ifno - Interface number, e.g., the 0 in "eth0"
+ *
+ * Returned Value:
+ * OK on success; -1 on failure with the errno variable set appropriately.
+ *
+ ****************************************************************************/
+
+int addroute(int sockfd, FAR struct sockaddr_storage *target,
+ FAR struct sockaddr_storage *netmask,
+ FAR struct sockaddr_storage *gateway, int ifno)
+{
+ struct rtentry entry;
+
+ /* Set up the rtentry structure */
+
+ entry.rt_ifno = ifno; /* Interface number, e.g., the 0 in "eth0" */
+ entry.rt_target = target; /* Target address */
+ entry.rt_netmask = netmask; /* Network mask defining the sub-net */
+ entry.rt_gateway = gateway; /* Gateway address associated with the hop */
+
+ /* Then perform the ioctl */
+
+ return ioctl(sockfd, SIOCADDRT, (unsigned long)((uintptr_t)&entry));
+}
diff --git a/nuttx/libc/net/lib_delroute.c b/nuttx/libc/net/lib_delroute.c
new file mode 100644
index 000000000..471391483
--- /dev/null
+++ b/nuttx/libc/net/lib_delroute.c
@@ -0,0 +1,88 @@
+/***************************************************************************
+ * libc/net/lib_delroute.c
+ *
+ * Copyright (C) 2013 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.
+ *
+ ***************************************************************************/
+
+/***************************************************************************
+ * Compilation Switches
+ ***************************************************************************/
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <stdint.h>
+#include <net/route.h>
+
+/***************************************************************************
+ * Global Functions
+ ***************************************************************************/
+
+/****************************************************************************
+ * Function: net_delroute
+ *
+ * Description:
+ * Add a new route to the routing table. This is just a convenience
+ * wrapper for the SIOCADDRT ioctl call.
+ *
+ * Parameters:
+ * sockfd - Any socket descriptor
+ * target - Target address (required)
+ * netmask - Network mask defining the sub-net (required)
+ *
+ * Returned Value:
+ * OK on success; -1 on failure with the errno variable set appropriately.
+ *
+ ****************************************************************************/
+
+int delroute(int sockfd, FAR struct sockaddr_storage *target,
+ FAR struct sockaddr_storage *netmask)
+{
+ struct rtentry entry;
+
+ /* Set up the rtentry structure */
+
+ entry.rt_target = target; /* Target address */
+ entry.rt_netmask = netmask; /* Network mask defining the sub-net */
+
+ entry.rt_ifno = 0; /* (not used for deletion) */
+ entry.rt_gateway = NULL; /* (not used for deletion) */
+
+ /* Then perform the ioctl */
+
+ return ioctl(sockfd, SIOCDELRT, (unsigned long)((uintptr_t)&entry));
+}
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
index fbc34ec78..d3e7b3b72 100644
--- a/nuttx/net/Kconfig
+++ b/nuttx/net/Kconfig
@@ -308,7 +308,7 @@ config NET_ROUTE
bool "Routing table suport"
default n
---help---
- Build in support for a routing table. See include/nuttx/net/route.h
+ Build in support for a routing table. See include/net/route.h
config NET_MAXROUTES
int "Routing table size"
diff --git a/nuttx/net/net_addroute.c b/nuttx/net/net_addroute.c
index 6b7ac9f6e..ee440c430 100644
--- a/nuttx/net/net_addroute.c
+++ b/nuttx/net/net_addroute.c
@@ -43,9 +43,8 @@
#include <string.h>
#include <errno.h>
-#include <nuttx/net/route.h>
-
#include "net_internal.h"
+#include "net_route.h"
#if defined(CONFIG_NET) && defined(CONFIG_NET_ROUTE)
diff --git a/nuttx/net/net_delroute.c b/nuttx/net/net_delroute.c
index b203f0349..6aa6f8e9f 100644
--- a/nuttx/net/net_delroute.c
+++ b/nuttx/net/net_delroute.c
@@ -43,9 +43,8 @@
#include <string.h>
#include <errno.h>
-#include <nuttx/net/route.h>
-
#include "net_internal.h"
+#include "net_route.h"
#if defined(CONFIG_NET) && defined(CONFIG_NET_ROUTE)
diff --git a/nuttx/net/net_findroute.c b/nuttx/net/net_findroute.c
index 5dea9d9ac..55c82402e 100644
--- a/nuttx/net/net_findroute.c
+++ b/nuttx/net/net_findroute.c
@@ -43,9 +43,8 @@
#include <string.h>
#include <errno.h>
-#include <nuttx/net/route.h>
-
#include "net_internal.h"
+#include "net_route.h"
#if defined(CONFIG_NET) && defined(CONFIG_NET_ROUTE)
diff --git a/nuttx/net/net_foreachroute.c b/nuttx/net/net_foreachroute.c
index 8eb844334..dc01e382a 100644
--- a/nuttx/net/net_foreachroute.c
+++ b/nuttx/net/net_foreachroute.c
@@ -43,9 +43,9 @@
#include <errno.h>
#include <arch/irq.h>
-#include <nuttx/net/route.h>
#include "net_internal.h"
+#include "net_route.h"
#if defined(CONFIG_NET) && defined(CONFIG_NET_ROUTE)
diff --git a/nuttx/include/nuttx/net/route.h b/nuttx/net/net_route.h
index 9fa761726..a2ba11145 100644
--- a/nuttx/include/nuttx/net/route.h
+++ b/nuttx/net/net_route.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * include/nuttx/net/route.h
+ * net/net_route.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __INCLUDE_NUTTX_NET_ROUTE_H
-#define __INCLUDE_NUTTX_NET_ROUTE_H
+#ifndef __NET_NET_ROUTE_H
+#define __NET_NET_ROUTE_H
/****************************************************************************
* Included Files
@@ -159,4 +159,4 @@ int net_foreachroute(route_handler_t handler, FAR void *arg);
#endif
#endif /* CONFIG_NET_ROUTE */
-#endif /* __INCLUDE_NUTTX_NET_ROUTE_H */
+#endif /* __NET_NET_ROUTE_H */
diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c
index ea5c0e436..12a31f0ce 100644
--- a/nuttx/net/netdev_ioctl.c
+++ b/nuttx/net/netdev_ioctl.c
@@ -51,7 +51,10 @@
#include <nuttx/net/net.h>
#include <net/if.h>
+#include <net/route.h>
#include <net/ethernet.h>
+#include <netinet/in.h>
+
#include <nuttx/net/uip/uip-arch.h>
#include <nuttx/net/uip/uip.h>
@@ -61,6 +64,7 @@
#endif
#include "net_internal.h"
+#include "net_route.h"
/****************************************************************************
* Pre-processor Definitions
@@ -200,12 +204,18 @@ static void ioctl_ifdown(FAR struct uip_driver_s *dev)
*
****************************************************************************/
-static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req)
+static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
+ FAR struct ifreq *req)
{
FAR struct uip_driver_s *dev;
int ret = OK;
nvdbg("cmd: %d\n", cmd);
+ if (!req)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
/* Find the network device associated with the device name
* in the request data.
@@ -357,7 +367,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd, struct ifreq *req)
default:
{
- ret = -EINVAL;
+ ret = -ENOTTY;
}
break;;
}
@@ -385,12 +395,18 @@ errout:
****************************************************************************/
#ifdef CONFIG_NET_IGMP
-static int netdev_imsfioctl(FAR struct socket *psock, int cmd, struct ip_msfilter *imsf)
+static int netdev_imsfioctl(FAR struct socket *psock, int cmd,
+ FAR struct ip_msfilter *imsf)
{
FAR struct uip_driver_s *dev;
int ret = OK;
nvdbg("cmd: %d\n", cmd);
+ if (!imsf)
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
/* Find the network device associated with the device name
* in the request data.
@@ -423,7 +439,7 @@ static int netdev_imsfioctl(FAR struct socket *psock, int cmd, struct ip_msfilte
case SIOCGIPMSFILTER: /* Retrieve source filter addresses */
default:
- ret = -EINVAL;
+ ret = -ENOTTY;
break;
}
@@ -433,6 +449,142 @@ errout:
#endif
/****************************************************************************
+ * Name: netdev_rtioctl
+ *
+ * Description:
+ * Perform routing table specific operations.
+ *
+ * Parameters:
+ * psock Socket structure
+ * dev Ethernet driver device structure
+ * cmd The ioctl command
+ * rtentry 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_ROUTE
+static int netdev_rtioctl(FAR struct socket *psock, int cmd,
+ FAR struct rtentry *rtentry)
+{
+ int ret;
+
+ /* Return an error if no rtentry structure is provided */
+
+ if (!rtentry)
+ {
+ return -EINVAL;
+ }
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCADDRT: /* Add an entry to the routing table */
+ {
+ uip_ipaddr_t target;
+ uip_ipaddr_t netmask;
+ uip_ipaddr_t gateway;
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *addr;
+#else
+ FAR struct sockaddr_in *addr;
+#endif
+ /* The target address and the netmask are required value */
+
+ if (!rtentry->rt_target || !rtentry->rt_netmask)
+ {
+ return -EINVAL;
+ }
+
+#ifdef CONFIG_NET_IPv6
+ addr = (FAR struct sockaddr_in6 *)rtentry->rt_target;
+ target = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+
+ addr = (FAR struct sockaddr_in6 *)rtentry->rt_netmask;
+ netmask = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+
+ /* The gateway is an optional argument */
+
+ if (rtentry->rt_gateway)
+ {
+ addr = (FAR struct sockaddr_in6 *)rtentry->rt_gateway;
+ gateway = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+ }
+ else
+ {
+ gateway = NULL;
+ }
+#else
+ addr = (FAR struct sockaddr_in *)rtentry->rt_target;
+ target = (uip_ipaddr_t)addr->sin_addr.s_addr;
+
+ addr = (FAR struct sockaddr_in *)rtentry->rt_netmask;
+ netmask = (uip_ipaddr_t)addr->sin_addr.s_addr;
+
+ /* The gateway is an optional argument */
+
+ if (rtentry->rt_gateway)
+ {
+ addr = (FAR struct sockaddr_in *)rtentry->rt_gateway;
+ gateway = (uip_ipaddr_t)addr->sin_addr.s_addr;
+ }
+ else
+ {
+ gateway = 0;
+ }
+#endif
+ ret = net_addroute(target, netmask, gateway, rtentry->rt_ifno);
+ }
+ break;
+
+ case SIOCDELRT: /* Delete an entry from the routing table */
+ {
+ uip_ipaddr_t target;
+ uip_ipaddr_t netmask;
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *addr;
+#else
+ FAR struct sockaddr_in *addr;
+#endif
+
+ /* The target address and the netmask are required value */
+
+ if (!rtentry->rt_target || !rtentry->rt_netmask)
+ {
+ return -EINVAL;
+ }
+
+#ifdef CONFIG_NET_IPv6
+ addr = (FAR struct sockaddr_in6 *)&rtentry->rt_target;
+ target = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+
+ addr = (FAR struct sockaddr_in6 *)&rtentry->rt_netmask;
+ netmask = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+#else
+ addr = (FAR struct sockaddr_in *)&rtentry->rt_target;
+ target = (uip_ipaddr_t)addr->sin_addr.s_addr;
+
+ addr = (FAR struct sockaddr_in *)&rtentry->rt_netmask;
+ netmask = (uip_ipaddr_t)addr->sin_addr.s_addr;
+#endif
+ ret = net_delroute(target, netmask);
+ }
+ break;
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+}
+#endif
+
+/****************************************************************************
* Global Functions
****************************************************************************/
@@ -445,7 +597,7 @@ errout:
* Parameters:
* sockfd Socket descriptor of device
* cmd The ioctl command
- * req The argument of the ioctl cmd
+ * arg The argument of the ioctl cmd
*
* Return:
* >=0 on success (positive non-zero values are cmd-specific)
@@ -454,9 +606,11 @@ errout:
* EBADF
* 'sockfd' is not a valid descriptor.
* EFAULT
- * 'req' references an inaccessible memory area.
+ * 'arg' references an inaccessible memory area.
+ * ENOTTY
+ * 'cmd' not valid.
* EINVAL
- * 'cmd' or 'req' is not valid.
+ * 'arg' is not valid.
* ENOTTY
* 'sockfd' is not associated with a network device.
* ENOTTY
@@ -475,9 +629,9 @@ int netdev_ioctl(int sockfd, int cmd, unsigned long arg)
* non-NULL.
*/
- if (!_SIOCVALID(cmd) || !arg)
+ if (!_SIOCVALID(cmd))
{
- ret = -EINVAL;
+ ret = -ENOTTY;
goto errout;
}
@@ -491,11 +645,18 @@ int netdev_ioctl(int sockfd, int cmd, unsigned long arg)
/* Execute the command */
- ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq*)arg);
+ ret = netdev_ifrioctl(psock, cmd, (FAR struct ifreq*)((uintptr_t)arg));
#ifdef CONFIG_NET_IGMP
- if (ret == -EINVAL)
+ if (ret == -ENOTTY)
+ {
+
+ ret = netdev_imsfioctl(psock, cmd, (FAR struct ip_msfilter*)((uintptr_t)arg));
+ }
+#endif
+#ifdef CONFIG_NET_ROUTE
+ if (ret == -ENOTTY)
{
- ret = netdev_imsfioctl(psock, cmd, (FAR struct ip_msfilter*)arg);
+ ret = netdev_rtioctl(psock, cmd, (FAR struct rtentry*)((uintptr_t)arg));
}
#endif