summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-15 12:19:44 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-15 12:19:44 -0600
commitc16ad40ac4e49dce5846763d2c31f571c978e355 (patch)
tree9c937d99fd955942764af7212621fa627afe425e /nuttx/net
parent413912e8554701cd97f84cd8d98f3e98999cb520 (diff)
downloadpx4-nuttx-c16ad40ac4e49dce5846763d2c31f571c978e355.tar.gz
px4-nuttx-c16ad40ac4e49dce5846763d2c31f571c978e355.tar.bz2
px4-nuttx-c16ad40ac4e49dce5846763d2c31f571c978e355.zip
Networking: Misck IPv6 detanglement
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/arp/arp_arpin.c6
-rw-r--r--nuttx/net/arp/arp_format.c4
-rw-r--r--nuttx/net/arp/arp_ipin.c2
-rw-r--r--nuttx/net/arp/arp_out.c12
-rw-r--r--nuttx/net/arp/arp_send.c10
-rw-r--r--nuttx/net/arp/arp_table.c4
-rw-r--r--nuttx/net/devif/ipv4_input.c2
-rw-r--r--nuttx/net/icmp/icmp.h2
-rw-r--r--nuttx/net/icmp/icmp_input.c4
-rw-r--r--nuttx/net/icmp/icmp_ping.c24
-rw-r--r--nuttx/net/icmp/icmp_send.c6
-rw-r--r--nuttx/net/icmpv6/icmpv6.h2
-rw-r--r--nuttx/net/icmpv6/icmpv6_input.c2
-rw-r--r--nuttx/net/icmpv6/icmpv6_ping.c22
-rw-r--r--nuttx/net/icmpv6/icmpv6_send.c6
-rw-r--r--nuttx/net/ipv6/ipv6.h6
-rw-r--r--nuttx/net/ipv6/ipv6_neighbor.c16
17 files changed, 65 insertions, 65 deletions
diff --git a/nuttx/net/arp/arp_arpin.c b/nuttx/net/arp/arp_arpin.c
index eed1539a6..99ff7ee67 100644
--- a/nuttx/net/arp/arp_arpin.c
+++ b/nuttx/net/arp/arp_arpin.c
@@ -123,7 +123,7 @@ void arp_arpin(FAR struct net_driver_s *dev)
/* ARP request. If it asked for our address, we send out a reply. */
- if (net_ipaddr_cmp(ipaddr, dev->d_ipaddr))
+ if (net_ipv4addr_cmp(ipaddr, dev->d_ipaddr))
{
struct eth_hdr_s *peth = ETHBUF;
@@ -142,7 +142,7 @@ void arp_arpin(FAR struct net_driver_s *dev)
parp->ah_dipaddr[0] = parp->ah_sipaddr[0];
parp->ah_dipaddr[1] = parp->ah_sipaddr[1];
- net_ipaddr_hdrcopy(parp->ah_sipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(parp->ah_sipaddr, &dev->d_ipaddr);
arp_dump(parp);
peth->type = HTONS(ETHTYPE_ARP);
@@ -157,7 +157,7 @@ void arp_arpin(FAR struct net_driver_s *dev)
* for us.
*/
- if (net_ipaddr_cmp(ipaddr, dev->d_ipaddr))
+ if (net_ipv4addr_cmp(ipaddr, dev->d_ipaddr))
{
/* Yes... Insert the address mapping in the ARP table */
diff --git a/nuttx/net/arp/arp_format.c b/nuttx/net/arp/arp_format.c
index 50a3054e1..21cd99d20 100644
--- a/nuttx/net/arp/arp_format.c
+++ b/nuttx/net/arp/arp_format.c
@@ -105,8 +105,8 @@ void arp_format(FAR struct net_driver_s *dev, in_addr_t ipaddr)
memcpy(eth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
memcpy(arp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
- net_ipaddr_hdrcopy(arp->ah_dipaddr, &ipaddr);
- net_ipaddr_hdrcopy(arp->ah_sipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(arp->ah_dipaddr, &ipaddr);
+ net_ipv4addr_hdrcopy(arp->ah_sipaddr, &dev->d_ipaddr);
arp->ah_opcode = HTONS(ARP_REQUEST);
arp->ah_hwtype = HTONS(ARP_HWTYPE_ETH);
diff --git a/nuttx/net/arp/arp_ipin.c b/nuttx/net/arp/arp_ipin.c
index ddd7102a1..558af73f3 100644
--- a/nuttx/net/arp/arp_ipin.c
+++ b/nuttx/net/arp/arp_ipin.c
@@ -99,7 +99,7 @@ void arp_ipin(FAR struct net_driver_s *dev)
*/
srcipaddr = net_ip4addr_conv32(IPBUF->eh_srcipaddr);
- if (net_ipaddr_maskcmp(srcipaddr, dev->d_ipaddr, dev->d_netmask))
+ if (net_ipv4addr_maskcmp(srcipaddr, dev->d_ipaddr, dev->d_netmask))
{
arp_update(IPBUF->eh_srcipaddr, ETHBUF->src);
}
diff --git a/nuttx/net/arp/arp_out.c b/nuttx/net/arp/arp_out.c
index 6b5b038c7..b5d5af755 100644
--- a/nuttx/net/arp/arp_out.c
+++ b/nuttx/net/arp/arp_out.c
@@ -92,7 +92,7 @@ static const uint16_t g_broadcast_ipaddr[2] = {0xffff, 0xffff};
* The following is the first three octects of the IGMP address:
*/
-#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
+#ifdef CONFIG_NET_IGMP
static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
#endif
@@ -163,12 +163,12 @@ void arp_out(FAR struct net_driver_s *dev)
/* First check if destination is a local broadcast. */
- if (net_ipaddr_hdrcmp(pip->eh_destipaddr, g_broadcast_ipaddr))
+ if (net_ipv4addr_hdrcmp(pip->eh_destipaddr, g_broadcast_ipaddr))
{
memcpy(peth->dest, g_broadcast_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
}
-#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
+#ifdef CONFIG_NET_IGMP
/* Check if the destination address is a multicast address
*
* - IPv4: multicast addresses lie in the class D group -- The address range
@@ -196,7 +196,7 @@ void arp_out(FAR struct net_driver_s *dev)
/* Check if the destination address is on the local network. */
destipaddr = net_ip4addr_conv32(pip->eh_destipaddr);
- if (!net_ipaddr_maskcmp(destipaddr, dev->d_ipaddr, dev->d_netmask))
+ if (!net_ipv4addr_maskcmp(destipaddr, dev->d_ipaddr, dev->d_netmask))
{
/* Destination address is not on the local network */
@@ -213,14 +213,14 @@ void arp_out(FAR struct net_driver_s *dev)
* destination address when determining the MAC address.
*/
- net_ipaddr_copy(ipaddr, dev->d_draddr);
+ net_ipv4addr_copy(ipaddr, dev->d_draddr);
#endif
}
else
{
/* Else, we use the destination IP address. */
- net_ipaddr_copy(ipaddr, destipaddr);
+ net_ipv4addr_copy(ipaddr, destipaddr);
}
/* Check if we already have this destination address in the ARP table */
diff --git a/nuttx/net/arp/arp_send.c b/nuttx/net/arp/arp_send.c
index b3803d0f1..baa8e4ea3 100644
--- a/nuttx/net/arp/arp_send.c
+++ b/nuttx/net/arp/arp_send.c
@@ -202,7 +202,7 @@ int arp_send(in_addr_t ipaddr)
return OK;
}
-#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
+#ifdef CONFIG_NET_IGMP
/* Check if the destination address is a multicast address
*
* - IPv4: multicast addresses lie in the class D group -- The address range
@@ -250,9 +250,9 @@ int arp_send(in_addr_t ipaddr)
/* Check if the destination address is on the local network. */
- if (!net_ipaddr_maskcmp(ipaddr, dev->d_ipaddr, dev->d_netmask))
+ if (!net_ipv4addr_maskcmp(ipaddr, dev->d_ipaddr, dev->d_netmask))
{
- net_ipaddr_t dripaddr;
+ in_addr_t dripaddr;
/* Destination address is not on the local network */
@@ -270,7 +270,7 @@ int arp_send(in_addr_t ipaddr)
* destination address when determining the MAC address.
*/
- net_ipaddr_copy(dripaddr, dev->d_draddr);
+ net_ipv4addr_copy(dripaddr, dev->d_draddr);
#endif
ipaddr = dripaddr;
}
@@ -338,7 +338,7 @@ int arp_send(in_addr_t ipaddr)
/* Notify the device driver that new TX data is available.
* NOTES: This is in essence what netdev_txnotify() does, which
- * is not possible to call since it expects a net_ipaddr_t as
+ * is not possible to call since it expects a in_addr_t as
* its single argument to lookup the network interface.
*/
diff --git a/nuttx/net/arp/arp_table.c b/nuttx/net/arp/arp_table.c
index c1b356f41..a9e201c73 100644
--- a/nuttx/net/arp/arp_table.c
+++ b/nuttx/net/arp/arp_table.c
@@ -173,7 +173,7 @@ void arp_update(FAR uint16_t *pipaddr, FAR uint8_t *ethaddr)
* the IP address in this ARP table entry.
*/
- if (net_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
+ if (net_ipv4addr_cmp(ipaddr, tabptr->at_ipaddr))
{
/* An old entry found, update this and return. */
@@ -252,7 +252,7 @@ FAR struct arp_entry *arp_find(in_addr_t ipaddr)
for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
{
tabptr = &g_arptable[i];
- if (net_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
+ if (net_ipv4addr_cmp(ipaddr, tabptr->at_ipaddr))
{
return tabptr;
}
diff --git a/nuttx/net/devif/ipv4_input.c b/nuttx/net/devif/ipv4_input.c
index c15e22f04..e7895d003 100644
--- a/nuttx/net/devif/ipv4_input.c
+++ b/nuttx/net/devif/ipv4_input.c
@@ -425,7 +425,7 @@ int ipv4_input(FAR struct net_driver_s *dev)
if (!net_ipv4addr_cmp(net_ip4addr_conv32(pbuf->destipaddr), dev->d_ipaddr))
{
#ifdef CONFIG_NET_IGMP
- net_ipv4addr_t destip = net_ip4addr_conv32(pbuf->destipaddr);
+ in_addr_t destip = net_ip4addr_conv32(pbuf->destipaddr);
if (igmp_grpfind(dev, &destip) == NULL)
#endif
{
diff --git a/nuttx/net/icmp/icmp.h b/nuttx/net/icmp/icmp.h
index a5cad2b19..3e55d4c51 100644
--- a/nuttx/net/icmp/icmp.h
+++ b/nuttx/net/icmp/icmp.h
@@ -85,7 +85,7 @@ void icmp_poll(FAR struct net_driver_s *dev);
/* Defined in icmp_send.c ***************************************************/
#ifdef CONFIG_NET_ICMP_PING
-void icmp_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr);
+void icmp_send(FAR struct net_driver_s *dev, FAR in_addr_t *destaddr);
#endif /* CONFIG_NET_ICMP_PING */
#undef EXTERN
diff --git a/nuttx/net/icmp/icmp_input.c b/nuttx/net/icmp/icmp_input.c
index 4539faf13..268742120 100644
--- a/nuttx/net/icmp/icmp_input.c
+++ b/nuttx/net/icmp/icmp_input.c
@@ -139,8 +139,8 @@ void icmp_input(FAR struct net_driver_s *dev)
/* Swap IP addresses. */
- net_ipaddr_hdrcopy(picmp->destipaddr, picmp->srcipaddr);
- net_ipaddr_hdrcopy(picmp->srcipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(picmp->destipaddr, picmp->srcipaddr);
+ net_ipv4addr_hdrcopy(picmp->srcipaddr, &dev->d_ipaddr);
/* Recalculate the ICMP checksum */
diff --git a/nuttx/net/icmp/icmp_ping.c b/nuttx/net/icmp/icmp_ping.c
index efcf64256..ef50fc97c 100644
--- a/nuttx/net/icmp/icmp_ping.c
+++ b/nuttx/net/icmp/icmp_ping.c
@@ -81,15 +81,15 @@ struct icmp_ping_s
{
FAR struct devif_callback_s *png_cb; /* Reference to callback instance */
- sem_t png_sem; /* Use to manage the wait for the response */
- uint32_t png_time; /* Start time for determining timeouts */
- uint32_t png_ticks; /* System clock ticks to wait */
- int png_result; /* 0: success; <0:negated errno on fail */
- net_ipaddr_t png_addr; /* The peer to be ping'ed */
- uint16_t png_id; /* Used to match requests with replies */
- uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
- uint16_t png_datlen; /* The length of data to send in the ECHO request */
- bool png_sent; /* true... the PING request has been sent */
+ sem_t png_sem; /* Use to manage the wait for the response */
+ uint32_t png_time; /* Start time for determining timeouts */
+ uint32_t png_ticks; /* System clock ticks to wait */
+ int png_result; /* 0: success; <0:negated errno on fail */
+ in_addr_t png_addr; /* The peer to be ping'ed */
+ uint16_t png_id; /* Used to match requests with replies */
+ uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
+ uint16_t png_datlen; /* The length of data to send in the ECHO request */
+ bool png_sent; /* true... the PING request has been sent */
};
/****************************************************************************
@@ -251,7 +251,7 @@ static uint16_t ping_interrupt(FAR struct net_driver_s *dev, FAR void *conn,
* device.
*/
- if (!net_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
+ if (!net_ipv4addr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
{
/* Destination address was not on the local network served by this
* device. If a timeout occurs, then the most likely reason is
@@ -324,8 +324,8 @@ end_wait:
*
****************************************************************************/
-int icmp_ping(net_ipaddr_t addr, uint16_t id, uint16_t seqno,
- uint16_t datalen, int dsecs)
+int icmp_ping(in_addr_t addr, uint16_t id, uint16_t seqno, uint16_t datalen,
+ int dsecs)
{
struct icmp_ping_s state;
net_lock_t save;
diff --git a/nuttx/net/icmp/icmp_send.c b/nuttx/net/icmp/icmp_send.c
index 2ff347ee7..e451e67cb 100644
--- a/nuttx/net/icmp/icmp_send.c
+++ b/nuttx/net/icmp/icmp_send.c
@@ -92,7 +92,7 @@
*
****************************************************************************/
-void icmp_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr)
+void icmp_send(FAR struct net_driver_s *dev, FAR in_addr_t *destaddr)
{
FAR struct icmp_iphdr_s *picmp = ICMPBUF;
@@ -124,8 +124,8 @@ void icmp_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr)
picmp->ttl = IP_TTL;
picmp->proto = IP_PROTO_ICMP;
- net_ipaddr_hdrcopy(picmp->srcipaddr, &dev->d_ipaddr);
- net_ipaddr_hdrcopy(picmp->destipaddr, destaddr);
+ net_ipv4addr_hdrcopy(picmp->srcipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(picmp->destipaddr, destaddr);
/* Calculate IP checksum. */
diff --git a/nuttx/net/icmpv6/icmpv6.h b/nuttx/net/icmpv6/icmpv6.h
index 0e872334b..c5740e8f0 100644
--- a/nuttx/net/icmpv6/icmpv6.h
+++ b/nuttx/net/icmpv6/icmpv6.h
@@ -85,7 +85,7 @@ void icmpv6_poll(FAR struct net_driver_s *dev);
/* Defined in icmpv6_send.c *************************************************/
#ifdef CONFIG_NET_ICMPv6_PING
-void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr);
+void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipv6addr_t *destaddr);
#endif /* CONFIG_NET_ICMPv6_PING */
#undef EXTERN
diff --git a/nuttx/net/icmpv6/icmpv6_input.c b/nuttx/net/icmpv6/icmpv6_input.c
index 1bc1e4bc3..6b53a13f1 100644
--- a/nuttx/net/icmpv6/icmpv6_input.c
+++ b/nuttx/net/icmpv6/icmpv6_input.c
@@ -122,7 +122,7 @@ void icmpv6_input(FAR struct net_driver_s *dev)
if (picmp->type == ICMPv6_NEIGHBOR_SOLICITATION)
{
- if (net_ipaddr_cmp(picmp->icmpv6data, dev->d_ipaddr))
+ if (net_ipv6addr_cmp(picmp->icmpv6data, dev->d_ipaddr))
{
if (picmp->options[0] == ICMPv6_OPTION_SOURCE_LINK_ADDRESS)
{
diff --git a/nuttx/net/icmpv6/icmpv6_ping.c b/nuttx/net/icmpv6/icmpv6_ping.c
index 46b71d55f..34b71bc7a 100644
--- a/nuttx/net/icmpv6/icmpv6_ping.c
+++ b/nuttx/net/icmpv6/icmpv6_ping.c
@@ -81,15 +81,15 @@ struct icmpv6_ping_s
{
FAR struct devif_callback_s *png_cb; /* Reference to callback instance */
- sem_t png_sem; /* Use to manage the wait for the response */
- uint32_t png_time; /* Start time for determining timeouts */
- uint32_t png_ticks; /* System clock ticks to wait */
- int png_result; /* 0: success; <0:negated errno on fail */
- net_ipaddr_t png_addr; /* The peer to be ping'ed */
- uint16_t png_id; /* Used to match requests with replies */
- uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
- uint16_t png_datlen; /* The length of data to send in the ECHO request */
- bool png_sent; /* true... the PING request has been sent */
+ sem_t png_sem; /* Use to manage the wait for the response */
+ uint32_t png_time; /* Start time for determining timeouts */
+ uint32_t png_ticks; /* System clock ticks to wait */
+ int png_result; /* 0: success; <0:negated errno on fail */
+ net_ipv6addr_t png_addr; /* The peer to be ping'ed */
+ uint16_t png_id; /* Used to match requests with replies */
+ uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
+ uint16_t png_datlen; /* The length of data to send in the ECHO request */
+ bool png_sent; /* true... the PING request has been sent */
};
/****************************************************************************
@@ -250,7 +250,7 @@ static uint16_t ping_interrupt(FAR struct net_driver_s *dev, FAR void *conn,
* device.
*/
- if (!net_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
+ if (!net_ipv6addr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
{
/* Destination address was not on the local network served by this
* device. If a timeout occurs, then the most likely reason is
@@ -323,7 +323,7 @@ end_wait:
*
****************************************************************************/
-int icmpv6_ping(net_ipaddr_t addr, uint16_t id, uint16_t seqno,
+int icmpv6_ping(net_ipv6addr_t addr, uint16_t id, uint16_t seqno,
uint16_t datalen, int dsecs)
{
struct icmpv6_ping_s state;
diff --git a/nuttx/net/icmpv6/icmpv6_send.c b/nuttx/net/icmpv6/icmpv6_send.c
index 3c071ed54..6df8dc26b 100644
--- a/nuttx/net/icmpv6/icmpv6_send.c
+++ b/nuttx/net/icmpv6/icmpv6_send.c
@@ -92,7 +92,7 @@
*
****************************************************************************/
-void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr)
+void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipv6addr_t *destaddr)
{
FAR struct icmpv6_iphdr_s *picmpv6 = ICMPv6BUF;
@@ -122,8 +122,8 @@ void icmpv6_send(FAR struct net_driver_s *dev, FAR net_ipaddr_t *destaddr)
picmpv6->nexthdr = IP_PROTO_ICMPv6;
picmpv6->hoplimit = IP_TTL;
- net_ipaddr_copy(picmpv6->srcipaddr, &dev->d_ipaddr);
- net_ipaddr_copy(picmpv6->destipaddr, destaddr);
+ net_ipv6addr_copy(picmpv6->srcipaddr, &dev->d_ipaddr);
+ net_ipv6addr_copy(picmpv6->destipaddr, destaddr);
/* Calculate the ICMPv6 checksum. */
diff --git a/nuttx/net/ipv6/ipv6.h b/nuttx/net/ipv6/ipv6.h
index 7027cc390..9ea1f0d5e 100644
--- a/nuttx/net/ipv6/ipv6.h
+++ b/nuttx/net/ipv6/ipv6.h
@@ -75,9 +75,9 @@ struct net_neighbor_addr_s
****************************************************************************/
void net_neighbor_init(void);
-void net_neighbor_add(net_ipaddr_t ipaddr, struct net_neighbor_addr_s *addr);
-void net_neighbor_update(net_ipaddr_t ipaddr);
-struct net_neighbor_addr_s *net_neighbor_lookup(net_ipaddr_t ipaddr);
+void net_neighbor_add(net_ipv6addr_t ipaddr, struct net_neighbor_addr_s *addr);
+void net_neighbor_update(net_ipv6addr_t ipaddr);
+struct net_neighbor_addr_s *net_neighbor_lookup(net_ipv6addr_t ipaddr);
void net_neighbor_periodic(void);
#endif /* CONFIG_NET_IPv6 */
diff --git a/nuttx/net/ipv6/ipv6_neighbor.c b/nuttx/net/ipv6/ipv6_neighbor.c
index 454a5f0f2..3be02e4c6 100644
--- a/nuttx/net/ipv6/ipv6_neighbor.c
+++ b/nuttx/net/ipv6/ipv6_neighbor.c
@@ -65,7 +65,7 @@
struct neighbor_entry
{
- net_ipaddr_t ipaddr;
+ net_ipv6addr_t ipaddr;
struct net_neighbor_addr_s addr;
uint8_t time;
};
@@ -80,13 +80,13 @@ static struct neighbor_entry entries[ENTRIES];
* Private Functions
****************************************************************************/
-static struct neighbor_entry *find_entry(net_ipaddr_t ipaddr)
+static struct neighbor_entry *find_entry(net_ipv6addr_t ipaddr)
{
int i;
for (i = 0; i < ENTRIES; ++i)
{
- if (net_ipaddr_cmp(entries[i].ipaddr, ipaddr))
+ if (net_ipv6addr_cmp(entries[i].ipaddr, ipaddr))
{
return &entries[i];
}
@@ -122,7 +122,7 @@ void net_neighbor_periodic(void)
}
}
-void net_neighbor_add(net_ipaddr_t ipaddr, struct net_neighbor_addr_s *addr)
+void net_neighbor_add(net_ipv6addr_t ipaddr, struct net_neighbor_addr_s *addr)
{
uint8_t oldest_time;
int oldest;
@@ -145,7 +145,7 @@ void net_neighbor_add(net_ipaddr_t ipaddr, struct net_neighbor_addr_s *addr)
oldest = i;
break;
}
- if (net_ipaddr_cmp(entries[i].ipaddr, addr))
+ if (net_ipv6addr_cmp(entries[i].ipaddr, addr))
{
oldest = i;
break;
@@ -162,11 +162,11 @@ void net_neighbor_add(net_ipaddr_t ipaddr, struct net_neighbor_addr_s *addr)
*/
entries[oldest].time = 0;
- net_ipaddr_copy(entries[oldest].ipaddr, ipaddr);
+ net_ipv6addr_copy(entries[oldest].ipaddr, ipaddr);
memcpy(&entries[oldest].addr, addr, sizeof(struct net_neighbor_addr_s));
}
-void net_neighbor_update(net_ipaddr_t ipaddr)
+void net_neighbor_update(net_ipv6addr_t ipaddr)
{
struct neighbor_entry *e;
@@ -177,7 +177,7 @@ void net_neighbor_update(net_ipaddr_t ipaddr)
}
}
-struct net_neighbor_addr_s *net_neighbor_lookup(net_ipaddr_t ipaddr)
+struct net_neighbor_addr_s *net_neighbor_lookup(net_ipv6addr_t ipaddr)
{
struct neighbor_entry *e;