summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-02-03 15:40:56 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-02-03 15:40:56 -0600
commit87bc48cc1efcedaae3bf1b176168ff3dc17637f7 (patch)
tree6953f9f33fcd7b75ec0019268bd13b3569099da8
parentbe5a9dbe26d3d362a250d7fbff2923090a144032 (diff)
downloadpx4-nuttx-87bc48cc1efcedaae3bf1b176168ff3dc17637f7.tar.gz
px4-nuttx-87bc48cc1efcedaae3bf1b176168ff3dc17637f7.tar.bz2
px4-nuttx-87bc48cc1efcedaae3bf1b176168ff3dc17637f7.zip
ICMPv6: This completes coding of the ICMPv6 auto-configuration feature. It is not yet functional
-rw-r--r--apps/examples/nettest/Kconfig3
-rw-r--r--apps/examples/nettest/nettest.c18
-rw-r--r--apps/examples/udp/Kconfig5
-rw-r--r--apps/examples/udp/target.c18
-rw-r--r--apps/nshlib/Kconfig7
-rw-r--r--apps/nshlib/nsh_netinit.c13
-rw-r--r--nuttx/net/icmpv6/icmpv6.h11
-rw-r--r--nuttx/net/icmpv6/icmpv6_autoconfig.c48
-rw-r--r--nuttx/net/icmpv6/icmpv6_input.c2
-rw-r--r--nuttx/net/netdev/netdev.h5
-rw-r--r--nuttx/net/netdev/netdev_ioctl.c120
11 files changed, 141 insertions, 109 deletions
diff --git a/apps/examples/nettest/Kconfig b/apps/examples/nettest/Kconfig
index d5cd9b610..49d885a80 100644
--- a/apps/examples/nettest/Kconfig
+++ b/apps/examples/nettest/Kconfig
@@ -76,6 +76,7 @@ config EXAMPLES_NETTEST_CLIENTIP
endif # EXAMPLES_NETTEST_IPv4
if EXAMPLES_NETTEST_IPv6
+if !NET_ICMPv6_AUTOCONF
comment "Target IPv6 address"
@@ -323,6 +324,8 @@ config EXAMPLES_NETTEST_IPv6NETMASK_8
individually. This is the eighth of the 8-values. The default for
all eight values is fe00::0.
+#endif /* NET_ICMPv6_AUTOCONF */
+
comment "Client IPv6 address"
config EXAMPLES_NETTEST_CLIENTIPv6ADDR_1
diff --git a/apps/examples/nettest/nettest.c b/apps/examples/nettest/nettest.c
index e4c9a1db3..b03b288c1 100644
--- a/apps/examples/nettest/nettest.c
+++ b/apps/examples/nettest/nettest.c
@@ -60,8 +60,7 @@
* Private Data
****************************************************************************/
-#ifdef CONFIG_EXAMPLES_NETTEST_IPv6
-#ifndef CONFIG_NET_ICMPv6_AUTOCONF
+#if defined(CONFIG_EXAMPLES_NETTEST_IPv6) && !defined(CONFIG_NET_ICMPv6_AUTOCONF)
/* Our host IPv6 address */
static const uint16_t g_ipv6_hostaddr[8] =
@@ -75,7 +74,6 @@ static const uint16_t g_ipv6_hostaddr[8] =
HTONS(CONFIG_EXAMPLES_NETTEST_IPv6ADDR_7),
HTONS(CONFIG_EXAMPLES_NETTEST_IPv6ADDR_8),
};
-#endif
/* Default routine IPv6 address */
@@ -104,7 +102,7 @@ static const uint16_t g_ipv6_netmask[8] =
HTONS(CONFIG_EXAMPLES_NETTEST_IPv6NETMASK_7),
HTONS(CONFIG_EXAMPLES_NETTEST_IPv6NETMASK_8),
};
-#endif /* CONFIG_EXAMPLES_NETTEST_IPv6 */
+#endif /* CONFIG_EXAMPLES_NETTEST_IPv6 && !CONFIG_NET_ICMPv6_AUTOCONF */
/****************************************************************************
* Public Functions
@@ -145,12 +143,12 @@ int nettest_main(int argc, char *argv[])
netlib_icmpv6_autoconfiguration("eth0");
-#else
+#else /* CONFIG_NET_ICMPv6_AUTOCONF */
+
/* Set up our fixed host address */
netlib_set_ipv6addr("eth0",
(FAR const struct in6_addr *)g_ipv6_hostaddr);
-#endif
/* Set up the default router address */
@@ -161,7 +159,10 @@ int nettest_main(int argc, char *argv[])
netlib_set_ipv6netmask("eth0",
(FAR const struct in6_addr *)g_ipv6_netmask);
-#else
+
+#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
+#else /* CONFIG_EXAMPLES_NETTEST_IPv6 */
+
/* Set up our host address */
addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_IPADDR);
@@ -176,7 +177,8 @@ int nettest_main(int argc, char *argv[])
addr.s_addr = HTONL(CONFIG_EXAMPLES_NETTEST_NETMASK);
netlib_set_ipv4netmask("eth0", &addr);
-#endif
+
+#endif /* CONFIG_EXAMPLES_NETTEST_IPv6 */
#ifdef CONFIG_EXAMPLES_NETTEST_SERVER
recv_server();
diff --git a/apps/examples/udp/Kconfig b/apps/examples/udp/Kconfig
index eecd937b0..ff357750e 100644
--- a/apps/examples/udp/Kconfig
+++ b/apps/examples/udp/Kconfig
@@ -56,6 +56,7 @@ config EXAMPLES_UDP_SERVERIP
endif # EXAMPLES_UDP_IPv4
if EXAMPLES_UDP_IPv6
+if !NET_ICMPv6_AUTOCONF
comment "Target IPv6 address"
@@ -303,7 +304,9 @@ config EXAMPLES_UDP_IPv6NETMASK_8
individually. This is the eighth of the 8-values. The default for
all eight values is fe00::0.
-comment "Client IPv6 address"
+#endif /* NET_ICMPv6_AUTOCONF */
+
+comment "Server IPv6 address"
config EXAMPLES_UDP_SERVERIPv6ADDR_1
hex "[0]"
diff --git a/apps/examples/udp/target.c b/apps/examples/udp/target.c
index 2d80ac0dc..48e28be8d 100644
--- a/apps/examples/udp/target.c
+++ b/apps/examples/udp/target.c
@@ -57,8 +57,7 @@
* Private Data
****************************************************************************/
-#ifdef CONFIG_EXAMPLES_UDP_IPv6
-#ifdef CONFIG_NET_ICMPv6_AUTOCONF
+#if defined(CONFIG_EXAMPLES_UDP_IPv6) && !defined(CONFIG_NET_ICMPv6_AUTOCONF)
/* Our host IPv6 address */
static const uint16_t g_ipv6_hostaddr[8] =
@@ -72,7 +71,6 @@ static const uint16_t g_ipv6_hostaddr[8] =
HTONS(CONFIG_EXAMPLES_UDP_IPv6ADDR_7),
HTONS(CONFIG_EXAMPLES_UDP_IPv6ADDR_8),
};
-#endif
/* Default routine IPv6 address */
@@ -101,7 +99,7 @@ static const uint16_t g_ipv6_netmask[8] =
HTONS(CONFIG_EXAMPLES_UDP_IPv6NETMASK_7),
HTONS(CONFIG_EXAMPLES_UDP_IPv6NETMASK_8),
};
-#endif /* CONFIG_EXAMPLES_UDP_IPv6 */
+#endif /* CONFIG_EXAMPLES_UDP_IPv6 && !CONFIG_NET_ICMPv6_AUTOCONF */
/****************************************************************************
* Public Functions
@@ -123,12 +121,12 @@ int udp_main(int argc, char *argv[])
netlib_icmpv6_autoconfiguration("eth0");
-#else
+#else /* CONFIG_NET_ICMPv6_AUTOCONF */
+
/* Set up our fixed host address */
netlib_set_ipv6addr("eth0",
(FAR const struct in6_addr *)g_ipv6_hostaddr);
-#endif
/* Set up the default router address */
@@ -139,7 +137,10 @@ int udp_main(int argc, char *argv[])
netlib_set_ipv6netmask("eth0",
(FAR const struct in6_addr *)g_ipv6_netmask);
-#else
+
+#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
+#else /* CONFIG_EXAMPLES_UDP_IPv6 */
+
struct in_addr addr;
/* Set up our host address */
@@ -156,7 +157,8 @@ int udp_main(int argc, char *argv[])
addr.s_addr = HTONL(CONFIG_EXAMPLES_UDP_NETMASK);
netlib_set_ipv4netmask("eth0", &addr);
-#endif
+
+#endif /* CONFIG_EXAMPLES_UDP_IPv6 */
#ifdef CONFIG_EXAMPLES_UDP_SERVER
recv_server();
diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig
index 8bcd5eda7..dc1001020 100644
--- a/apps/nshlib/Kconfig
+++ b/apps/nshlib/Kconfig
@@ -930,8 +930,7 @@ config NSH_NETMASK
endif # NET_IPv4
-if NET_IPv6
-if !NET_ICMPv6_AUTOCONF
+if NET_IPv6 && !NET_ICMPv6_AUTOCONF
comment "Target IPv6 address"
@@ -1023,8 +1022,6 @@ config NSH_IPv6ADDR_8
individually. This is the last of the 8-values. The default for
all eight values is fc00::2.
-endif # !NET_ICMPv6_AUTOCONF
-
comment "Router IPv6 address"
config NSH_DRIPv6ADDR_1
@@ -1189,7 +1186,7 @@ config NSH_IPv6NETMASK_8
individually. This is the eighth of the 8-values. The default for
all eight values is fe00::0.
-endif #NET_IPv6
+endif #NET_IPv6 && !NET_ICMPv6_AUTOCONF
endmenu # IP Address Configuration
config NSH_DNS
diff --git a/apps/nshlib/nsh_netinit.c b/apps/nshlib/nsh_netinit.c
index c2b8bf952..1c4722909 100644
--- a/apps/nshlib/nsh_netinit.c
+++ b/apps/nshlib/nsh_netinit.c
@@ -131,8 +131,7 @@
static sem_t g_notify_sem;
#endif
-#ifdef CONFIG_NET_IPv6
-#ifndef CONFIG_NET_ICMPv6_AUTOCONF
+#if defined(CONFIG_NET_IPv6) && !defined(CONFIG_NET_ICMPv6_AUTOCONF)
/* Host IPv6 address */
static const uint16_t g_ipv6_hostaddr[8] =
@@ -146,7 +145,6 @@ static const uint16_t g_ipv6_hostaddr[8] =
HTONS(CONFIG_NSH_IPv6ADDR_7),
HTONS(CONFIG_NSH_IPv6ADDR_8),
};
-#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
/* Default routine IPv6 address */
@@ -175,7 +173,7 @@ static const uint16_t g_ipv6_netmask[8] =
HTONS(CONFIG_NSH_IPv6NETMASK_7),
HTONS(CONFIG_NSH_IPv6NETMASK_8),
};
-#endif /* CONFIG_NET_IPv6 */
+#endif /* CONFIG_NET_IPv6 && !CONFIG_NET_ICMPv6_AUTOCONF*/
/****************************************************************************
* Private Function Prototypes
@@ -260,13 +258,12 @@ static void nsh_netinit_configure(void)
netlib_icmpv6_autoconfiguration(NET_DEVNAME);
-#else
+#else /* CONFIG_NET_ICMPv6_AUTOCONF */
/* Set up our fixed host address */
netlib_set_ipv6addr(NET_DEVNAME,
(FAR const struct in6_addr *)g_ipv6_hostaddr);
-#endif
/* Set up the default router address */
@@ -277,7 +274,9 @@ static void nsh_netinit_configure(void)
netlib_set_ipv6netmask(NET_DEVNAME,
(FAR const struct in6_addr *)g_ipv6_netmask);
-#endif
+
+#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
+#endif /* CONFIG_NET_IPv6 */
#if defined(CONFIG_NSH_DHCPC) || defined(CONFIG_NSH_DNS)
/* Set up the resolver */
diff --git a/nuttx/net/icmpv6/icmpv6.h b/nuttx/net/icmpv6/icmpv6.h
index 2a9a094f2..67a6be624 100644
--- a/nuttx/net/icmpv6/icmpv6.h
+++ b/nuttx/net/icmpv6/icmpv6.h
@@ -93,10 +93,6 @@ struct icmpv6_rnotify_s
{
#ifdef CONFIG_NET_MULTILINK
FAR struct icmpv6_notify_s *rn_flink; /* Supports singly linked list */
-#endif
- net_ipv6addr_t rn_prefix; /* Waited for router prefix */
- uint8_t rn_preflen; /* Prefix length (# valid leading bits) */
-#ifdef CONFIG_NET_MULTILINK
char rn_ifname[IFNAMSIZ]; /* Device name */
#endif
sem_t rn_sem; /* Will wake up the waiter */
@@ -431,6 +427,9 @@ int icmpv6_rwait(FAR struct icmpv6_rnotify_s *notify,
* wake-up any threads that may be waiting for this particular Router
* Advertisement.
*
+ * NOTE: On success the network has the new address applied and is in
+ * the down state.
+ *
* Assumptions:
* This function is called from the MAC device driver indirectly through
* icmpv6_icmpv6in() will execute with the network locked.
@@ -438,8 +437,8 @@ int icmpv6_rwait(FAR struct icmpv6_rnotify_s *notify,
****************************************************************************/
#ifdef CONFIG_NET_ICMPv6_AUTOCONF
-void icmpv6_rnotify(FAR struct net_driver_s *dev, const net_ipv6addr_t prefix,
- unsigned int preflen);
+void icmpv6_rnotify(FAR struct net_driver_s *dev, const net_ipv6addr_t draddr,
+ const net_ipv6addr_t prefix, unsigned int preflen);
#else
# define icmpv6_rnotify(d,p,l)
#endif
diff --git a/nuttx/net/icmpv6/icmpv6_autoconfig.c b/nuttx/net/icmpv6/icmpv6_autoconfig.c
index ed7577d08..747651e3d 100644
--- a/nuttx/net/icmpv6/icmpv6_autoconfig.c
+++ b/nuttx/net/icmpv6/icmpv6_autoconfig.c
@@ -52,6 +52,7 @@
#include <nuttx/net/netdev.h>
#include "devif/devif.h"
+#include "netdev/netdev.h"
#include "icmpv6/icmpv6.h"
/****************************************************************************
@@ -327,7 +328,7 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
ndbg("ERROR: Only Ethernet is supported\n");
return -ENOSYS;
-#else
+#else /* CONFIG_NET_ETHERNET */
struct icmpv6_rnotify_s notify;
net_ipv6addr_t lladdr;
net_lock_t save;
@@ -348,6 +349,11 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
return -ENOSYS;
}
#endif
+ /* The interface should be in the down state */
+
+ save = net_lock();
+ netdev_ifdown(dev);
+ net_unlock(save);
/* IPv6 Stateless Autoconfiguration
* Reference: http://www.tcpipguide.com/free/t_IPv6AutoconfiguratinoandRenumbering.htm
@@ -378,6 +384,10 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
memset(&lladdr[1], 0, 4* sizeof(uint16_t)); /* 64 more zeroes */
memcpy(&lladdr[5], dev->d_mac.ether_addr_octet, sizeof(struct ether_addr)); /* 48-bit Ethernet address */
+ nvdbg("lladdr=%04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n",
+ lladdr[0], lladdr[1], lladdr[2], lladdr[3],
+ lladdr[4], lladdr[6], lladdr[6], lladdr[7]);
+
#ifdef CONFIG_NET_ICMPv6_NEIGHBOR
/* 2. Link-Local Address Uniqueness Test: The node tests to ensure that
* the address it generated isn't for some reason already in use on the
@@ -410,6 +420,11 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
net_ipv6addr_copy(dev->d_ipv6addr, lladdr);
+ /* Bring the interface up with the new, temporary IP address */
+
+ save = net_lock();
+ netdev_ifup(dev);
+
/* 4. Router Contact: The node next attempts to contact a local router for
* more information on continuing the configuration. This is done either
* by listening for Router Advertisement messages sent periodically by
@@ -417,7 +432,6 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
* for information on what to do next.
*/
- save = net_lock();
for (retries = 0; retries < CONFIG_ICMPv6_AUTOCONF_MAXTRIES; retries++)
{
/* Set up the Router Advertisement BEFORE we send the Router
@@ -447,17 +461,22 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
break;
}
- nvdbg("Timed out... retrying\n");
+ nvdbg("Timed out... retrying %d\n", retries + 1);
}
- net_unlock(save);
-
- /* Check for failures */
+ /* Check for failures. Note: On successful return, the network will be
+ * in the down state, but not in the event of failures.
+ */
if (ret < 0)
{
ndbg("ERROR: Failed to get the router advertisement: %d (retries=%d)\n",
ret, retries);
+
+ /* Take the network down and return the failure */
+
+ netdev_ifdown(dev);
+ net_unlock(save);
return ret;
}
@@ -466,20 +485,23 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
* network "stateful" auto-configuration is in use, and tell it the
* address of a DHCP server to use. Alternately, it will tell the host
* how to determine its global Internet address.
- */
-#warning Missing logic
-
- /* 6. Global Address Configuration: Assuming that stateless auto-
+ *
+ * 6. Global Address Configuration: Assuming that stateless auto-
* configuration is in use on the network, the host will configure
* itself with its globally-unique Internet address. This address is
* generally formed from a network prefix provided to the host by the
* router, combined with the device's identifier as generated in the
* first step.
*/
-#warning Missing logic
- return ret;
-#endif
+ /* On success, the new address was already set (in icmpv_rnotify()). We
+ * need only to bring the network back to the up state and return success.
+ */
+
+ netdev_ifup(dev);
+ net_unlock(save);
+ return OK;
+#endif /* CONFIG_NET_ETHERNET */
}
#endif /* CONFIG_NET_ICMPv6_AUTOCONF */
diff --git a/nuttx/net/icmpv6/icmpv6_input.c b/nuttx/net/icmpv6/icmpv6_input.c
index e3dc4d24b..8aeaddfe8 100644
--- a/nuttx/net/icmpv6/icmpv6_input.c
+++ b/nuttx/net/icmpv6/icmpv6_input.c
@@ -321,7 +321,7 @@ void icmpv6_input(FAR struct net_driver_s *dev)
{
/* Yes.. Notify any waiting threads */
- icmpv6_rnotify(dev, opt->prefix, opt->preflen);
+ icmpv6_rnotify(dev, icmp->srcipaddr, opt->prefix, opt->preflen);
goto icmpv_send_nothing;
}
diff --git a/nuttx/net/netdev/netdev.h b/nuttx/net/netdev/netdev.h
index 28dbf83f1..d0083723b 100644
--- a/nuttx/net/netdev/netdev.h
+++ b/nuttx/net/netdev/netdev.h
@@ -85,6 +85,11 @@ void netdev_semtake(void);
void netdev_semgive(void);
#endif
+/* netdev_ioctl.c ************************************************************/
+
+void netdev_ifup(FAR struct net_driver_s *dev);
+void netdev_ifdown(FAR struct net_driver_s *dev);
+
/* netdev_findbyname.c *******************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
diff --git a/nuttx/net/netdev/netdev_ioctl.c b/nuttx/net/netdev/netdev_ioctl.c
index 7a61897dc..5eae3b816 100644
--- a/nuttx/net/netdev/netdev_ioctl.c
+++ b/nuttx/net/netdev/netdev_ioctl.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/netdev/netdev_ioctl.c
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -316,58 +316,6 @@ static void ioctl_setipv6addr(FAR net_ipv6addr_t outaddr,
#endif
/****************************************************************************
- * Name: ioctl_ifup / ioctl_ifdown
- *
- * Description:
- * Bring the interface up/down
- *
- ****************************************************************************/
-
-static void ioctl_ifup(FAR struct net_driver_s *dev)
-{
- /* Make sure that the device supports the d_ifup() method */
-
- if (dev->d_ifup)
- {
- /* Is the interface already up? */
-
- if ((dev->d_flags & IFF_UP) == 0)
- {
- /* No, bring the interface up now */
-
- if (dev->d_ifup(dev) == OK)
- {
- /* Mark the interface as up */
-
- dev->d_flags |= IFF_UP;
- }
- }
- }
-}
-
-static void ioctl_ifdown(FAR struct net_driver_s *dev)
-{
- /* Make sure that the device supports the d_ifdown() method */
-
- if (dev->d_ifdown)
- {
- /* Is the interface already down? */
-
- if ((dev->d_flags & IFF_UP) != 0)
- {
- /* No, take the interface down now */
-
- if (dev->d_ifdown(dev) == OK)
- {
- /* Mark the interface as down */
-
- dev->d_flags &= ~IFF_UP;
- }
- }
- }
-}
-
-/****************************************************************************
* Name: netdev_ifrdev
*
* Description:
@@ -445,9 +393,9 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
dev = netdev_ifrdev(req);
if (dev)
{
- ioctl_ifdown(dev);
+ netdev_ifdown(dev);
ioctl_setipv4addr(&dev->d_ipaddr, &req->ifr_addr);
- ioctl_ifup(dev);
+ netdev_ifup(dev);
ret = OK;
}
}
@@ -538,9 +486,9 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
{
FAR struct lifreq *lreq = (FAR struct lifreq *)req;
- ioctl_ifdown(dev);
+ netdev_ifdown(dev);
ioctl_setipv6addr(dev->d_ipv6addr, &lreq->lifr_addr);
- ioctl_ifup(dev);
+ netdev_ifup(dev);
ret = OK;
}
}
@@ -650,7 +598,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
{
/* Yes.. bring the interface up */
- ioctl_ifup(dev);
+ netdev_ifup(dev);
}
/* Is this a request to take the interface down? */
@@ -659,7 +607,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
{
/* Yes.. take the interface down */
- ioctl_ifdown(dev);
+ netdev_ifdown(dev);
}
}
@@ -713,7 +661,7 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
dev = netdev_ifrdev(req);
if (dev)
{
- ioctl_ifdown(dev);
+ netdev_ifdown(dev);
#ifdef CONFIG_NET_IPv4
dev->d_ipaddr = 0;
#endif
@@ -1051,4 +999,56 @@ errout:
return ERROR;
}
+/****************************************************************************
+ * Name: netdev_ifup / netdev_ifdown
+ *
+ * Description:
+ * Bring the interface up/down
+ *
+ ****************************************************************************/
+
+void netdev_ifup(FAR struct net_driver_s *dev)
+{
+ /* Make sure that the device supports the d_ifup() method */
+
+ if (dev->d_ifup)
+ {
+ /* Is the interface already up? */
+
+ if ((dev->d_flags & IFF_UP) == 0)
+ {
+ /* No, bring the interface up now */
+
+ if (dev->d_ifup(dev) == OK)
+ {
+ /* Mark the interface as up */
+
+ dev->d_flags |= IFF_UP;
+ }
+ }
+ }
+}
+
+void netdev_ifdown(FAR struct net_driver_s *dev)
+{
+ /* Make sure that the device supports the d_ifdown() method */
+
+ if (dev->d_ifdown)
+ {
+ /* Is the interface already down? */
+
+ if ((dev->d_flags & IFF_UP) != 0)
+ {
+ /* No, take the interface down now */
+
+ if (dev->d_ifdown(dev) == OK)
+ {
+ /* Mark the interface as down */
+
+ dev->d_flags &= ~IFF_UP;
+ }
+ }
+ }
+}
+
#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */