summaryrefslogtreecommitdiff
path: root/nuttx/include/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-16 17:46:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-16 17:46:25 +0000
commit4077a70fc256a7dd65febe986f176b8ac62091fc (patch)
tree6f0e34d559c8fa2f07c686043df3494cd7fdcff2 /nuttx/include/net
parent42027d080b72b8198072e7dc3933d8b70b6b40a5 (diff)
downloadpx4-nuttx-4077a70fc256a7dd65febe986f176b8ac62091fc.tar.gz
px4-nuttx-4077a70fc256a7dd65febe986f176b8ac62091fc.tar.bz2
px4-nuttx-4077a70fc256a7dd65febe986f176b8ac62091fc.zip
Add basic structure to support netdevice ioctls
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@344 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include/net')
-rw-r--r--nuttx/include/net/ioctls.h104
-rw-r--r--nuttx/include/net/uip/uip-arch.h21
2 files changed, 122 insertions, 3 deletions
diff --git a/nuttx/include/net/ioctls.h b/nuttx/include/net/ioctls.h
new file mode 100644
index 000000000..d95371190
--- /dev/null
+++ b/nuttx/include/net/ioctls.h
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * net/ioctls.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __NET_IOCTLS_H
+#define __NET_IOCTLS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/socket.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* These are ioctl commands to use with a socket FD. At present, commnads
+ * are accepted onloy to set/get IP addresses, broadcast address, network
+ * masks, and hardware address, and a few others
+ */
+
+#define _SIOCBASE (0x8900)
+#define _SIOCMASK (0x00ff)
+#define _SIOCVALID(c) (((c) & ~_SIOCMASK) == _SIOCBASE)
+
+#define SIOCGIFADDR (_SIOCBASE|0x0001) /* Get IP address */
+#define SIOCSIFADDR (_SIOCBASE|0x0002) /* Set IP address */
+#define SIOCGIFBRDADDR (_SIOCBASE|0x0003) /* Get broadcast IP address */
+#define SIOCSIFBRDADDR (_SIOCBASE|0x0004) /* Set broadcast IP address */
+#define SIOCGIFNETMASK (_SIOCBASE|0x0005) /* Get network mask */
+#define SIOCSIFNETMASK (_SIOCBASE|0x0006) /* Set network mask */
+#define SIOCGIFMTU (_SIOCBASE|0x0007) /* Get MTU size */
+#define SIOCSIFHWADDR (_SIOCBASE|0x0008) /* Set hardware address */
+#define SIOCGIFHWADDR (_SIOCBASE|0x0009) /* Get hardware address */
+#define SIOCDIFADDR (_SIOCBASE|0x000a) /* Delete IP address */
+#define SIOCGIFCOUNT (_SIOCBASE|0x000b) /* Get number of devices */
+
+/* Sizing parameters */
+
+#define IFNAMSIZ 6
+#define IFHWADDRLEN 6
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+struct ifreq
+{
+ char ifr_name[IFNAMSIZ]; /* Network device name (e.g. "eth0") */
+ union
+ {
+ struct sockaddr ifru_addr; /* IP Address */
+ struct sockaddr ifru_broadaddr; /* Broadcast address */
+ struct sockaddr ifru_netmask; /* Netmask */
+ struct sockaddr ifru_hwaddr; /* MAC address */
+ int ifru_count; /* Number of devices */
+ int ifru_mtu; /* MTU size */
+ } ifr_ifru;
+};
+
+#define ifr_addr ifr_ifru.ifru_addr /* Address */
+#define ifr_broadaddr ifr_ifru.ifru_broadaddr /* Broadcast address */
+#define ifr_netmask ifr_ifru.ifru_netmask /* Interface net mask */
+#define ifr_hwaddr ifr_ifru.ifru_hwaddr /* MAC address */
+#define ifr_mtu ifr_ifru.ifru_mtu /* MTU */
+#define ifr_count ifr_ifru.ifru_count /* Number of devices */
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __NET_IOCTLS_H */
diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h
index 56a794b3c..e54956888 100644
--- a/nuttx/include/net/uip/uip-arch.h
+++ b/nuttx/include/net/uip/uip-arch.h
@@ -42,7 +42,9 @@
#ifndef __UIP_ARCH_H
#define __UIP_ARCH_H
+#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/ioctl.h>
#include <net/uip/uip.h>
/****************************************************************************
@@ -84,9 +86,22 @@
struct uip_driver_s
{
- /* The uIP packet buffer.
- *
- * The d_buf array is used to hold incoming and outgoing
+ /* This link is used to maintain a single-linked list of ethernet drivers.
+ * Must be the first field in the structure due to blink type casting.
+ */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ FAR struct uip_driver_s *flink;
+
+ /* This is the name of network device assigned when netdev_register was called.
+ * This name is only used to support socket ioctl lookups by device name
+ * Examples: "eth0"
+ */
+
+ char d_ifname[IFNAMSIZ];
+#endif
+
+ /* The d_buf array is used to hold incoming and outgoing
* packets. The device driver should place incoming data into this
* buffer. When sending data, the device driver should read the link
* level headers and the TCP/IP headers from this buffer. The size of