summaryrefslogtreecommitdiff
path: root/nuttx/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/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/net')
-rw-r--r--nuttx/net/Makefile15
-rw-r--r--nuttx/net/net-internal.h20
-rw-r--r--nuttx/net/net-sockets.c18
-rw-r--r--nuttx/net/netdev-find.c116
-rw-r--r--nuttx/net/netdev-ioctl.c90
-rw-r--r--nuttx/net/netdev-register.c147
-rw-r--r--nuttx/net/uip/uip-arp.c330
-rw-r--r--nuttx/net/uip/uip-send.c2
-rw-r--r--nuttx/net/uip/uip.c8
9 files changed, 588 insertions, 158 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 2257e446e..eae467517 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -39,24 +39,27 @@ CFLAGS += -I./uip
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ifeq ($(CONFIG_NET),y)
-STD_ASRCS =
-STD_CSRCS = socket.c bind.c connect.c send.c sendto.c recv.c recvfrom.c \
+SOCK_ASRCS =
+SOCK_CSRCS = socket.c bind.c connect.c send.c sendto.c recv.c recvfrom.c \
net-sockets.c net-close.c
ifeq ($(CONFIG_NET_SOCKOPTS),y)
-STD_CSRCS += setsockopt.c getsockopt.c
+SOCK_CSRCS += setsockopt.c getsockopt.c
ifneq ($(CONFIG_DISABLE_CLOCK),y)
-STD_CSRCS += net-timeo.c net-dsec2timeval.c net-timeval2dsec.c
+SOCK_CSRCS += net-timeo.c net-dsec2timeval.c net-timeval2dsec.c
endif
endif
+NETDEV_ASRCS =
+NETDEV_CSRCS = netdev-register.c netdev-ioctl.c netdev-find.c
+
include uip/Make.defs
endif
-ASRCS = $(STD_ASRCS) $(UIP_ASRCS)
+ASRCS = $(SOCK_ASRCS) $(NETDEV_ASRCS) $(UIP_ASRCS)
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = $(STD_CSRCS) $(UIP_CSRCS)
+CSRCS = $(SOCK_CSRCS) $(NETDEV_CSRCS) $(UIP_CSRCS)
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index f517f863d..220f46b54 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -122,6 +122,13 @@
* Public Variables
****************************************************************************/
+/* List of registered ethernet device drivers */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+extern struct uip_driver_s *g_netdevices;
+extern sem_t g_netdev_sem;
+#endif
+
/****************************************************************************
* Pulblic Function Prototypes
****************************************************************************/
@@ -148,6 +155,19 @@ EXTERN socktimeo_t net_timeval2dsec(struct timeval *tv);
EXTERN void net_dsec2timeval(uint16 dsec, struct timeval *tv);
#endif
+/* net-register.c ************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN void netdev_semtake(void);
+# define netdev_semgive() sem_post(&g_netdev_sem)
+#endif
+
+/* net-find.c ****************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+FAR struct uip_driver_s *netdev_find(const char *ifname);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/net/net-sockets.c b/nuttx/net/net-sockets.c
index 3a6821051..db5c48ac8 100644
--- a/nuttx/net/net-sockets.c
+++ b/nuttx/net/net-sockets.c
@@ -38,6 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#ifdef CONFIG_NET
#include <string.h>
#include <semaphore.h>
@@ -71,6 +72,7 @@
* Private Functions
****************************************************************************/
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
static void _net_semtake(FAR struct socketlist *list)
{
/* Take the semaphore (perhaps waiting) */
@@ -85,10 +87,11 @@ static void _net_semtake(FAR struct socketlist *list)
}
}
-#define _net_semgive(list) sem_post(&list->sl_sem)
+# define _net_semgive(list) sem_post(&list->sl_sem)
+#endif
/****************************************************************************
- * Pulblic Functions
+ * Public Functions
****************************************************************************/
/* This is called from the initialization logic to configure the socket layer */
@@ -99,9 +102,15 @@ void net_initialize(void)
uip_init();
- /* Initialize the socket lay -- nothing to do */
+ /* Initialize the socket layer */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ sem_init(&g_netdev_sem, 0, 1);
+#endif
}
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+
/* Allocate a list of files for a new task */
FAR struct socketlist *net_alloclist(void)
@@ -261,3 +270,6 @@ FAR struct socket *sockfd_socket(int sockfd)
}
return NULL;
}
+
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* CONFIG_NET */ \ No newline at end of file
diff --git a/nuttx/net/netdev-find.c b/nuttx/net/netdev-find.c
new file mode 100644
index 000000000..c783f8c6f
--- /dev/null
+++ b/nuttx/net/netdev-find.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * net/netdev-find.c
+ *
+ * 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 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 <errno.h>
+
+#include <net/uip/uip-arch.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int g_next_devnum = 0;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* List of registered ethernet device drivers */
+struct uip_driver_s *g_netdevices;
+sem_t g_netdev_sem;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_find
+ *
+ * Description:
+ * Find a previously registered network device
+ *
+ * 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_find(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-ioctl.c b/nuttx/net/netdev-ioctl.c
new file mode 100644
index 000000000..3e8c1a933
--- /dev/null
+++ b/nuttx/net/netdev-ioctl.c
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * net/netdev-ioctl.c
+ *
+ * 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 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 <sys/socket.h>
+#include <errno.h>
+#include <nuttx/net.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: netdev_ioctl
+ *
+ * Description:
+ * Perform network device specific operations.
+ *
+ * Parameters:
+ * fd Socket descriptor of device
+ * cmd The ioctl command
+ * req The argument of the ioctl cmd
+ *
+ * Return:
+ * >=0 on success (positive non-zero values are cmd-specific)
+ * -1 on failure withi errno set properly:
+ *
+ * EBADF
+ * 'fd' is not a valid descriptor.
+ * EFAULT
+ * 'arg' references an inaccessible memory area.
+ * EINVAL
+ * 'cmd' or 'arg' is not valid.
+ * ENOTTY
+ * 'fd' is not associated with a character special device.
+ * ENOTTY
+ * The specified request does not apply to the kind of object that the
+ * descriptor 'fd' references.
+ *
+ ****************************************************************************/
+
+int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
+{
+#warning "Network ioctls not implemented"
+ *get_errno_ptr() = ENOSYS;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev-register.c b/nuttx/net/netdev-register.c
new file mode 100644
index 000000000..736c5e782
--- /dev/null
+++ b/nuttx/net/netdev-register.c
@@ -0,0 +1,147 @@
+/****************************************************************************
+ * net/netdev-register.c
+ *
+ * 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 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 <sys/socket.h>
+#include <stdio.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+
+#include <net/uip/uip-arch.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int g_next_devnum = 0;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* List of registered ethernet device drivers */
+struct uip_driver_s *g_netdevices = NULL;
+sem_t g_netdev_sem;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: netdev_semtake
+ *
+ * Description:
+ * Managed access to the network device list
+ *
+ ****************************************************************************/
+
+void netdev_semtake(void)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&g_netdev_sem) != 0)
+ {
+ /* The only case that an error should occr here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(*get_errno_ptr() == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Function: netdev_register
+ *
+ * Description:
+ * Register a netword 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; -1 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 the interface */
+
+ devnum = g_next_devnum++;
+ snprintf( dev->d_ifname, IFNAMSIZ, "eth%d", devnum );
+
+ /* Add the device to the list of known network devices */
+
+ dev->flink = g_netdevices;
+ g_netdevices = dev;
+ netdev_semgive();
+ return OK;
+ }
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index ac2a952c7..9e029f372 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -102,9 +102,10 @@ static uint8 tmpage;
void uip_arp_init(void)
{
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
- memset(arp_table[i].ipaddr, 0, 4);
- }
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ memset(arp_table[i].ipaddr, 0, 4);
+ }
}
/* Periodic ARP processing function.
@@ -119,73 +120,87 @@ void uip_arp_timer(void)
struct arp_entry *tabptr;
++arptime;
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
- tabptr = &arp_table[i];
- if((tabptr->ipaddr[0] | tabptr->ipaddr[1]) != 0 &&
- arptime - tabptr->time >= UIP_ARP_MAXAGE) {
- memset(tabptr->ipaddr, 0, 4);
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &arp_table[i];
+ if ((tabptr->ipaddr[0] | tabptr->ipaddr[1]) != 0 && arptime - tabptr->time >= UIP_ARP_MAXAGE)
+ {
+ memset(tabptr->ipaddr, 0, 4);
+ }
}
- }
-
}
static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
{
- register struct arp_entry *tabptr;
+ struct arp_entry *tabptr;
+
/* Walk through the ARP mapping table and try to find an entry to
- update. If none is found, the IP -> MAC address mapping is
- inserted in the ARP table. */
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
-
- tabptr = &arp_table[i];
- /* Only check those entries that are actually in use. */
- if(tabptr->ipaddr[0] != 0 &&
- tabptr->ipaddr[1] != 0) {
-
- /* Check if the source IP address of the incoming packet matches
- the IP address in this ARP table entry. */
- if(pipaddr[0] == tabptr->ipaddr[0] &&
- pipaddr[1] == tabptr->ipaddr[1]) {
-
- /* An old entry found, update this and return. */
- memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
- tabptr->time = arptime;
-
- return;
- }
+ * update. If none is found, the IP -> MAC address mapping is
+ * inserted in the ARP table.
+ */
+
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &arp_table[i];
+
+ /* Only check those entries that are actually in use. */
+
+ if (tabptr->ipaddr[0] != 0 && tabptr->ipaddr[1] != 0)
+ {
+ /* Check if the source IP address of the incoming packet matches
+ * the IP address in this ARP table entry.
+ */
+
+ if (pipaddr[0] == tabptr->ipaddr[0] && pipaddr[1] == tabptr->ipaddr[1])
+ {
+ /* An old entry found, update this and return. */
+ memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
+ tabptr->time = arptime;
+
+ return;
+ }
+ }
}
- }
/* If we get here, no existing ARP table entry was found, so we
create one. */
/* First, we try to find an unused entry in the ARP table. */
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
- tabptr = &arp_table[i];
- if(tabptr->ipaddr[0] == 0 &&
- tabptr->ipaddr[1] == 0) {
- break;
+
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &arp_table[i];
+ if (tabptr->ipaddr[0] == 0 && tabptr->ipaddr[1] == 0)
+ {
+ break;
+ }
}
- }
/* If no unused entry is found, we try to find the oldest entry and
- throw it away. */
- if(i == UIP_ARPTAB_SIZE) {
- tmpage = 0;
- c = 0;
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
+ * throw it away.
+ */
+
+ if (i == UIP_ARPTAB_SIZE)
+ {
+ tmpage = 0;
+ c = 0;
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &arp_table[i];
+ if (arptime - tabptr->time > tmpage)
+ {
+ tmpage = arptime - tabptr->time;
+ c = i;
+ }
+ }
+ i = c;
tabptr = &arp_table[i];
- if(arptime - tabptr->time > tmpage) {
- tmpage = arptime - tabptr->time;
- c = i;
- }
}
- i = c;
- tabptr = &arp_table[i];
- }
/* Now, i is the ARP table entry which we will fill with the new
- information. */
+ * information.
+ */
+
memcpy(tabptr->ipaddr, pipaddr, 4);
memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
tabptr->time = arptime;
@@ -210,17 +225,16 @@ void uip_arp_ipin(void)
/* Only insert/update an entry if the source IP address of the
incoming IP packet comes from a host on the local network. */
- if((IPBUF->srcipaddr[0] & uip_netmask[0]) !=
- (uip_hostaddr[0] & uip_netmask[0])) {
- return;
- }
- if((IPBUF->srcipaddr[1] & uip_netmask[1]) !=
- (uip_hostaddr[1] & uip_netmask[1])) {
- return;
- }
- uip_arp_update(IPBUF->srcipaddr, &(IPBUF->ethhdr.src));
+ if ((IPBUF->srcipaddr[0] & uip_netmask[0]) != (uip_hostaddr[0] & uip_netmask[0]))
+ {
+ return;
+ }
- return;
+ if ((IPBUF->srcipaddr[1] & uip_netmask[1]) != (uip_hostaddr[1] & uip_netmask[1]))
+ {
+ return;
+ }
+ uip_arp_update(IPBUF->srcipaddr, &(IPBUF->ethhdr.src));
}
#endif /* 0 */
@@ -247,49 +261,57 @@ void uip_arp_ipin(void)
void uip_arp_arpin(struct uip_driver_s *dev)
{
- if(dev->d_len < sizeof(struct arp_hdr)) {
- dev->d_len = 0;
- return;
- }
+ if (dev->d_len < sizeof(struct arp_hdr))
+ {
+ dev->d_len = 0;
+ return;
+ }
dev->d_len = 0;
- switch(BUF->opcode) {
- case HTONS(ARP_REQUEST):
- /* ARP request. If it asked for our address, we send out a
- reply. */
- if(uip_ipaddr_cmp(BUF->dipaddr, uip_hostaddr)) {
- /* First, we register the one who made the request in our ARP
- table, since it is likely that we will do more communication
- with this host in the future. */
- uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
-
- /* The reply opcode is 2. */
- BUF->opcode = HTONS(2);
-
- memcpy(BUF->dhwaddr.addr, BUF->shwaddr.addr, 6);
- memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
- memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
- memcpy(BUF->ethhdr.dest.addr, BUF->dhwaddr.addr, 6);
-
- BUF->dipaddr[0] = BUF->sipaddr[0];
- BUF->dipaddr[1] = BUF->sipaddr[1];
- BUF->sipaddr[0] = uip_hostaddr[0];
- BUF->sipaddr[1] = uip_hostaddr[1];
-
- BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
- dev->d_len = sizeof(struct arp_hdr);
- }
- break;
- case HTONS(ARP_REPLY):
- /* ARP reply. We insert or update the ARP table if it was meant
- for us. */
- if(uip_ipaddr_cmp(BUF->dipaddr, uip_hostaddr)) {
- uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
+ switch(BUF->opcode)
+ {
+ case HTONS(ARP_REQUEST):
+ /* ARP request. If it asked for our address, we send out a reply. */
+
+ if (uip_ipaddr_cmp(BUF->dipaddr, uip_hostaddr))
+ {
+ /* First, we register the one who made the request in our ARP
+ * table, since it is likely that we will do more communication
+ * with this host in the future.
+ */
+
+ uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
+
+ /* The reply opcode is 2. */
+
+ BUF->opcode = HTONS(2);
+
+ memcpy(BUF->dhwaddr.addr, BUF->shwaddr.addr, 6);
+ memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
+ memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
+ memcpy(BUF->ethhdr.dest.addr, BUF->dhwaddr.addr, 6);
+
+ BUF->dipaddr[0] = BUF->sipaddr[0];
+ BUF->dipaddr[1] = BUF->sipaddr[1];
+ BUF->sipaddr[0] = uip_hostaddr[0];
+ BUF->sipaddr[1] = uip_hostaddr[1];
+
+ BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
+ dev->d_len = sizeof(struct arp_hdr);
+ }
+ break;
+
+ case HTONS(ARP_REPLY):
+ /* ARP reply. We insert or update the ARP table if it was meant
+ * for us.
+ */
+
+ if (uip_ipaddr_cmp(BUF->dipaddr, uip_hostaddr))
+ {
+ uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
+ }
+ break;
}
- break;
- }
-
- return;
}
/* Prepend Ethernet header to an outbound IP packet and see if we need
@@ -329,54 +351,70 @@ void uip_arp_out(struct uip_driver_s *dev)
packet with an ARP request for the IP address. */
/* First check if destination is a local broadcast. */
- if(uip_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr)) {
- memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, 6);
- } else {
- /* Check if the destination address is on the local network. */
- if(!uip_ipaddr_maskcmp(IPBUF->destipaddr, uip_hostaddr, uip_netmask)) {
- /* Destination address was not on the local network, so we need to
- use the default router's IP address instead of the destination
- address when determining the MAC address. */
- uip_ipaddr_copy(ipaddr, uip_draddr);
- } else {
- /* Else, we use the destination IP address. */
- uip_ipaddr_copy(ipaddr, IPBUF->destipaddr);
- }
- for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
- tabptr = &arp_table[i];
- if(uip_ipaddr_cmp(ipaddr, tabptr->ipaddr)) {
- break;
- }
+ if (uip_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr))
+ {
+ memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, 6);
}
-
- if(i == UIP_ARPTAB_SIZE) {
- /* The destination address was not in our ARP table, so we
- overwrite the IP packet with an ARP request. */
-
- memset(BUF->ethhdr.dest.addr, 0xff, 6);
- memset(BUF->dhwaddr.addr, 0x00, 6);
- memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
- memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
-
- uip_ipaddr_copy(BUF->dipaddr, ipaddr);
- uip_ipaddr_copy(BUF->sipaddr, uip_hostaddr);
- BUF->opcode = HTONS(ARP_REQUEST); /* ARP request. */
- BUF->hwtype = HTONS(ARP_HWTYPE_ETH);
- BUF->protocol = HTONS(UIP_ETHTYPE_IP);
- BUF->hwlen = 6;
- BUF->protolen = 4;
- BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
-
- dev->d_appdata = &dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN];
-
- dev->d_len = sizeof(struct arp_hdr);
- return;
+ else
+ {
+ /* Check if the destination address is on the local network. */
+
+ if (!uip_ipaddr_maskcmp(IPBUF->destipaddr, uip_hostaddr, uip_netmask))
+ {
+ /* Destination address was not on the local network, so we need to
+ * use the default router's IP address instead of the destination
+ * address when determining the MAC address.
+ */
+
+ uip_ipaddr_copy(ipaddr, uip_draddr);
+ }
+ else
+ {
+ /* Else, we use the destination IP address. */
+
+ uip_ipaddr_copy(ipaddr, IPBUF->destipaddr);
+ }
+
+ for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
+ {
+ tabptr = &arp_table[i];
+ if (uip_ipaddr_cmp(ipaddr, tabptr->ipaddr))
+ {
+ break;
+ }
+ }
+
+ if (i == UIP_ARPTAB_SIZE)
+ {
+ /* The destination address was not in our ARP table, so we
+ * overwrite the IP packet with an ARP request.
+ */
+
+ memset(BUF->ethhdr.dest.addr, 0xff, 6);
+ memset(BUF->dhwaddr.addr, 0x00, 6);
+ memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
+ memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
+
+ uip_ipaddr_copy(BUF->dipaddr, ipaddr);
+ uip_ipaddr_copy(BUF->sipaddr, uip_hostaddr);
+ BUF->opcode = HTONS(ARP_REQUEST); /* ARP request. */
+ BUF->hwtype = HTONS(ARP_HWTYPE_ETH);
+ BUF->protocol = HTONS(UIP_ETHTYPE_IP);
+ BUF->hwlen = 6;
+ BUF->protolen = 4;
+ BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
+
+ dev->d_appdata = &dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN];
+
+ dev->d_len = sizeof(struct arp_hdr);
+ return;
+ }
+
+ /* Build an ethernet header. */
+
+ memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, 6);
}
-
- /* Build an ethernet header. */
- memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, 6);
- }
memcpy(IPBUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
IPBUF->ethhdr.type = HTONS(UIP_ETHTYPE_IP);
diff --git a/nuttx/net/uip/uip-send.c b/nuttx/net/uip/uip-send.c
index d5acbb0e4..6cdfd7252 100644
--- a/nuttx/net/uip/uip-send.c
+++ b/nuttx/net/uip/uip-send.c
@@ -41,6 +41,8 @@
* Included Files
****************************************************************************/
+#include <string.h>
+
#include <net/uip/uip.h>
#include <net/uip/uip-arch.h>
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index bd3f2e69c..f345607a1 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -139,8 +139,10 @@ extern void uip_log(char *msg);
****************************************************************************/
/* The IP address of this host. If it is defined to be fixed (by
- setting UIP_FIXEDADDR to 1 in uipopt.h), the address is set
- here. Otherwise, the address */
+ * setting UIP_FIXEDADDR to 1 in uipopt.h), the address is set
+ * here.
+ */
+
#if UIP_FIXEDADDR > 0
const uip_ipaddr_t uip_hostaddr =
{HTONS((UIP_IPADDR0 << 8) | UIP_IPADDR1),
@@ -1625,7 +1627,7 @@ tcp_send_synack:
{
uip_urglen = 0;
#else /* UIP_URGDATA > 0 */
- dev->d_appdata = ((char *)dev->d_appdata) + ((BUF->urgp[0] << 8) | BUF->urgp[1]);
+ dev->d_appdata = ((uint8*)dev->d_appdata) + ((BUF->urgp[0] << 8) | BUF->urgp[1]);
dev->d_len -= (BUF->urgp[0] << 8) | BUF->urgp[1];
#endif /* UIP_URGDATA > 0 */
}