summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-11-22 07:55:45 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-11-22 07:55:45 -0600
commita849dbaa6fcde0beefbc0263d91ddd0554696181 (patch)
treebacfc6509ab2d0d23c8a9c64d32efc3c8de8c590 /nuttx/net
parent4c4e426fc019c4802443890c78841b4087bbd32a (diff)
downloadpx4-nuttx-a849dbaa6fcde0beefbc0263d91ddd0554696181.tar.gz
px4-nuttx-a849dbaa6fcde0beefbc0263d91ddd0554696181.tar.bz2
px4-nuttx-a849dbaa6fcde0beefbc0263d91ddd0554696181.zip
Back out a misconception about INADDR_ANY introduce with some previous commits
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/ipv6/Make.defs2
-rw-r--r--nuttx/net/ipv6/ipv6.h2
-rw-r--r--nuttx/net/ipv6/ipv6_global.c61
-rw-r--r--nuttx/net/udp/udp_conn.c72
4 files changed, 19 insertions, 118 deletions
diff --git a/nuttx/net/ipv6/Make.defs b/nuttx/net/ipv6/Make.defs
index e419cd752..1636db59c 100644
--- a/nuttx/net/ipv6/Make.defs
+++ b/nuttx/net/ipv6/Make.defs
@@ -37,7 +37,7 @@
ifeq ($(CONFIG_NET_IPv6),y)
-NET_CSRCS += ipv6_global.c ipv6_neighbor.c
+NET_CSRCS += ipv6_neighbor.c
# Include utility build support
diff --git a/nuttx/net/ipv6/ipv6.h b/nuttx/net/ipv6/ipv6.h
index 7df96322d..7027cc390 100644
--- a/nuttx/net/ipv6/ipv6.h
+++ b/nuttx/net/ipv6/ipv6.h
@@ -70,8 +70,6 @@ struct net_neighbor_addr_s
* Public Data
****************************************************************************/
-extern const in6_addr_t g_in6addr_any;
-
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
diff --git a/nuttx/net/ipv6/ipv6_global.c b/nuttx/net/ipv6/ipv6_global.c
deleted file mode 100644
index 127d2d2f6..000000000
--- a/nuttx/net/ipv6/ipv6_global.c
+++ /dev/null
@@ -1,61 +0,0 @@
-/****************************************************************************
- * net/ipv6/ipv6_global.c
- *
- * Copyright (C) 2012, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <netinit/in.h>
-#include "ipv6/ipv6.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-const in6_addr_t g_in6addr_any = IN6ADDR_ANY_INIT;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
diff --git a/nuttx/net/udp/udp_conn.c b/nuttx/net/udp/udp_conn.c
index 42c4cf6c1..e54b0a48f 100644
--- a/nuttx/net/udp/udp_conn.c
+++ b/nuttx/net/udp/udp_conn.c
@@ -140,10 +140,17 @@ static FAR struct udp_conn_s *udp_find_conn(uint16_t portno)
#ifdef CONFIG_NETDEV_MULTINIC
/* If the port local port number assigned to the connections matches
* AND the IP address of the connection matches, then return a
- * reference to the connection structure.
+ * reference to the connection structure. INADDR_ANY is a special
+ * case: There can only be instance of a port number with INADDR_ANY.
*/
- if (conn->lport == portno && net_ipaddr_cmp(conn->lipaddr, ipaddr))
+ if (conn->lport == portno &&
+ (net_ipaddr_cmp(conn->lipaddr, ipaddr) ||
+#ifdef CONFIG_NET_IPv6
+ net_ipaddr_cmp(conn->lipaddr, g_allzeroaddr)))
+#else
+ net_ipaddr_cmp(conn->lipaddr, INADDR_ANY)))
+#endif
{
return conn;
}
@@ -353,7 +360,9 @@ FAR struct udp_conn_s *udp_active(FAR struct udp_iphdr_s *buf)
* - If multiple network interfaces are supported, then the local
* IP address is available and we will insist that the
* destination IP matches the bound address (or the destination
- * IP address is a broadcase address).
+ * IP address is a broadcast address). If a socket is bound to
+ * INADDRY_ANY (lipaddr), then it should receive all packets
+ * directed to the port.
* - Finally, if the connection is bound to a remote IP address,
* the source IP address of the packet is checked. Broadcast
* addresses are also accepted.
@@ -365,7 +374,8 @@ FAR struct udp_conn_s *udp_active(FAR struct udp_iphdr_s *buf)
if (conn->lport != 0 && buf->destport == conn->lport &&
(conn->rport == 0 || buf->srcport == conn->rport) &&
#ifdef CONFIG_NETDEV_MULTINIC
- (net_ipaddr_hdrcmp(buf->destipaddr, &g_alloneaddr) ||
+ (net_ipaddr_hdrcmp(buf->destipaddr, &g_allzeroaddr) ||
+ net_ipaddr_hdrcmp(buf->destipaddr, &g_alloneaddr) ||
net_ipaddr_hdrcmp(buf->destipaddr, &conn->lipaddr)) &&
#endif
(net_ipaddr_cmp(conn->ripaddr, g_allzeroaddr) ||
@@ -431,7 +441,6 @@ int udp_bind(FAR struct udp_conn_s *conn, FAR const struct sockaddr_in *addr)
int ret;
#ifdef CONFIG_NETDEV_MULTINIC
- FAR struct net_driver_s *dev;
net_ipaddr_t ipaddr;
#ifdef CONFIG_NET_IPv6
@@ -439,33 +448,17 @@ int udp_bind(FAR struct udp_conn_s *conn, FAR const struct sockaddr_in *addr)
ipaddr = addr->sin6_addr.in6_u.u6_addr16;
- /* Is the address IN6ADDR_ANY? */
-
- if (net_ipaddr_cmp(ipaddr, g_in6addr_any))
#else
/* Get the IPv4 address that we are binding to */
ipaddr = addr->sin_addr.s_addr;
- /* Is the address INADDR_ANY? */
-
- if (net_ipaddr_cmp(ipaddr, INADDR_ANY))
#endif
- {
- /* Get the default device */
- dev = netdev_default();
- if (dev == NULL)
- {
- return -EADDRNOTAVAIL;
- }
-
- /* Use the IP address assigned to the default device */
-
- ipaddr = dev->d_ipaddr;
- }
-
- /* Bind the local IP address to the connection */
+ /* Bind the local IP address to the connection. NOTE this address may be
+ * INADDR_ANY meaning, essentially, that we are binding to all interfaces
+ * for receiving (Sending will use the default port).
+ */
net_ipaddr_copy(conn->lipaddr, ipaddr);
#endif
@@ -544,35 +537,6 @@ int udp_connect(FAR struct udp_conn_s *conn,
FAR const struct sockaddr_in *addr)
#endif
{
-#ifdef CONFIG_NETDEV_MULTINIC
- FAR struct net_driver_s *dev;
-
- /* Has this connection already been bound to a local IP address (lipaddr)? */
-
-#ifdef CONFIG_NET_IPv6
- /* Is the address IN6ADDR_ANY? */
-
- if (net_ipaddr_cmp(conn->lipaddr, g_in6addr_any))
-#else
- /* Is the address INADDR_ANY? */
-
- if (net_ipaddr_cmp(conn->lipaddr, INADDR_ANY))
-#endif
- {
- /* Get the default device */
-
- dev = netdev_default();
- if (dev == NULL)
- {
- return -EADDRNOTAVAIL;
- }
-
- /* Use the IP address assigned to the default device */
-
- net_ipaddr_copy(conn->lipaddr, dev->d_ipaddr);
- }
-#endif /* CONFIG_NETDEV_MULTINIC */
-
/* Has this address already been bound to a local port (lport)? */
if (!conn->lport)