summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-16 22:12:04 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-16 22:12:04 +0000
commit9e15c4be04516ac9957f33ea179a188cc2a081a0 (patch)
tree77fe706483352a68b683ecde64215d54cbc89f4f /nuttx/net
parent4077a70fc256a7dd65febe986f176b8ac62091fc (diff)
downloadpx4-nuttx-9e15c4be04516ac9957f33ea179a188cc2a081a0.tar.gz
px4-nuttx-9e15c4be04516ac9957f33ea179a188cc2a081a0.tar.bz2
px4-nuttx-9e15c4be04516ac9957f33ea179a188cc2a081a0.zip
Associate address with network driver; implement ioctl calls to set addresses
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@345 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile2
-rw-r--r--nuttx/net/net-internal.h8
-rw-r--r--nuttx/net/net-sockets.c2
-rw-r--r--nuttx/net/netdev-count.c103
-rw-r--r--nuttx/net/netdev-find.c7
-rw-r--r--nuttx/net/netdev-ioctl.c148
-rw-r--r--nuttx/net/uip/uip-arp.c102
-rw-r--r--nuttx/net/uip/uip-fw.c209
-rw-r--r--nuttx/net/uip/uip-tcpconn.c2
-rw-r--r--nuttx/net/uip/uip-udpconn.c4
-rw-r--r--nuttx/net/uip/uip.c102
11 files changed, 447 insertions, 242 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index eae467517..680db599d 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -51,7 +51,7 @@ endif
endif
NETDEV_ASRCS =
-NETDEV_CSRCS = netdev-register.c netdev-ioctl.c netdev-find.c
+NETDEV_CSRCS = netdev-register.c netdev-ioctl.c netdev-find.c netdev-count.c
include uip/Make.defs
endif
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index 220f46b54..eca4ec5cc 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -165,7 +165,13 @@ EXTERN void netdev_semtake(void);
/* net-find.c ****************************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
-FAR struct uip_driver_s *netdev_find(const char *ifname);
+EXTERN FAR struct uip_driver_s *netdev_find(const char *ifname);
+#endif
+
+/* net-count.c ***************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN int netdev_count(void);
#endif
#undef EXTERN
diff --git a/nuttx/net/net-sockets.c b/nuttx/net/net-sockets.c
index db5c48ac8..71641a8fa 100644
--- a/nuttx/net/net-sockets.c
+++ b/nuttx/net/net-sockets.c
@@ -272,4 +272,4 @@ FAR struct socket *sockfd_socket(int sockfd)
}
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
-#endif /* CONFIG_NET */ \ No newline at end of file
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/netdev-count.c b/nuttx/net/netdev-count.c
new file mode 100644
index 000000000..c4ca49fd5
--- /dev/null
+++ b/nuttx/net/netdev-count.c
@@ -0,0 +1,103 @@
+/****************************************************************************
+ * net/netdev-count.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 <string.h>
+#include <errno.h>
+
+#include <net/uip/uip-arch.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Priviate 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-find.c b/nuttx/net/netdev-find.c
index c783f8c6f..a975569d2 100644
--- a/nuttx/net/netdev-find.c
+++ b/nuttx/net/netdev-find.c
@@ -41,6 +41,7 @@
#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
#include <sys/types.h>
+#include <string.h>
#include <errno.h>
#include <net/uip/uip-arch.h>
@@ -59,16 +60,10 @@
* 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
****************************************************************************/
diff --git a/nuttx/net/netdev-ioctl.c b/nuttx/net/netdev-ioctl.c
index 3e8c1a933..cdc7c80b8 100644
--- a/nuttx/net/netdev-ioctl.c
+++ b/nuttx/net/netdev-ioctl.c
@@ -42,12 +42,55 @@
#include <sys/types.h>
#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <string.h>
#include <errno.h>
#include <nuttx/net.h>
+#include <net/uip/uip-arch.h>
+#include <net/uip/uip.h>
+
#include "net-internal.h"
/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _get_ipaddr / _set_ipaddr
+ *
+ * Description:
+ * Copy IP addresses into and out of device structure
+ *
+ ****************************************************************************/
+
+static void _get_ipaddr(struct sockaddr *outaddr, uip_ipaddr_t *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ struct sockaddr_in6 *dest = (struct sockaddr_in6 *)outaddr;
+ memcpy(&dest->sin6_addr.in6_u, inaddr, IFHWADDRLEN);
+#else
+ struct sockaddr_in *dest = (struct sockaddr_in *)outaddr;
+ dest->sin_addr.s_addr = *inaddr;
+#endif
+}
+
+static void _set_ipaddr(uip_ipaddr_t *outaddr, struct sockaddr *inaddr)
+{
+#ifdef CONFIG_NET_IPv6
+ struct sockaddr_in6 *src = (struct sockaddr_in6 *)inaddr;
+ memcpy(outaddr, &src->sin6_addr.in6_u, IFHWADDRLEN);
+#else
+ struct sockaddr_in *src = (struct sockaddr_in *)inaddr;
+ *outaddr = src->sin_addr.s_addr;
+#endif
+}
+
+/****************************************************************************
* Global Functions
****************************************************************************/
@@ -58,7 +101,7 @@
* Perform network device specific operations.
*
* Parameters:
- * fd Socket descriptor of device
+ * sockfd Socket descriptor of device
* cmd The ioctl command
* req The argument of the ioctl cmd
*
@@ -67,23 +110,112 @@
* -1 on failure withi errno set properly:
*
* EBADF
- * 'fd' is not a valid descriptor.
+ * 'sockfd' is not a valid descriptor.
* EFAULT
- * 'arg' references an inaccessible memory area.
+ * 'req' references an inaccessible memory area.
* EINVAL
- * 'cmd' or 'arg' is not valid.
+ * 'cmd' or 'req' is not valid.
* ENOTTY
- * 'fd' is not associated with a character special device.
+ * 'sockfd' is not associated with a network device.
* ENOTTY
* The specified request does not apply to the kind of object that the
- * descriptor 'fd' references.
+ * descriptor 'sockfd' references.
*
****************************************************************************/
int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
{
-#warning "Network ioctls not implemented"
- *get_errno_ptr() = ENOSYS;
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ FAR struct uip_driver_s *dev;
+ int err;
+
+ if (!_SIOCVALID(cmd) || !req)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Find the network device associated with the device name
+ * in the request data.
+ */
+
+ dev = netdev_find(req->ifr_name);
+ if (!dev)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Execute the command */
+
+ switch (cmd)
+ {
+ case SIOCGIFADDR: /* Get IP address */
+ _get_ipaddr(&req->ifr_addr, &dev->d_ipaddr);
+ break;
+
+ case SIOCSIFADDR: /* Set IP address */
+ _set_ipaddr(&dev->d_ipaddr, &req->ifr_addr);
+ break;
+
+ case SIOCGIFDSTADDR: /* Get P-to-P address */
+ _get_ipaddr(&req->ifr_dstaddr, &dev->d_draddr);
+ break;
+
+ case SIOCSIFDSTADDR: /* Set P-to-P address */
+ _set_ipaddr(&dev->d_draddr, &req->ifr_dstaddr);
+ break;
+
+ case SIOCGIFNETMASK: /* Get network mask */
+ _get_ipaddr(&req->ifr_addr, &dev->d_netmask);
+ break;
+
+ case SIOCSIFNETMASK: /* Set network mask */
+ _set_ipaddr(&dev->d_netmask, &req->ifr_addr);
+ break;
+
+ case SIOCGIFMTU: /* Get MTU size */
+ req->ifr_mtu = UIP_BUFSIZE;
+ break;
+
+ case SIOCGIFHWADDR: /* Get hardware address */
+ memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.addr, IFHWADDRLEN);
+ break;
+
+ case SIOCSIFHWADDR: /* Set hardware address */
+ memcpy(dev->d_mac.addr, req->ifr_hwaddr.sa_data, IFHWADDRLEN);
+ break;
+
+ case SIOCDIFADDR: /* Delete IP address */
+ memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t));
+ break;
+
+ case SIOCGIFCOUNT: /* Get number of devices */
+ req->ifr_count = netdev_count();
+ break;
+
+ case SIOCGIFBRDADDR: /* Get broadcast IP address */
+ case SIOCSIFBRDADDR: /* Set broadcast IP address */
+ err = ENOSYS;
+ goto errout;
+
+ default:
+ err = EINVAL;
+ goto errout;
+ }
+
+ return OK;
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index 9e029f372..90ff6047e 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -40,7 +40,9 @@
*/
#include <sys/types.h>
+#include <sys/ioctl.h>
#include <string.h>
+#include <netinet/in.h>
#include <net/uip/uip-arch.h>
#include <net/uip/uip-arp.h>
@@ -53,24 +55,27 @@ struct arp_hdr
uint8 protolen;
uint16 opcode;
struct uip_eth_addr shwaddr;
- uint16 sipaddr[2];
+ in_addr_t sipaddr;
struct uip_eth_addr dhwaddr;
- uint16 dipaddr[2];
+ in_addr_t dipaddr;
};
-struct ethip_hdr {
+struct ethip_hdr
+{
struct uip_eth_hdr ethhdr;
+
/* IP header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ in_addr_t srcipaddr;
+ in_addr_t destipaddr;
};
#define ARP_REQUEST 1
@@ -78,8 +83,9 @@ struct ethip_hdr {
#define ARP_HWTYPE_ETH 1
-struct arp_entry {
- uint16 ipaddr[2];
+struct arp_entry
+{
+ in_addr_t ipaddr;
struct uip_eth_addr ethaddr;
uint8 time;
};
@@ -89,7 +95,7 @@ static const struct uip_eth_addr broadcast_ethaddr =
static const uint16 broadcast_ipaddr[2] = {0xffff,0xffff};
static struct arp_entry arp_table[UIP_ARPTAB_SIZE];
-static uint16 ipaddr[2];
+static in_addr_t ipaddr;
static uint8 i, c;
static uint8 arptime;
@@ -104,7 +110,7 @@ void uip_arp_init(void)
{
for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
{
- memset(arp_table[i].ipaddr, 0, 4);
+ memset(&arp_table[i].ipaddr, 0, sizeof(in_addr_t));
}
}
@@ -123,14 +129,14 @@ void uip_arp_timer(void)
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)
+ if (tabptr->ipaddr != 0 && arptime - tabptr->time >= UIP_ARP_MAXAGE)
{
- memset(tabptr->ipaddr, 0, 4);
+ tabptr->ipaddr = 0;
}
}
}
-static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
+static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr)
{
struct arp_entry *tabptr;
@@ -145,16 +151,16 @@ static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
/* Only check those entries that are actually in use. */
- if (tabptr->ipaddr[0] != 0 && tabptr->ipaddr[1] != 0)
+ if (tabptr->ipaddr != 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])
+ if (uip_ipaddr_cmp(pipaddr, tabptr->ipaddr))
{
/* An old entry found, update this and return. */
- memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
+ memcpy(tabptr->ethaddr.addr, ethaddr->addr, IFHWADDRLEN);
tabptr->time = arptime;
return;
@@ -170,7 +176,7 @@ static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
{
tabptr = &arp_table[i];
- if (tabptr->ipaddr[0] == 0 && tabptr->ipaddr[1] == 0)
+ if (tabptr->ipaddr == 0)
{
break;
}
@@ -201,8 +207,8 @@ static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
* information.
*/
- memcpy(tabptr->ipaddr, pipaddr, 4);
- memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
+ tabptr->ipaddr = pipaddr;
+ memcpy(tabptr->ethaddr.addr, ethaddr->addr, IFHWADDRLEN);
tabptr->time = arptime;
}
@@ -225,15 +231,11 @@ 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]))
+ if ((IPBUF->srcipaddr & dev->d_netmask) != (dev->d_ipaddr & dev->d_netmask))
{
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 */
@@ -273,7 +275,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
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))
+ if (uip_ipaddr_cmp(BUF->dipaddr, dev->d_ipaddr))
{
/* First, we register the one who made the request in our ARP
* table, since it is likely that we will do more communication
@@ -286,15 +288,13 @@ void uip_arp_arpin(struct uip_driver_s *dev)
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);
+ memcpy(BUF->dhwaddr.addr, BUF->shwaddr.addr, IFHWADDRLEN);
+ memcpy(BUF->shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN);
+ memcpy(BUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN);
+ memcpy(BUF->ethhdr.dest.addr, BUF->dhwaddr.addr, IFHWADDRLEN);
- 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->dipaddr = BUF->sipaddr;
+ BUF->sipaddr = dev->d_ipaddr;
BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
dev->d_len = sizeof(struct arp_hdr);
@@ -306,7 +306,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
* for us.
*/
- if (uip_ipaddr_cmp(BUF->dipaddr, uip_hostaddr))
+ if (uip_ipaddr_cmp(BUF->dipaddr, dev->d_ipaddr))
{
uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
}
@@ -354,20 +354,20 @@ void uip_arp_out(struct uip_driver_s *dev)
if (uip_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr))
{
- memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, 6);
+ memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, IFHWADDRLEN);
}
else
{
/* Check if the destination address is on the local network. */
- if (!uip_ipaddr_maskcmp(IPBUF->destipaddr, uip_hostaddr, uip_netmask))
+ if (!uip_ipaddr_maskcmp(IPBUF->destipaddr, dev->d_ipaddr, dev->d_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);
+ uip_ipaddr_copy(ipaddr, dev->d_draddr);
}
else
{
@@ -391,17 +391,17 @@ void uip_arp_out(struct uip_driver_s *dev)
* 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);
+ memset(BUF->ethhdr.dest.addr, 0xff, IFHWADDRLEN);
+ memset(BUF->dhwaddr.addr, 0x00, IFHWADDRLEN);
+ memcpy(BUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN);
+ memcpy(BUF->shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN);
uip_ipaddr_copy(BUF->dipaddr, ipaddr);
- uip_ipaddr_copy(BUF->sipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->sipaddr, dev->d_ipaddr);
BUF->opcode = HTONS(ARP_REQUEST); /* ARP request. */
BUF->hwtype = HTONS(ARP_HWTYPE_ETH);
BUF->protocol = HTONS(UIP_ETHTYPE_IP);
- BUF->hwlen = 6;
+ BUF->hwlen = IFHWADDRLEN;
BUF->protolen = 4;
BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
@@ -413,9 +413,9 @@ void uip_arp_out(struct uip_driver_s *dev)
/* Build an ethernet header. */
- memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, 6);
+ memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, IFHWADDRLEN);
}
- memcpy(IPBUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
+ memcpy(IPBUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN);
IPBUF->ethhdr.type = HTONS(UIP_ETHTYPE_IP);
diff --git a/nuttx/net/uip/uip-fw.c b/nuttx/net/uip/uip-fw.c
index 18834c883..b529c6e06 100644
--- a/nuttx/net/uip/uip-fw.c
+++ b/nuttx/net/uip/uip-fw.c
@@ -52,44 +52,50 @@ static struct uip_fw_netif *defaultnetif = NULL;
struct tcpip_hdr
{
- /* IP header. */
- uint8 vhl,
- tos;
- uint16 len,
- ipid,
- ipoffset;
- uint8 ttl,
- proto;
+ /* IP header */
+
+ uint8 vhl;
+ uint8 tos;
+ uint16 len;
+ uint16 ipid;
+ uint16 ipoffset;
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
-
- /* TCP header. */
- uint16 srcport,
- destport;
- uint8 seqno[4],
- ackno[4],
- tcpoffset,
- flags,
- wnd[2];
+ in_addr_t srcipaddr;
+ in_addr_t destipaddr;
+
+ /* TCP header */
+
+ uint16 srcport;
+ uint16 destport;
+ uint8 seqno[4];
+ uint8 ackno[4];
+ uint8 tcpoffset;
+ uint8 flags;
+ uint8 wnd[2];
uint16 tcpchksum;
- uint8 urgp[2];
+ uint8 urgp[2];
uint8 optdata[4];
};
-struct icmpip_hdr {
- /* IP header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+struct icmpip_hdr
+{
+ /* IP header */
+
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
- /* ICMP (echo) header. */
+ in_addr_t srcipaddr;
+ in_addr_t destipaddr;
+
+ /* ICMP (echo) header */
+
uint8 type, icode;
uint16 icmpchksum;
uint16 id, seqno;
@@ -115,8 +121,8 @@ struct icmpip_hdr {
struct fwcache_entry
{
uint16 timer;
- uint16 srcipaddr[2];
- uint16 destipaddr[2];
+ in_addr_t srcipaddr;
+ in_addr_t destipaddr;
uint16 ipid;
uint8 proto;
uint8 unused;
@@ -159,22 +165,6 @@ void uip_fw_init(void)
}
}
-/* Check if an IP address is within the network defined by an IP
- * address and a netmask.
- *
- * ipaddr The IP address to be checked.
- * netipaddr The IP address of the network.
- * netmask The netmask of the network.
- *
- * Return: Non-zero if IP address is in network, zero otherwise.
- */
-
-static unsigned char ipaddr_maskcmp(uint16 *ipaddr, uint16 *netipaddr, uint16 *netmask)
-{
- return (ipaddr[0] & netmask [0]) == (netipaddr[0] & netmask[0]) &&
- (ipaddr[1] & netmask[1]) == (netipaddr[1] & netmask[1]);
-}
-
/* Send out an ICMP TIME-EXCEEDED message.
*
* This function replaces the packet in the d_buf buffer with the
@@ -183,10 +173,10 @@ static unsigned char ipaddr_maskcmp(uint16 *ipaddr, uint16 *netipaddr, uint16 *n
static void time_exceeded(struct uip_driver_s *dev)
{
- uint16 tmp16;
+ in_addr_t tmp_addr;
/* We don't send out ICMP errors for ICMP messages. */
- if(ICMPBUF->proto == UIP_PROTO_ICMP) {
+ if (ICMPBUF->proto == UIP_PROTO_ICMP) {
dev->d_len = 0;
return;
}
@@ -202,17 +192,16 @@ static void time_exceeded(struct uip_driver_s *dev)
ICMPBUF->icmpchksum = ~uip_chksum((uint16 *)&(ICMPBUF->type), 36);
/* Set the IP destination address to be the source address of the
- original packet. */
- tmp16= BUF->destipaddr[0];
- BUF->destipaddr[0] = BUF->srcipaddr[0];
- BUF->srcipaddr[0] = tmp16;
- tmp16 = BUF->destipaddr[1];
- BUF->destipaddr[1] = BUF->srcipaddr[1];
- BUF->srcipaddr[1] = tmp16;
+ * original packet.
+ */
+
+ tmp_addr = BUF->destipaddr;
+ BUF->destipaddr = BUF->srcipaddr;
+ BUF->srcipaddr = tmp_addr;
/* Set our IP address as the source address. */
- BUF->srcipaddr[0] = uip_hostaddr[0];
- BUF->srcipaddr[1] = uip_hostaddr[1];
+
+ BUF->srcipaddr = dev->d_ipaddr;
/* The size of the ICMP time exceeded packet is 36 + the size of the
IP header (20) = 56. */
@@ -245,11 +234,11 @@ static void fwcache_register(struct uip_driver_s *dev)
fw = NULL;
/* Find the oldest entry in the cache. */
- for(i = 0; i < FWCACHE_SIZE; ++i) {
- if(fwcache[i].timer == 0) {
+ for (i = 0; i < FWCACHE_SIZE; ++i) {
+ if (fwcache[i].timer == 0) {
fw = &fwcache[i];
break;
- } else if(fwcache[i].timer <= oldest) {
+ } else if (fwcache[i].timer <= oldest) {
fw = &fwcache[i];
oldest = fwcache[i].timer;
}
@@ -257,10 +246,8 @@ static void fwcache_register(struct uip_driver_s *dev)
fw->timer = FW_TIME;
fw->ipid = BUF->ipid;
- fw->srcipaddr[0] = BUF->srcipaddr[0];
- fw->srcipaddr[1] = BUF->srcipaddr[1];
- fw->destipaddr[0] = BUF->destipaddr[0];
- fw->destipaddr[1] = BUF->destipaddr[1];
+ fw->srcipaddr = BUF->srcipaddr;
+ fw->destipaddr = BUF->destipaddr;
fw->proto = BUF->proto;
#if notdef
fw->payload[0] = BUF->srcport;
@@ -274,20 +261,24 @@ static void fwcache_register(struct uip_driver_s *dev)
/* Find a network interface for the IP packet in d_buf. */
-static struct uip_fw_netif *find_netif(struct uip_driver_s *dev)
+static struct uip_fw_netif *find_netif (struct uip_driver_s *dev)
{
struct uip_fw_netif *netif;
/* Walk through every network interface to check for a match. */
- for(netif = netifs; netif != NULL; netif = netif->next) {
- if(ipaddr_maskcmp(BUF->destipaddr, netif->ipaddr,
- netif->netmask)) {
- /* If there was a match, we break the loop. */
- return netif;
+
+ for (netif = netifs; netif != NULL; netif = netif->next)
+ {
+ if (uip_ipaddr_maskcmp(BUF->destipaddr, netif->ipaddr, netif->netmask))
+ {
+ /* If there was a match, we break the loop. */
+
+ return netif;
+ }
}
- }
/* If no matching netif was found, we use default netif. */
+
return defaultnetif;
}
@@ -310,7 +301,7 @@ uint8 uip_fw_output(struct uip_driver_s *dev)
{
struct uip_fw_netif *netif;
- if(dev->d_len == 0) {
+ if (dev->d_len == 0) {
return UIP_FW_ZEROLEN;
}
@@ -318,23 +309,23 @@ uint8 uip_fw_output(struct uip_driver_s *dev)
#if UIP_BROADCAST
/* Link local broadcasts go out on all interfaces. */
- if(/*BUF->proto == UIP_PROTO_UDP &&*/
+ if (/*BUF->proto == UIP_PROTO_UDP &&*/
BUF->destipaddr[0] == 0xffff &&
BUF->destipaddr[1] == 0xffff) {
- if(defaultnetif != NULL) {
+ if (defaultnetif != NULL) {
defaultnetif->output();
}
- for(netif = netifs; netif != NULL; netif = netif->next) {
+ for (netif = netifs; netif != NULL; netif = netif->next) {
netif->output();
}
return UIP_FW_OK;
}
#endif /* UIP_BROADCAST */
- netif = find_netif(dev);
+ netif = find_netif (dev);
dbg("uip_fw_output: netif %p ->output %p len %d\n", netif, netif->output, dev->d_len);
- if(netif == NULL) {
+ if (netif == NULL) {
return UIP_FW_NOROUTE;
}
/* If we now have found a suitable network interface, we call its
@@ -353,36 +344,35 @@ uint8 uip_fw_forward(struct uip_driver_s *dev)
struct fwcache_entry *fw;
/* First check if the packet is destined for ourselves and return 0
- to indicate that the packet should be processed locally. */
- if(BUF->destipaddr[0] == uip_hostaddr[0] &&
- BUF->destipaddr[1] == uip_hostaddr[1]) {
- return UIP_FW_LOCAL;
- }
+ * to indicate that the packet should be processed locally.
+ */
+
+ if (BUF->destipaddr == dev->d_ipaddr)
+ {
+ return UIP_FW_LOCAL;
+ }
/* If we use ping IP address configuration, and our IP address is
not yet configured, we should intercept all ICMP echo packets. */
#if UIP_PINGADDRCONF
- if((uip_hostaddr[0] | uip_hostaddr[1]) == 0 &&
- BUF->proto == UIP_PROTO_ICMP &&
- ICMPBUF->type == ICMP_ECHO) {
- return UIP_FW_LOCAL;
- }
+ if (dev->d_ipaddr == 0 && BUF->proto == UIP_PROTO_ICMP && ICMPBUF->type == ICMP_ECHO)
+ {
+ return UIP_FW_LOCAL;
+ }
#endif /* UIP_PINGADDRCONF */
/* Check if the packet is in the forwarding cache already, and if so
we drop it. */
- for(fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw) {
- if(fw->timer != 0 &&
+ for (fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw) {
+ if (fw->timer != 0 &&
#if UIP_REASSEMBLY > 0
fw->len == BUF->len &&
fw->offset == BUF->ipoffset &&
#endif
fw->ipid == BUF->ipid &&
- fw->srcipaddr[0] == BUF->srcipaddr[0] &&
- fw->srcipaddr[1] == BUF->srcipaddr[1] &&
- fw->destipaddr[0] == BUF->destipaddr[0] &&
- fw->destipaddr[1] == BUF->destipaddr[1] &&
+ fw->srcipaddr == BUF->srcipaddr &&
+ fw->destipaddr == BUF->destipaddr &&
#if notdef
fw->payload[0] == BUF->srcport &&
fw->payload[1] == BUF->destport &&
@@ -398,31 +388,34 @@ uint8 uip_fw_forward(struct uip_driver_s *dev)
of the packet.
*/
- if(BUF->ttl <= 1) {
- /* No time exceeded for broadcasts and multicasts! */
- if(BUF->destipaddr[0] == 0xffff && BUF->destipaddr[1] == 0xffff) {
- return UIP_FW_LOCAL;
+ if (BUF->ttl <= 1)
+ {
+ /* No time exceeded for broadcasts and multicasts! */
+
+ if (BUF->destipaddr == 0xffffffff)
+ {
+ return UIP_FW_LOCAL;
+ }
+ time_exceeded(dev);
}
- time_exceeded(dev);
- }
/* Decrement the TTL (time-to-live) value in the IP header */
BUF->ttl = BUF->ttl - 1;
/* Update the IP checksum. */
- if(BUF->ipchksum >= HTONS(0xffff - 0x0100)) {
+ if (BUF->ipchksum >= HTONS(0xffff - 0x0100)) {
BUF->ipchksum = BUF->ipchksum + HTONS(0x0100) + 1;
} else {
BUF->ipchksum = BUF->ipchksum + HTONS(0x0100);
}
- if(dev->d_len > 0) {
+ if (dev->d_len > 0) {
dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_TCPIP_HLEN];
uip_fw_output(dev);
}
#if UIP_BROADCAST
- if(BUF->destipaddr[0] == 0xffff && BUF->destipaddr[1] == 0xffff) {
+ if (BUF->destipaddr[0] == 0xffff && BUF->destipaddr[1] == 0xffff) {
return UIP_FW_LOCAL;
}
#endif /* UIP_BROADCAST */
@@ -463,8 +456,8 @@ void uip_fw_default(struct uip_fw_netif *netif)
void uip_fw_periodic(void)
{
struct fwcache_entry *fw;
- for(fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw) {
- if(fw->timer > 0) {
+ for (fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw) {
+ if (fw->timer > 0) {
--fw->timer;
}
}
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 37ee80ae3..f604c26c7 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -580,7 +580,7 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
/* The sockaddr address is 32-bits in network order. */
- uip_ipaddr_copy(&conn->ripaddr, addr->sin_addr.s_addr);
+ uip_ipaddr_copy(conn->ripaddr, addr->sin_addr.s_addr);
/* And, finally, put the connection structure into the active
* list. Because g_active_tcp_connections is accessed from user level and
diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c
index e67bbd04b..329852499 100644
--- a/nuttx/net/uip/uip-udpconn.c
+++ b/nuttx/net/uip/uip-udpconn.c
@@ -345,12 +345,12 @@ int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
if (addr)
{
conn->rport = addr->sin_port;
- uip_ipaddr_copy(&conn->ripaddr, &addr->sin_addr.s_addr);
+ uip_ipaddr_copy(conn->ripaddr, addr->sin_addr.s_addr);
}
else
{
conn->rport = 0;
- uip_ipaddr_copy(&conn->ripaddr, &all_zeroes_addr);
+ uip_ipaddr_copy(conn->ripaddr, all_zeroes_addr);
}
conn->ttl = UIP_TTL;
return OK;
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index f345607a1..677cf64db 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -74,6 +74,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/ioctl.h>
#include <debug.h>
#include <net/uip/uipopt.h>
@@ -138,29 +139,6 @@ extern void uip_log(char *msg);
* Public Variables
****************************************************************************/
-/* 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.
- */
-
-#if UIP_FIXEDADDR > 0
-const uip_ipaddr_t uip_hostaddr =
- {HTONS((UIP_IPADDR0 << 8) | UIP_IPADDR1),
- HTONS((UIP_IPADDR2 << 8) | UIP_IPADDR3)};
-
-const uip_ipaddr_t uip_draddr =
- {HTONS((UIP_DRIPADDR0 << 8) | UIP_DRIPADDR1),
- HTONS((UIP_DRIPADDR2 << 8) | UIP_DRIPADDR3)};
-
-const uip_ipaddr_t uip_netmask =
- {HTONS((UIP_NETMASK0 << 8) | UIP_NETMASK1),
- HTONS((UIP_NETMASK2 << 8) | UIP_NETMASK3)};
-#else
-uip_ipaddr_t uip_hostaddr;
-uip_ipaddr_t uip_draddr;
-uip_ipaddr_t uip_netmask;
-#endif /* UIP_FIXEDADDR */
-
#if UIP_URGDATA > 0
void *uip_urgdata; /* The uip_urgdata pointer points to urgent data
* (out-of-band data), if present. */
@@ -168,13 +146,20 @@ uint16 uip_urglen;
uint16 uip_surglen;
#endif /* UIP_URGDATA > 0 */
-uint8 uip_flags; /* The uip_flags variable is used for communication
- * between the TCP/IP stack and the application
- * program. */
-struct uip_conn *uip_conn; /* uip_conn always points to the current connection. */
+/* The uip_flags variable is used for communication between the TCP/IP
+ * stack and the application program.
+ */
+
+uint8 uip_flags;
+
+/* uip_conn always points to the current connection. */
+
+struct uip_conn *uip_conn;
+
+/* The uip_listenports list all currently listening ports. */
uint16 uip_listenports[UIP_LISTENPORTS];
- /* The uip_listenports list all currently listening ports. */
+
#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_conn;
#endif /* CONFIG_NET_UDP */
@@ -194,27 +179,20 @@ const uip_ipaddr_t all_ones_addr =
#ifdef CONFIG_NET_IPv6
{0xffff,0xffff,0xffff,0xffff,0xffff,0xffff,0xffff,0xffff};
#else /* CONFIG_NET_IPv6 */
- {0xffff,0xffff};
+ {0xffffffff};
#endif /* CONFIG_NET_IPv6 */
const uip_ipaddr_t all_zeroes_addr =
#ifdef CONFIG_NET_IPv6
{0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000};
#else /* CONFIG_NET_IPv6 */
- {0x0000,0x0000};
+ {0x00000000};
#endif /* CONFIG_NET_IPv6 */
/****************************************************************************
* Private Variables
****************************************************************************/
-#if UIP_FIXEDETHADDR
-const struct uip_eth_addr uip_ethaddr =
-{{ UIP_ETHADDR0, UIP_ETHADDR1, UIP_ETHADDR2, UIP_ETHADDR3, UIP_ETHADDR4, UIP_ETHADDR5 }};
-#else
-struct uip_eth_addr uip_ethaddr = {{ 0,0,0,0,0,0 }};
-#endif
-
static uint16 ipid; /* Ths ipid variable is an increasing number that is
* used for the IP ID field. */
@@ -283,7 +261,7 @@ static uint16 upper_layer_chksum(struct uip_driver_s *dev, uint8 proto)
sum = upper_layer_len + proto;
/* Sum IP source and destination addresses. */
- sum = chksum(sum, (uint8 *)&BUF->srcipaddr[0], 2 * sizeof(uip_ipaddr_t));
+ sum = chksum(sum, (uint8 *)&BUF->srcipaddr, 2 * sizeof(uip_ipaddr_t));
/* Sum TCP header and data. */
sum = chksum(sum, &dev->d_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len);
@@ -397,9 +375,6 @@ void uip_init(void)
uip_udpinit();
/* IPv4 initialization. */
-#if UIP_FIXEDADDR == 0
- /* uip_hostaddr[0] = uip_hostaddr[1] = 0;*/
-#endif /* UIP_FIXEDADDR */
}
void uip_unlisten(uint16 port)
@@ -465,8 +440,8 @@ static uint8 uip_reass(void)
* fragment into the buffer.
*/
- if (BUF->srcipaddr[0] == FBUF->srcipaddr[0] && BUF->srcipaddr[1] == FBUF->srcipaddr[1] &&
- BUF->destipaddr[0] == FBUF->destipaddr[0] && BUF->destipaddr[1] == FBUF->destipaddr[1] &&
+ if (uip_addr_cmp(BUF->srcipaddr, FBUF->srcipaddr) &&
+ uip_addr_cmp(BUF->destipaddr == FBUF->destipaddr) &&
BUF->ipid[0] == FBUF->ipid[0] && BUF->ipid[1] == FBUF->ipid[1])
{
len = (BUF->len[0] << 8) + BUF->len[1] - (BUF->vhl & 0x0f) * 4;
@@ -879,7 +854,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
}
#endif /* CONFIG_NET_IPv6 */
- if (uip_ipaddr_cmp(uip_hostaddr, all_zeroes_addr))
+ if (uip_ipaddr_cmp(dev->d_ipaddr, all_zeroes_addr))
{
/* If we are configured to use ping IP address configuration and
hasn't been assigned an IP address yet, we accept all ICMP
@@ -914,19 +889,21 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
/* Check if the packet is destined for our IP address. */
#ifndef CONFIG_NET_IPv6
- if (!uip_ipaddr_cmp(BUF->destipaddr, uip_hostaddr))
+ if (!uip_ipaddr_cmp(BUF->destipaddr, dev->d_ipaddr))
{
UIP_STAT(++uip_stat.ip.drop);
- goto drop;
+ goto drop;
}
#else /* CONFIG_NET_IPv6 */
/* For IPv6, packet reception is a little trickier as we need to
- make sure that we listen to certain multicast addresses (all
- hosts multicast address, and the solicited-node multicast
- address) as well. However, we will cheat here and accept all
- multicast packets that are sent to the ff02::/16 addresses. */
- if (!uip_ipaddr_cmp(BUF->destipaddr, uip_hostaddr) &&
- BUF->destipaddr[0] != HTONS(0xff02))
+ * make sure that we listen to certain multicast addresses (all
+ * hosts multicast address, and the solicited-node multicast
+ * address) as well. However, we will cheat here and accept all
+ * multicast packets that are sent to the ff02::/16 addresses.
+ */
+
+ if (!uip_ipaddr_cmp(BUF->destipaddr, dev->d_ipaddr) &&
+ BUF->destipaddr & HTONL(0xffff0000) != HTONL(0xff020000))
{
UIP_STAT(++uip_stat.ip.drop);
goto drop;
@@ -992,10 +969,9 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
the destination IP address of this ping packet and assign it to
ourself. */
#if UIP_PINGADDRCONF
- if ((uip_hostaddr[0] | uip_hostaddr[1]) == 0)
+ if (dev->d_ipaddr == 0)
{
- uip_hostaddr[0] = BUF->destipaddr[0];
- uip_hostaddr[1] = BUF->destipaddr[1];
+ dev->d_ipaddr = BUF->destipaddr;
}
#endif /* UIP_PINGADDRCONF */
@@ -1013,7 +989,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
/* Swap IP addresses. */
uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
UIP_STAT(++uip_stat.icmp.sent);
goto send;
@@ -1040,7 +1016,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
a neighbor advertisement message back. */
if (ICMPBUF->type == ICMP6_NEIGHBOR_SOLICITATION)
{
- if (uip_ipaddr_cmp(ICMPBUF->icmp6data, uip_hostaddr))
+ if (uip_ipaddr_cmp(ICMPBUF->icmp6data, dev->d_ipaddr))
{
if (ICMPBUF->options[0] == ICMP6_OPTION_SOURCE_LINK_ADDRESS)
{
@@ -1056,10 +1032,10 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
ICMPBUF->reserved1 = ICMPBUF->reserved2 = ICMPBUF->reserved3 = 0;
uip_ipaddr_copy(ICMPBUF->destipaddr, ICMPBUF->srcipaddr);
- uip_ipaddr_copy(ICMPBUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(ICMPBUF->srcipaddr, dev->d_ipaddr);
ICMPBUF->options[0] = ICMP6_OPTION_TARGET_LINK_ADDRESS;
ICMPBUF->options[1] = 1; /* Options length, 1 = 8 bytes. */
- memcpy(&(ICMPBUF->options[2]), &uip_ethaddr, sizeof(uip_ethaddr));
+ memcpy(&(ICMPBUF->options[2]), &dev->d_mac, IFHWADDRLEN);
ICMPBUF->icmpchksum = 0;
ICMPBUF->icmpchksum = ~uip_icmp6chksum(dev);
goto send;
@@ -1075,7 +1051,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
ICMPBUF->type = ICMP6_ECHO_REPLY;
uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
ICMPBUF->icmpchksum = 0;
ICMPBUF->icmpchksum = ~uip_icmp6chksum(dev);
@@ -1160,7 +1136,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
BUF->srcport = uip_udp_conn->lport;
BUF->destport = uip_udp_conn->rport;
- uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
uip_ipaddr_copy(BUF->destipaddr, uip_udp_conn->ripaddr);
dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
@@ -1275,7 +1251,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
/* Swap IP addresses. */
uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
- uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
/* And send out the RST packet! */
goto tcp_send_noconn;
@@ -1875,7 +1851,7 @@ tcp_send_synack:
BUF->srcport = uip_connr->lport;
BUF->destport = uip_connr->rport;
- uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
+ uip_ipaddr_copy(BUF->srcipaddr, dev->d_ipaddr);
uip_ipaddr_copy(BUF->destipaddr, uip_connr->ripaddr);
if (uip_connr->tcpstateflags & UIP_STOPPED)