summaryrefslogtreecommitdiff
path: root/nuttx/net/netdev
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-06-27 09:56:45 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-06-27 09:56:45 -0600
commit4aea19bae0f90ef3c01fe72eb2e7b32d25386c5c (patch)
tree9b9a9443fd2df33c6ef543d98609ca2a9174f885 /nuttx/net/netdev
parent527d7522fa05478cf7a20e16b037a2c13f3ac0fd (diff)
downloadpx4-nuttx-4aea19bae0f90ef3c01fe72eb2e7b32d25386c5c.tar.gz
px4-nuttx-4aea19bae0f90ef3c01fe72eb2e7b32d25386c5c.tar.bz2
px4-nuttx-4aea19bae0f90ef3c01fe72eb2e7b32d25386c5c.zip
NET: Move net/netdev*.c to net/netdev/netdev*.c
Diffstat (limited to 'nuttx/net/netdev')
-rw-r--r--nuttx/net/netdev/netdev_carrier.c134
-rw-r--r--nuttx/net/netdev/netdev_count.c103
-rw-r--r--nuttx/net/netdev/netdev_findbyaddr.c215
-rw-r--r--nuttx/net/netdev/netdev_findbyname.c112
-rw-r--r--nuttx/net/netdev/netdev_foreach.c115
-rw-r--r--nuttx/net/netdev/netdev_ioctl.c750
-rw-r--r--nuttx/net/netdev/netdev_register.c150
-rw-r--r--nuttx/net/netdev/netdev_rxnotify.c109
-rw-r--r--nuttx/net/netdev/netdev_sem.c179
-rw-r--r--nuttx/net/netdev/netdev_txnotify.c108
-rw-r--r--nuttx/net/netdev/netdev_unregister.c160
11 files changed, 2135 insertions, 0 deletions
diff --git a/nuttx/net/netdev/netdev_carrier.c b/nuttx/net/netdev/netdev_carrier.c
new file mode 100644
index 000000000..07589a64a
--- /dev/null
+++ b/nuttx/net/netdev/netdev_carrier.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * net/netdev/netdev_carrier.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Max Holtzberg <mh@uvc.de>
+ *
+ * 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>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_carrier_on
+ *
+ * Description:
+ * Notifies the uip layer about an available carrier.
+ * (e.g. a cable was plugged in)
+ *
+ * Parameters:
+ * dev - The device driver structure
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ ****************************************************************************/
+
+int netdev_carrier_on(FAR struct uip_driver_s *dev)
+{
+ if (dev)
+ {
+ dev->d_flags |= IFF_RUNNING;
+ return OK;
+ }
+
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Function: netdev_carrier_off
+ *
+ * Description:
+ * Notifies the uip layer about an disappeared carrier.
+ * (e.g. a cable was unplugged)
+ *
+ * Parameters:
+ * dev - The device driver structure
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ ****************************************************************************/
+
+int netdev_carrier_off(FAR struct uip_driver_s *dev)
+{
+ if (dev)
+ {
+ dev->d_flags &= ~IFF_RUNNING;
+ return OK;
+ }
+
+ return -EINVAL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_count.c b/nuttx/net/netdev/netdev_count.c
new file mode 100644
index 000000000..23aac4c99
--- /dev/null
+++ b/nuttx/net/netdev/netdev_count.c
@@ -0,0 +1,103 @@
+/****************************************************************************
+ * net/netdev/netdev_count.c
+ *
+ * Copyright (C) 2007-2009 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_count
+ *
+ * Description:
+ * Return the number of network devices
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * The number of network devices
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_count(void)
+{
+ struct uip_driver_s *dev;
+ int ndev;
+
+ netdev_semtake();
+ for (dev = g_netdevices, ndev = 0; dev; dev = dev->flink, ndev++);
+ netdev_semgive();
+ return ndev;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_findbyaddr.c b/nuttx/net/netdev/netdev_findbyaddr.c
new file mode 100644
index 000000000..0abda865c
--- /dev/null
+++ b/nuttx/net/netdev/netdev_findbyaddr.c
@@ -0,0 +1,215 @@
+/****************************************************************************
+ * net/netdev/netdev_findbyaddr.c
+ *
+ * Copyright (C) 2007-2009, 2014 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+#include "route/route.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_maskcmp
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_finddevice
+ *
+ * Description:
+ * Find a previously registered network device by matching a local address
+ * with the subnet served by the device. Only "up" devices are considered
+ * (since a "down" device has no meaningful address).
+ *
+ * Parameters:
+ * addr - Pointer to the remote address of a connection
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+static FAR struct uip_driver_s *netdev_finddevice(const uip_ipaddr_t addr)
+{
+ struct uip_driver_s *dev;
+
+ /* Examine each registered network device */
+
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ /* Is the interface in the "up" state? */
+
+ if ((dev->d_flags & IFF_UP) != 0)
+ {
+ /* Yes.. check for an address match (under the netmask) */
+
+ if (uip_ipaddr_maskcmp(dev->d_ipaddr, addr, dev->d_netmask))
+ {
+ /* Its a match */
+
+ netdev_semgive();
+ return dev;
+ }
+ }
+ }
+
+ /* No device with the matching address found */
+
+ netdev_semgive();
+ return NULL;
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_findbyaddr
+ *
+ * Description:
+ * Find a previously registered network device by matching an arbitrary
+ * IP address.
+ *
+ * Parameters:
+ * addr - Pointer to the remote address of a connection
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t addr)
+{
+ struct uip_driver_s *dev;
+#ifdef CONFIG_NET_ROUTE
+ uip_ipaddr_t router;
+ int ret;
+#endif
+
+ /* First, see if the address maps to the a local network */
+
+ dev = netdev_finddevice(addr);
+ if (dev)
+ {
+ return dev;
+ }
+
+ /* No.. The address lies on an external network */
+
+#ifdef CONFIG_NET_ROUTE
+ /* If we have a routing table, then perhaps we can find the the local
+ * address of a router that can forward packets to the external network.
+ */
+
+#ifdef CONFIG_NET_IPv6
+ ret = net_router(addr, router);
+#else
+ ret = net_router(addr, &router);
+#endif
+ if (ret >= 0)
+ {
+ /* Success... try to find the network device associated with the local
+ * router address
+ */
+
+ dev = netdev_finddevice(router);
+ if (dev)
+ {
+ return dev;
+ }
+ }
+#endif /* CONFIG_NET_ROUTE */
+
+ /* The above lookup will fail if the packet is being sent out of our
+ * out subnet to a router and there is no routing information.
+ *
+ * However, if there is only a single, registered network interface, then
+ * the decision is pretty easy. Use that device and its default router
+ * address.
+ */
+
+ netdev_semtake();
+ if (g_netdevices && !g_netdevices->flink)
+ {
+ dev = g_netdevices;
+ }
+ netdev_semgive();
+
+ /* If we will did not find the network device, then we might as well fail
+ * because we are not configured properly to determine the route to the
+ * target.
+ */
+
+ return dev;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_findbyname.c b/nuttx/net/netdev/netdev_findbyname.c
new file mode 100644
index 000000000..de351404c
--- /dev/null
+++ b/nuttx/net/netdev/netdev_findbyname.c
@@ -0,0 +1,112 @@
+/****************************************************************************
+ * net/netdev/netdev_findbyname.c
+ *
+ * Copyright (C) 2007, 2008 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <string.h>
+#include <errno.h>
+
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_findbyname
+ *
+ * Description:
+ * Find a previously registered network device using its assigned
+ * network interface name
+ *
+ * Parameters:
+ * ifname The interface name of the device of interest
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+FAR struct uip_driver_s *netdev_findbyname(const char *ifname)
+{
+ struct uip_driver_s *dev;
+ if (ifname)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (strcmp(ifname, dev->d_ifname) == 0)
+ {
+ netdev_semgive();
+ return dev;
+ }
+ }
+ netdev_semgive();
+ }
+ return NULL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_foreach.c b/nuttx/net/netdev/netdev_foreach.c
new file mode 100644
index 000000000..ccec01800
--- /dev/null
+++ b/nuttx/net/netdev/netdev_foreach.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * net/netdev/netdev_foreach.c
+ *
+ * Copyright (C) 2007-2009, 2012 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <debug.h>
+#include <nuttx/net/net.h>
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_foreach
+ *
+ * Description:
+ * Enumerate each registered network device.
+ *
+ * NOTE: netdev semaphore held throughout enumeration.
+ *
+ * Parameters:
+ * callback - Will be called for each registered device
+ * arg - User argument passed to callback()
+ *
+ * Returned Value:
+ * 0:Enumeration completed 1:Enumeration terminated early by callback
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_foreach(netdev_callback_t callback, void *arg)
+{
+ struct uip_driver_s *dev;
+ int ret = 0;
+
+ if (callback)
+ {
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ if (callback(dev, arg) != 0)
+ {
+ ret = 1;
+ break;
+ }
+ }
+ netdev_semgive();
+ }
+ return ret;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_ioctl.c b/nuttx/net/netdev/netdev_ioctl.c
new file mode 100644
index 000000000..6d742701d
--- /dev/null
+++ b/nuttx/net/netdev/netdev_ioctl.c
@@ -0,0 +1,750 @@
+/****************************************************************************
+ * net/netdev/netdev_ioctl.c
+ *
+ * Copyright (C) 2007-2012 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/net.h>
+
+#include <net/if.h>
+#include <net/route.h>
+#include <net/ethernet.h>
+#include <netinet/in.h>
+
+#include <nuttx/net/netdev.h>
+#include <nuttx/net/uip.h>
+
+#ifdef CONFIG_NET_IGMP
+# include "sys/sockio.h"
+# include "nuttx/net/igmp.h"
+#endif
+
+#include "net.h"
+#include "netdev/netdev.h"
+#include "route/route.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+# define AF_INETX AF_INET6
+#else
+# define AF_INETX AF_INET
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ioctl_getipaddr
+ *
+ * Description:
+ * Copy IP addresses from device structure to user memory.
+ *
+ * Input Parameters:
+ * outaddr - Pointer to the user-provided memory to receive the address.
+ * Actual type may be either 'struct sockaddr' (IPv4 only) or type
+ * 'struct sockaddr_storage' (both IPv4 and IPv6).
+ * inaddr - The source IP adress in the device structure.
+ *
+ ****************************************************************************/
+
+static void ioctl_getipaddr(FAR void *outaddr, FAR const uip_ipaddr_t *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR struct sockaddr_in6 *dest = (FAR struct sockaddr_in6 *)outaddr;
+ dest->sin_family = AF_INET6;
+ dest->sin_port = 0;
+ memcpy(dest->sin6_addr.in6_u.u6_addr8, inaddr, 16);
+#else
+ FAR struct sockaddr_in *dest = (FAR struct sockaddr_in *)outaddr;
+ dest->sin_family = AF_INET;
+ dest->sin_port = 0;
+ dest->sin_addr.s_addr = *inaddr;
+#endif
+}
+
+/****************************************************************************
+ * Name: ioctl_setipaddr
+ *
+ * Description:
+ * Copy IP addresses from user memory into the device structure
+ *
+ * Input Parameters:
+ * outaddr - Pointer to the source IP address in the device structure.
+ * inaddr - Pointer to the user-provided memory to containing the new IP
+ * address. Actual type may be either 'struct sockaddr' (IPv4 only) or
+ * type 'struct sockaddr_storage' (both IPv4 and IPv6).
+ *
+ ****************************************************************************/
+
+static void ioctl_setipaddr(FAR uip_ipaddr_t *outaddr, FAR const void *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *src = (FAR const struct sockaddr_in6 *)inaddr;
+ memcpy(outaddr, src->sin6_addr.in6_u.u6_addr8, 16);
+#else
+ FAR const struct sockaddr_in *src = (FAR const struct sockaddr_in *)inaddr;
+ *outaddr = src->sin_addr.s_addr;
+#endif
+}
+
+/****************************************************************************
+ * Name: ioctl_ifup / ioctl_ifdown
+ *
+ * Description:
+ * Bring the interface up/down
+ *
+ ****************************************************************************/
+
+static void ioctl_ifup(FAR struct uip_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 uip_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:
+ * Verify the struct ifreq and get the Ethernet device.
+ *
+ * Parameters:
+ * req - The argument of the ioctl cmd
+ *
+ * Return:
+ * A pointer to the driver structure on success; NULL on failure.
+ *
+ ****************************************************************************/
+
+static FAR struct uip_driver_s *netdev_ifrdev(FAR struct ifreq *req)
+{
+ if (!req)
+ {
+ return NULL;
+ }
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ return netdev_findbyname(req->ifr_name);
+}
+
+/****************************************************************************
+ * Name: netdev_ifrioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * 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)
+ * Negated errno returned on failure.
+ *
+ ****************************************************************************/
+
+static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
+ FAR struct ifreq *req)
+{
+ FAR struct uip_driver_s *dev;
+ int ret = -EINVAL;
+
+ nvdbg("cmd: %d\n", cmd);
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCGIFADDR: /* Get IP address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCSIFADDR: /* Set IP address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_ifdown(dev);
+ ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr);
+ ioctl_ifup(dev);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCGIFDSTADDR: /* Get P-to-P address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCSIFDSTADDR: /* Set P-to-P address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCGIFNETMASK: /* Get network mask */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCSIFNETMASK: /* Set network mask */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCGIFMTU: /* Get MTU size */
+ {
+ req->ifr_mtu = CONFIG_NET_BUFSIZE;
+ ret = OK;
+ }
+ break;
+
+ case SIOCSIFFLAGS: /* Sets the interface flags */
+ {
+ /* Is this a request to bring the interface up? */
+
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ if (req->ifr_flags & IFF_UP)
+ {
+ /* Yes.. bring the interface up */
+
+ ioctl_ifup(dev);
+ }
+
+ /* Is this a request to take the interface down? */
+
+ else if (req->ifr_flags & IFF_DOWN)
+ {
+ /* Yes.. take the interface down */
+
+ ioctl_ifdown(dev);
+ }
+ }
+
+ ret = OK;
+ }
+ break;
+
+ case SIOCGIFFLAGS: /* Gets the interface flags */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ req->ifr_flags = dev->d_flags;
+ }
+
+ ret = OK;
+ }
+ break;
+
+ /* MAC address operations only make sense if Ethernet is supported */
+
+#ifdef CONFIG_NET_ETHERNET
+ case SIOCGIFHWADDR: /* Get hardware address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ req->ifr_hwaddr.sa_family = AF_INETX;
+ memcpy(req->ifr_hwaddr.sa_data,
+ dev->d_mac.ether_addr_octet, IFHWADDRLEN);
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCSIFHWADDR: /* Set hardware address -- will not take effect until ifup */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ req->ifr_hwaddr.sa_family = AF_INETX;
+ memcpy(dev->d_mac.ether_addr_octet,
+ req->ifr_hwaddr.sa_data, IFHWADDRLEN);
+ ret = OK;
+ }
+ }
+ break;
+#endif
+
+ case SIOCDIFADDR: /* Delete IP address */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ ioctl_ifdown(dev);
+ memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t));
+ ret = OK;
+ }
+ }
+ break;
+
+ case SIOCGIFCOUNT: /* Get number of devices */
+ {
+ req->ifr_count = netdev_count();
+ ret = -ENOSYS;
+ }
+ break;
+
+ case SIOCGIFBRDADDR: /* Get broadcast IP address */
+ case SIOCSIFBRDADDR: /* Set broadcast IP address */
+ {
+ ret = -ENOSYS;
+ }
+ break;
+
+#ifdef CONFIG_NET_ARPIOCTLS
+ case SIOCSARP: /* Set a ARP mapping */
+ case SIOCDARP: /* Delete an ARP mapping */
+ case SIOCGARP: /* Get an ARP mapping */
+# error "IOCTL Commands not implemented"
+#endif
+
+ default:
+ {
+ ret = -ENOTTY;
+ }
+ break;;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: netdev_imsfdev
+ *
+ * Description:
+ * Verify the struct ip_msfilter and get the Ethernet device.
+ *
+ * Parameters:
+ * req - The argument of the ioctl cmd
+ *
+ * Return:
+ * A pointer to the driver structure on success; NULL on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static FAR struct uip_driver_s *netdev_imsfdev(FAR struct ip_msfilter *imsf)
+{
+ if (!imsf)
+ {
+ return NULL;
+ }
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ return netdev_findbyname(imsf->imsf_name);
+}
+#endif
+
+/****************************************************************************
+ * 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,
+ FAR struct ip_msfilter *imsf)
+{
+ FAR struct uip_driver_s *dev;
+ int ret = -EINVAL;
+
+ nvdbg("cmd: %d\n", cmd);
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCSIPMSFILTER: /* Set source filter content */
+ {
+ dev = netdev_imsfdev(imsf);
+ if (dev)
+ {
+ 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 = -ENOTTY;
+ break;
+ }
+
+ return ret;
+}
+#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 = -EINVAL;
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCADDRT: /* Add an entry to the routing table */
+ {
+ if (rtentry)
+ {
+ uip_ipaddr_t target;
+ uip_ipaddr_t netmask;
+ uip_ipaddr_t router;
+#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 router is an optional argument */
+
+ if (rtentry->rt_router)
+ {
+ addr = (FAR struct sockaddr_in6 *)rtentry->rt_router;
+ router = (uip_ipaddr_t)addr->sin6_addr.u6_addr16;
+ }
+ else
+ {
+ router = 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 router is an optional argument */
+
+ if (rtentry->rt_router)
+ {
+ addr = (FAR struct sockaddr_in *)rtentry->rt_router;
+ router = (uip_ipaddr_t)addr->sin_addr.s_addr;
+ }
+ else
+ {
+ router = 0;
+ }
+#endif
+ ret = net_addroute(target, netmask, router);
+ }
+ }
+ break;
+
+ case SIOCDELRT: /* Delete an entry from the routing table */
+ {
+ if (rtentry)
+ {
+ 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
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: netdev_ioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of device
+ * cmd The ioctl command
+ * arg 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
+ * 'arg' references an inaccessible memory area.
+ * ENOTTY
+ * 'cmd' not valid.
+ * EINVAL
+ * 'arg' 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))
+ {
+ ret = -ENOTTY;
+ 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*)((uintptr_t)arg));
+#ifdef CONFIG_NET_IGMP
+ 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_rtioctl(psock, cmd, (FAR struct rtentry*)((uintptr_t)arg));
+ }
+#endif
+
+ /* Check for success or failure */
+
+ if (ret >= 0)
+ {
+ return ret;
+ }
+
+/* On failure, set the errno and return -1 */
+
+errout:
+ errno = -ret;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_register.c b/nuttx/net/netdev/netdev_register.c
new file mode 100644
index 000000000..da48bf7a3
--- /dev/null
+++ b/nuttx/net/netdev/netdev_register.c
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * net/netdev/netdev_register.c
+ *
+ * Copyright (C) 2007-2012 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_SLIP
+# define NETDEV_FORMAT "sl%d"
+#else
+# define NETDEV_FORMAT "eth%d"
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int g_next_devnum = 0;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* List of registered ethernet device drivers */
+
+struct uip_driver_s *g_netdevices = NULL;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_register
+ *
+ * Description:
+ * Register a network device driver and assign a name to it so tht it can
+ * be found in subsequent network ioctl operations on the device.
+ *
+ * Parameters:
+ * dev - The device driver structure to register
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ * Assumptions:
+ * Called during system initialization from normal user mode
+ *
+ ****************************************************************************/
+
+int netdev_register(FAR struct uip_driver_s *dev)
+{
+ if (dev)
+ {
+ int devnum;
+ netdev_semtake();
+
+ /* Assign a device name to the interface */
+
+ devnum = g_next_devnum++;
+ snprintf(dev->d_ifname, IFNAMSIZ, NETDEV_FORMAT, devnum );
+
+ /* Add the device to the list of known network devices */
+
+ dev->flink = g_netdevices;
+ g_netdevices = dev;
+
+ /* Configure the device for IGMP support */
+
+#ifdef CONFIG_NET_IGMP
+ igmp_devinit(dev);
+#endif
+ netdev_semgive();
+
+#ifdef CONFIG_NET_ETHERNET
+ nlldbg("Registered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
+ dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
+ dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
+ dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5],
+ dev->d_ifname);
+#else
+ nlldbg("Registered dev: %s\n", dev->d_ifname);
+#endif
+ return OK;
+ }
+ return -EINVAL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_rxnotify.c b/nuttx/net/netdev/netdev_rxnotify.c
new file mode 100644
index 000000000..1187cd0d6
--- /dev/null
+++ b/nuttx/net/netdev/netdev_rxnotify.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * net/netdev/netdev_rxnotify.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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET_RXAVAIL)
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_rxnotify
+ *
+ * Description:
+ * Notify the device driver that the application waits for RX data.
+ *
+ * Parameters:
+ * raddr - The remote address to send the data
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+void netdev_rxnotify(const uip_ipaddr_t raddr)
+{
+
+ /* Find the device driver that serves the subnet of the remote address */
+
+ struct uip_driver_s *dev = netdev_findbyaddr(raddr);
+
+ if (dev && dev->d_rxavail)
+ {
+ /* Notify the device driver that new RX data is available. */
+
+ (void)dev->d_rxavail(dev);
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS && CONFIG_NET_RXAVAIL */
diff --git a/nuttx/net/netdev/netdev_sem.c b/nuttx/net/netdev/netdev_sem.c
new file mode 100644
index 000000000..cf6557999
--- /dev/null
+++ b/nuttx/net/netdev/netdev_sem.c
@@ -0,0 +1,179 @@
+/****************************************************************************
+ * net/netdev/netdev_sem.c
+ *
+ * Copyright (C) 2012 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+
+#include <unistd.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define NO_HOLDER (pid_t)-1
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/* There is at least on context in which recursive semaphores are required:
+ * When netdev_foreach is used with a telnet client, we will deadlock if we
+ * do not provide this capability.
+ */
+
+struct netdev_sem_s
+{
+ sem_t sem;
+ pid_t holder;
+ unsigned int count;
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+static struct netdev_sem_s g_devlock;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_seminit
+ *
+ * Description:
+ * Initialize the network device semaphore.
+ *
+ ****************************************************************************/
+
+void netdev_seminit(void)
+{
+ sem_init(&g_devlock.sem, 0, 1);
+ g_devlock.holder = NO_HOLDER;
+ g_devlock.count = 0;
+}
+
+/****************************************************************************
+ * Function: netdev_semtake
+ *
+ * Description:
+ * Get exclusive access to the network device list.
+ *
+ ****************************************************************************/
+
+void netdev_semtake(void)
+{
+ pid_t me = getpid();
+
+ /* Does this thread already hold the semaphore? */
+
+ if (g_devlock.holder == me)
+ {
+ /* Yes.. just increment the reference count */
+
+ g_devlock.count++;
+ }
+ else
+ {
+ /* No.. take the semaphore (perhaps waiting) */
+
+ while (net_lockedwait(&g_devlock.sem) != 0)
+ {
+ /* The only case that an error should occur here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+
+ /* Now this thread holds the semaphore */
+
+ g_devlock.holder = me;
+ g_devlock.count = 1;
+ }
+}
+
+/****************************************************************************
+ * Function: netdev_semtake
+ *
+ * Description:
+ * Release exclusive access to the network device list
+ *
+ ****************************************************************************/
+
+void netdev_semgive(void)
+{
+ DEBUGASSERT(g_devlock.holder == getpid() && g_devlock.count > 0);
+
+ /* If the count would go to zero, then release the semaphore */
+
+ if (g_devlock.count == 1)
+ {
+ /* We no longer hold the semaphore */
+
+ g_devlock.holder = NO_HOLDER;
+ g_devlock.count = 0;
+ sem_post(&g_devlock.sem);
+ }
+ else
+ {
+ /* We still hold the semaphore. Just decrement the count */
+
+ g_devlock.count--;
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_txnotify.c b/nuttx/net/netdev/netdev_txnotify.c
new file mode 100644
index 000000000..d6aea425a
--- /dev/null
+++ b/nuttx/net/netdev/netdev_txnotify.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ * net/netdev/netdev_txnotify.c
+ *
+ * Copyright (C) 2007-2009, 2012 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_txnotify
+ *
+ * Description:
+ * Notify the device driver that new TX data is available.
+ *
+ * Parameters:
+ * raddr - The remote address to send the data
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+void netdev_txnotify(const uip_ipaddr_t raddr)
+{
+ /* Find the device driver that serves the subnet of the remote address */
+
+ struct uip_driver_s *dev = netdev_findbyaddr(raddr);
+
+ if (dev && dev->d_txavail)
+ {
+ /* Notify the device driver that new TX data is available. */
+
+ (void)dev->d_txavail(dev);
+ }
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_unregister.c b/nuttx/net/netdev/netdev_unregister.c
new file mode 100644
index 000000000..35108ba98
--- /dev/null
+++ b/nuttx/net/netdev/netdev_unregister.c
@@ -0,0 +1,160 @@
+/****************************************************************************
+ * net/netdev/netdev_unregister.c
+ *
+ * Copyright (C) 2011 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <nuttx/net/netdev.h>
+
+#include "net.h"
+#include "netdev/netdev.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_SLIP
+# define NETDEV_FORMAT "sl%d"
+#else
+# define NETDEV_FORMAT "eth%d"
+#endif
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_unregister
+ *
+ * Description:
+ * Unregister a network device driver.
+ *
+ * Parameters:
+ * dev - The device driver structure to un-register
+ *
+ * Returned Value:
+ * 0:Success; negated errno on failure
+ *
+ * Assumptions:
+ * Currently only called for USB networking devices when the device is
+ * physically removed from the slot
+ *
+ ****************************************************************************/
+
+int netdev_unregister(FAR struct uip_driver_s *dev)
+{
+ struct uip_driver_s *prev;
+ struct uip_driver_s *curr;
+
+ if (dev)
+ {
+ netdev_semtake();
+
+ /* Find the device in the list of known network devices */
+
+ for (prev = NULL, curr = g_netdevices;
+ curr && curr != dev;
+ prev = curr, curr = curr->flink);
+
+ /* Remove the device to the list of known network devices */
+
+ if (curr)
+ {
+ /* Where was the entry */
+
+ if (prev)
+ {
+ /* The entry was in the middle or at the end of the list */
+
+ prev->flink = curr->flink;
+ }
+ else
+ {
+ /* The entry was at the beginning of the list */
+
+ g_netdevices = curr;
+ }
+
+ curr->flink = NULL;
+ }
+
+ netdev_semgive();
+
+#ifdef CONFIG_NET_ETHERNET
+ nlldbg("Unregistered MAC: %02x:%02x:%02x:%02x:%02x:%02x as dev: %s\n",
+ dev->d_mac.ether_addr_octet[0], dev->d_mac.ether_addr_octet[1],
+ dev->d_mac.ether_addr_octet[2], dev->d_mac.ether_addr_octet[3],
+ dev->d_mac.ether_addr_octet[4], dev->d_mac.ether_addr_octet[5],
+ dev->d_ifname);
+#else
+ nlldbg("Registered dev: %s\n", dev->d_ifname);
+#endif
+ return OK;
+ }
+
+ return -EINVAL;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */