summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-16 08:51:18 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-16 08:51:18 -0600
commit8c1935a004d78bfcdd80638c38fcaa07152f6815 (patch)
treee4d690ddb01d48ed029fe5d816573cd68269bf91 /nuttx
parent7d10c05a0f354f89bba5850a6d7b2a9b6675dd91 (diff)
downloadpx4-nuttx-8c1935a004d78bfcdd80638c38fcaa07152f6815.tar.gz
px4-nuttx-8c1935a004d78bfcdd80638c38fcaa07152f6815.tar.bz2
px4-nuttx-8c1935a004d78bfcdd80638c38fcaa07152f6815.zip
Networking: More detangling of IPv6 logic. Next steps will be more invasive and will get moved to a branch
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/include/nuttx/net/net.h3
-rw-r--r--nuttx/net/arp/arp_send.c4
-rw-r--r--nuttx/net/netdev/netdev.h17
-rw-r--r--nuttx/net/netdev/netdev_findbyaddr.c199
-rw-r--r--nuttx/net/netdev/netdev_rxnotify.c4
-rw-r--r--nuttx/net/netdev/netdev_txnotify.c4
-rw-r--r--nuttx/net/socket/getsockname.c295
-rw-r--r--nuttx/net/socket/socket.c131
8 files changed, 524 insertions, 133 deletions
diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h
index b077b7371..dcec612aa 100644
--- a/nuttx/include/nuttx/net/net.h
+++ b/nuttx/include/nuttx/net/net.h
@@ -96,7 +96,8 @@ struct devif_callback_s; /* Forward reference */
struct socket
{
- int s_crefs; /* Reference count on the socket */
+ int16_t s_crefs; /* Reference count on the socket */
+ uint8_t s_domain; /* Domain: PF_INET, PF_INET6, or PF_PACKET */
uint8_t s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
uint8_t s_flags; /* See _SF_* definitions */
diff --git a/nuttx/net/arp/arp_send.c b/nuttx/net/arp/arp_send.c
index baa8e4ea3..e0d29c9df 100644
--- a/nuttx/net/arp/arp_send.c
+++ b/nuttx/net/arp/arp_send.c
@@ -223,9 +223,9 @@ int arp_send(in_addr_t ipaddr)
/* Get the device that can route this request */
#ifdef CONFIG_NET_MULTILINK
- dev = netdev_findbyaddr(g_allzeroaddr, ipaddr);
+ dev = netdev_findby_ipv4addr(g_allzeroaddr, ipaddr);
#else
- dev = netdev_findbyaddr(ipaddr);
+ dev = netdev_findby_ipv4addr(ipaddr);
#endif
if (!dev)
{
diff --git a/nuttx/net/netdev/netdev.h b/nuttx/net/netdev/netdev.h
index 70333a283..b25cda598 100644
--- a/nuttx/net/netdev/netdev.h
+++ b/nuttx/net/netdev/netdev.h
@@ -94,11 +94,22 @@ FAR struct net_driver_s *netdev_findbyname(FAR const char *ifname);
/* netdev_findbyaddr.c *******************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
+#ifdef CONFIG_NET_IPv4
#ifdef CONFIG_NET_MULTILINK
-FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t lipaddr,
- const net_ipaddr_t ripaddr);
+FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t lipaddr,
+ in_addr_t ripaddr);
#else
-FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr);
+FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr);
+#endif
+#endif
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_MULTILINK
+FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t lipaddr,
+ const net_ipv6addr_t ripaddr);
+#else
+FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t ripaddr);
+#endif
#endif
#endif
diff --git a/nuttx/net/netdev/netdev_findbyaddr.c b/nuttx/net/netdev/netdev_findbyaddr.c
index f232f178e..570b84a0c 100644
--- a/nuttx/net/netdev/netdev_findbyaddr.c
+++ b/nuttx/net/netdev/netdev_findbyaddr.c
@@ -73,7 +73,7 @@
****************************************************************************/
/****************************************************************************
- * Function: netdev_finddevice
+ * Function: netdev_finddevice_ipv4addr
*
* Description:
* Find a previously registered network device by matching a local address
@@ -91,7 +91,8 @@
*
****************************************************************************/
-static FAR struct net_driver_s *netdev_finddevice(const net_ipaddr_t ripaddr)
+#ifdef CONFIG_NET_IPv4
+static FAR struct net_driver_s *netdev_finddevice_ipv4addr(in_addr_t ripaddr)
{
FAR struct net_driver_s *dev;
@@ -121,17 +122,71 @@ static FAR struct net_driver_s *netdev_finddevice(const net_ipaddr_t ripaddr)
netdev_semgive();
return NULL;
}
+#endif /* CONFIG_NET_IPv4 */
+
+/****************************************************************************
+ * Function: netdev_finddevice_ipv6addr
+ *
+ * Description:
+ * Find a previously registered network device by matching a local address
+ * with the subnet served by the device. Only "up" devices are considered
+ * (since a "down" device has no meaningful address).
+ *
+ * Parameters:
+ * ripaddr - Remote address of a connection to use in the lookup
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+static FAR struct net_driver_s *
+netdev_finddevice_ipv6addr(const net_ipv6addr_t ripaddr)
+{
+ FAR struct net_driver_s *dev;
+
+ /* Examine each registered network device */
+
+ netdev_semtake();
+ for (dev = g_netdevices; dev; dev = dev->flink)
+ {
+ /* Is the interface in the "up" state? */
+
+ if ((dev->d_flags & IFF_UP) != 0)
+ {
+ /* Yes.. check for an address match (under the netmask) */
+
+ if (net_ipaddr_maskcmp(dev->d_ipv6ipaddr, ripaddr, dev->d_ipv6netmask))
+ {
+ /* Its a match */
+
+ netdev_semgive();
+ return dev;
+ }
+ }
+ }
+
+ /* No device with the matching address found */
+
+ netdev_semgive();
+ return NULL;
+}
+#endif /* CONFIG_NET_IPv6 */
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
- * Function: netdev_findbyaddr
+ * Function: netdev_findby_ipv4addr
*
* Description:
* Find a previously registered network device by matching an arbitrary
- * IP address.
+ * IPv4 address.
*
* Parameters:
* lipaddr - Local, bound address of a connection. Used only if ripaddr
@@ -146,11 +201,12 @@ static FAR struct net_driver_s *netdev_finddevice(const net_ipaddr_t ripaddr)
*
****************************************************************************/
+#ifdef CONFIG_NET_IPv4
#ifdef CONFIG_NET_MULTILINK
-FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t lipaddr,
- const net_ipaddr_t ripaddr)
+FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t lipaddr,
+ in_addr_t ripaddr)
#else
-FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
+FAR struct net_driver_s *netdev_findby_ipv4addr(in_addr_t ripaddr)
#endif
{
struct net_driver_s *dev;
@@ -161,12 +217,12 @@ FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
/* First, check if this is the broadcast IP address */
- if (net_ipaddr_cmp(ripaddr, g_alloneaddr))
+ if (net_ipv4addr_cmp(ripaddr, g_alloneaddr))
{
#ifdef CONFIG_NET_MULTILINK
/* Yes.. Check the local, bound address. Is it INADDR_ANY? */
- if (net_ipaddr_cmp(lipaddr, g_allzeroaddr))
+ if (net_ipv4addr_cmp(lipaddr, g_allzeroaddr))
{
/* Yes.. In this case, I think we are supposed to send the
* broadcast packet out ALL local networks. I am not sure
@@ -180,7 +236,7 @@ FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
{
/* Return the device associated with the local address */
- return netdev_finddevice(lipaddr);
+ return netdev_finddevice_ipv4addr(lipaddr);
}
#else
/* If there is only a single, registered network interface, then the
@@ -193,7 +249,7 @@ FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
/* Check if the address maps to a local network */
- dev = netdev_finddevice(ripaddr);
+ dev = netdev_finddevice_ipv4addr(ripaddr);
if (dev)
{
return dev;
@@ -206,18 +262,132 @@ FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
* address of a router that can forward packets to the external network.
*/
+ ret = net_router(ripaddr, &router);
+ if (ret >= 0)
+ {
+ /* Success... try to find the network device associated with the local
+ * router address
+ */
+
+ dev = netdev_finddevice_ipv4addr(router);
+ if (dev)
+ {
+ return dev;
+ }
+ }
+#endif /* CONFIG_NET_ROUTE */
+
+ /* The above lookup will fail if the packet is being sent out of our
+ * out subnet to a router and there is no routing information.
+ */
+
+#ifndef CONFIG_NET_MULTILINK
+ /* If there is only a single, registered network interface, then the
+ * decision is pretty easy. Use that device and its default router
+ * address.
+ */
+
+ dev = g_netdevices;
+#endif
+
+ /* If we will did not find the network device, then we might as well fail
+ * because we are not configured properly to determine the route to the
+ * destination.
+ */
+
+ return dev;
+}
+#endif /* CONFIG_NET_IPv4 */
+
+/****************************************************************************
+ * Function: netdev_findby_ipv6addr
+ *
+ * Description:
+ * Find a previously registered network device by matching an arbitrary
+ * IPv6 address.
+ *
+ * Parameters:
+ * lipaddr - Local, bound address of a connection. Used only if ripaddr
+ * is the broadcast address. Used only if CONFIG_NET_MULTILINK.
+ * ripaddr - Remote address of a connection to use in the lookup
+ *
+ * Returned Value:
+ * Pointer to driver on success; null on failure
+ *
+ * Assumptions:
+ * Called from normal user mode
+ *
+ ****************************************************************************/
+
#ifdef CONFIG_NET_IPv6
- ret = net_router(ripaddr, router);
+#ifdef CONFIG_NET_MULTILINK
+FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t lipaddr,
+ const net_ipv6addr_t ripaddr)
#else
- ret = net_router(ripaddr, &router);
+FAR struct net_driver_s *netdev_findby_ipv6addr(const net_ipv6addr_t ripaddr)
#endif
+{
+ struct net_driver_s *dev;
+#ifdef CONFIG_NET_ROUTE
+ net_ipaddr_t router;
+ int ret;
+#endif
+
+ /* First, check if this is the broadcast IP address */
+
+ if (net_ipv6addr_cmp(ripaddr, g_alloneaddr))
+ {
+#ifdef CONFIG_NET_MULTILINK
+ /* Yes.. Check the local, bound address. Is it INADDR_ANY? */
+
+ if (net_ipv6addr_cmp(lipaddr, g_allzeroaddr))
+ {
+ /* Yes.. In this case, I think we are supposed to send the
+ * broadcast packet out ALL local networks. I am not sure
+ * of that and, in any event, there is nothing we can do
+ * about that here.
+ */
+
+ return NULL;
+ }
+ else
+ {
+ /* Return the device associated with the local address */
+
+ return netdev_finddevice_ipv6addr(lipaddr);
+ }
+#else
+ /* If there is only a single, registered network interface, then the
+ * decision is pretty easy.
+ */
+
+ return g_netdevices;
+#endif
+ }
+
+ /* Check if the address maps to a local network */
+
+ dev = netdev_finddevice_ipv6addr(ripaddr);
+ if (dev)
+ {
+ return dev;
+ }
+
+ /* No.. The address lies on an external network */
+
+#ifdef CONFIG_NET_ROUTE
+ /* If we have a routing table, then perhaps we can find the local
+ * address of a router that can forward packets to the external network.
+ */
+
+ ret = net_router(ripaddr, router);
if (ret >= 0)
{
/* Success... try to find the network device associated with the local
* router address
*/
- dev = netdev_finddevice(router);
+ dev = netdev_finddevice_ipv6addr(router);
if (dev)
{
return dev;
@@ -245,5 +415,6 @@ FAR struct net_driver_s *netdev_findbyaddr(const net_ipaddr_t ripaddr)
return dev;
}
+#endif /* CONFIG_NET_IPv6 */
#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/net/netdev/netdev_rxnotify.c b/nuttx/net/netdev/netdev_rxnotify.c
index e471dbb54..a859d8178 100644
--- a/nuttx/net/netdev/netdev_rxnotify.c
+++ b/nuttx/net/netdev/netdev_rxnotify.c
@@ -102,9 +102,9 @@ void netdev_rxnotify(const net_ipaddr_t ripaddr)
/* Find the device driver that serves the subnet of the remote address */
#ifdef CONFIG_NET_MULTILINK
- dev = netdev_findbyaddr(lipaddr, ripaddr);
+ dev = netdev_findby_ipv4addr(lipaddr, ripaddr);
#else
- dev = netdev_findbyaddr(ripaddr);
+ dev = netdev_findby_ipv4addr(ripaddr);
#endif
if (dev && dev->d_rxavail)
diff --git a/nuttx/net/netdev/netdev_txnotify.c b/nuttx/net/netdev/netdev_txnotify.c
index 644a6a2a2..1e9a80c47 100644
--- a/nuttx/net/netdev/netdev_txnotify.c
+++ b/nuttx/net/netdev/netdev_txnotify.c
@@ -102,9 +102,9 @@ void netdev_txnotify(const net_ipaddr_t ripaddr)
/* Find the device driver that serves the subnet of the remote address */
#ifdef CONFIG_NET_MULTILINK
- dev = netdev_findbyaddr(lipaddr, ripaddr);
+ dev = netdev_findby_ipv4addr(lipaddr, ripaddr);
#else
- dev = netdev_findbyaddr(ripaddr);
+ dev = netdev_findby_ipv4addr(ripaddr);
#endif
if (dev && dev->d_txavail)
diff --git a/nuttx/net/socket/getsockname.c b/nuttx/net/socket/getsockname.c
index 34fea0c12..04b96b01b 100644
--- a/nuttx/net/socket/getsockname.c
+++ b/nuttx/net/socket/getsockname.c
@@ -61,26 +61,14 @@
****************************************************************************/
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: getsockname
+ * Function: get_ipv4_sockname
*
* Description:
* The getsockname() function retrieves the locally-bound name of the
- * specified socket, stores this address in the sockaddr structure pointed
- * to by the 'addr' argument, and stores the length of this address in the
- * object pointed to by the 'addrlen' argument.
- *
- * If the actual length of the address is greater than the length of the
- * supplied sockaddr structure, the stored address will be truncated.
- *
- * If the socket has not been bound to a local name, the value stored in
- * the object pointed to by address is unspecified.
+ * specified PF_NET socket.
*
* Parameters:
- * sockfd Socket descriptor of socket [in]
+ * psock Point to the socket structure instance [in]
* addr sockaddr structure to receive data [out]
* addrlen Length of sockaddr structure [in/out]
*
@@ -98,56 +86,152 @@
*
****************************************************************************/
-int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
+#ifdef CONFIG_NET_IPv4
+int ipv4_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr,
+ FAR socklen_t *addrlen)
{
- FAR struct socket *psock = sockfd_socket(sockfd);
FAR struct net_driver_s *dev;
-
#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
-#ifdef CONFIG_NET_IPv6
- FAR struct sockaddr_in6 *outaddr = (FAR struct sockaddr_in6 *)addr;
-#else
FAR struct sockaddr_in *outaddr = (FAR struct sockaddr_in *)addr;
#endif
+#ifdef CONFIG_NETDEV_MULTINIC
+ in_addr_t lipaddr;
+ in_addr_t ripaddr;
#endif
- int err;
+ /* Check if enough space has been provided for the full address */
- /* Verify that the sockfd corresponds to valid, allocated socket */
+ if (*addrlen < sizeof(struct sockaddr_in))
+ {
+ /* This function is supposed to return the partial address if
+ * a smaller buffer has been provided. This support has not
+ * been implemented.
+ */
- if (!psock || psock->s_crefs <= 0)
+ return -ENOSYS;
+ }
+
+ /* Set the port number */
+
+ switch (psock->s_type)
{
- err = EBADF;
- goto errout;
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ FAR struct tcp_conn_s *tcp_conn = (FAR struct tcp_conn_s *)psock->s_conn;
+ outaddr->sin_port = tcp_conn->lport; /* Already in network byte order */
+#ifdef CONFIG_NETDEV_MULTINIC
+ lipaddr = tcp_conn->lipaddr;
+ ripaddr = tcp_conn->ripaddr;
+#endif
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ FAR struct udp_conn_s *udp_conn = (FAR struct udp_conn_s *)psock->s_conn;
+ outaddr->sin_port = udp_conn->lport; /* Already in network byte order */
+#ifdef CONFIG_NETDEV_MULTINIC
+ lipaddr = udp_conn->lipaddr;
+ ripaddr = udp_conn->ripaddr;
+#endif
+ }
+ break;
+#endif
+
+ default:
+ return -EOPNOTSUPP;
}
- /* Some sanity checking... Shouldn't need this on a buckled up embedded
- * system (?)
+ /* The socket/connection does not know its IP address unless
+ * CONFIG_NETDEV_MULTINIC is selected. Otherwise the design supports only
+ * a single network device and only the network device knows the IP address.
*/
-#ifdef CONFIG_DEBUG
- if (!addr || !addrlen)
+ netdev_semtake();
+
+#ifdef CONFIG_NETDEV_MULTINIC
+ /* Find the device matching the IPv4 address in the connection structure */
+
+ dev = netdev_findby_ipv4addr(lipaddr, ripaddr);
+#else
+ /* There is only one, the first network device in the list. */
+
+ dev = g_netdevices;
+#endif
+
+ if (!dev)
{
- err = EINVAL;
- goto errout;
+ netdev_semgive();
+ return -EINVAL;
}
+
+ /* Set the address family and the IP address */
+
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+ outaddr->sin_family = AF_INET;
+ outaddr->sin_addr.s_addr = dev->d_ipaddr;
+ *addrlen = sizeof(struct sockaddr_in);
#endif
+ netdev_semgive();
- /* Check if enough space has been provided for the full address */
+ /* Return success */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Function: ipv6_getsockname
+ *
+ * Description:
+ * The getsockname() function retrieves the locally-bound name of the
+ * specified PF_NET6 socket.
+ *
+ * Parameters:
+ * psock Point to the socket structure instance [in]
+ * addr sockaddr structure to receive data [out]
+ * addrlen Length of sockaddr structure [in/out]
+ *
+ * Returned Value:
+ * On success, 0 is returned, the 'addr' argument points to the address
+ * of the socket, and the 'addrlen' argument points to the length of the
+ * address. Otherwise, -1 is returned and errno is set to indicate the error.
+ * Possible errno values that may be returned include:
+ *
+ * EBADF - The socket argument is not a valid file descriptor.
+ * EOPNOTSUPP - The operation is not supported for this socket's protocol.
+ * EINVAL - The socket has been shut down.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
#ifdef CONFIG_NET_IPv6
- if (*addrlen < sizeof(struct sockaddr_in6))
-#else
- if (*addrlen < sizeof(struct sockaddr_in))
+int ipv6_getsockname(FAR struct socket *psock, FAR struct sockaddr *addr,
+ FAR socklen_t *addrlen)
+{
+ FAR struct net_driver_s *dev;
+#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
+ FAR struct sockaddr_in6 *outaddr = (FAR struct sockaddr_in6 *)addr;
+#endif
+#ifdef CONFIG_NETDEV_MULTINIC
+ net_ipv6addr_t *lipaddr;
+ net_ipv6addr_t *ripaddr;
#endif
+
+ /* Check if enough space has been provided for the full address */
+
+ if (*addrlen < sizeof(struct sockaddr_in6))
{
/* This function is supposed to return the partial address if
* a smaller buffer has been provided. This support has not
* been implemented.
*/
- err = ENOSYS;
- goto errout;
+ return -ENOSYS;
}
/* Set the port number */
@@ -159,6 +243,10 @@ int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
{
FAR struct tcp_conn_s *tcp_conn = (FAR struct tcp_conn_s *)psock->s_conn;
outaddr->sin_port = tcp_conn->lport; /* Already in network byte order */
+#ifdef CONFIG_NETDEV_MULTINIC
+ lipaddr = tcp_conn->lipaddr;
+ ripaddr = tcp_conn->ripaddr;
+#endif
}
break;
#endif
@@ -168,6 +256,10 @@ int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
{
FAR struct udp_conn_s *udp_conn = (FAR struct udp_conn_s *)psock->s_conn;
outaddr->sin_port = udp_conn->lport; /* Already in network byte order */
+#ifdef CONFIG_NETDEV_MULTINIC
+ lipaddr = &udp_conn->lipaddr;
+ ripaddr = &udp_conn->ripaddr;
+#endif
}
break;
#endif
@@ -177,42 +269,139 @@ int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
goto errout;
}
- /* ISSUE: As of this writing, the socket/connection does not know its IP
- * address. This is because the uIP design is only intended to support
- * a single network device and, therefore, only the network device knows
- * the IP address.
- *
- * Right now, we can just pick the first network device. But that may
- * not work in the future.
+ /* The socket/connection does not know its IP address unless
+ * CONFIG_NETDEV_MULTINIC is selected. Otherwise the design supports only
+ * a single network device and only the network device knows the IP address.
*/
netdev_semtake();
+
+#ifdef CONFIG_NETDEV_MULTINIC
+ /* Find the device matching the IPv6 address in the connection structure */
+
+ dev = netdev_findby_ipv6addr(*lipaddr, *ripaddr);
+#else
+ /* There is only one, the first network device in the list. */
+
dev = g_netdevices;
+#endif
+
if (!dev)
{
netdev_semgive();
- err = EINVAL;
- goto errout;
+ return -EINVAL;
}
/* Set the address family and the IP address */
#if defined(CONFIG_NET_TCP) || defined(CONFIG_NET_UDP)
-#ifdef CONFIG_NET_IPv6
outaddr->sin_family = AF_INET6;
memcpy(outaddr->sin6_addr.in6_u.u6_addr8, dev->d_ipaddr, 16);
*addrlen = sizeof(struct sockaddr_in6);
-#else
- outaddr->sin_family = AF_INET;
- outaddr->sin_addr.s_addr = dev->d_ipaddr;
- *addrlen = sizeof(struct sockaddr_in);
-#endif
#endif
netdev_semgive();
/* Return success */
return OK;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: getsockname
+ *
+ * Description:
+ * The getsockname() function retrieves the locally-bound name of the
+ * specified socket, stores this address in the sockaddr structure pointed
+ * to by the 'addr' argument, and stores the length of this address in the
+ * object pointed to by the 'addrlen' argument.
+ *
+ * If the actual length of the address is greater than the length of the
+ * supplied sockaddr structure, the stored address will be truncated.
+ *
+ * If the socket has not been bound to a local name, the value stored in
+ * the object pointed to by address is unspecified.
+ *
+ * Parameters:
+ * sockfd Socket descriptor of socket [in]
+ * addr sockaddr structure to receive data [out]
+ * addrlen Length of sockaddr structure [in/out]
+ *
+ * Returned Value:
+ * On success, 0 is returned, the 'addr' argument points to the address
+ * of the socket, and the 'addrlen' argument points to the length of the
+ * address. Otherwise, -1 is returned and errno is set to indicate the error.
+ * Possible errno values that may be returned include:
+ *
+ * EBADF - The socket argument is not a valid file descriptor.
+ * EOPNOTSUPP - The operation is not supported for this socket's protocol.
+ * EINVAL - The socket has been shut down.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int getsockname(int sockfd, FAR struct sockaddr *addr, FAR socklen_t *addrlen)
+{
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ int ret;
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Some sanity checking... Shouldn't need this on a buckled up embedded
+ * system (?)
+ */
+
+#ifdef CONFIG_DEBUG
+ if (!addr || !addrlen)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+#endif
+
+ /* Handle by address domain */
+
+ switch (psock->s_domain)
+ {
+#ifdef CONFIG_NET_IPv4
+ case PF_INET:
+ ret = ipv4_getsockname(psock, addr, addrlen);
+ break;
+#endif
+
+#ifdef CONFIG_NET_IPv6
+ case PF_INET6:
+ ret = ipv6_getsockname(psock, addr, addrlen);
+ break;
+#endif
+
+ case PF_PACKET:
+ default:
+ err = EAFNOSUPPORT;
+ goto errout;
+ }
+
+ /* Check for failure */
+
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ return OK;
errout:
set_errno(err);
diff --git a/nuttx/net/socket/socket.c b/nuttx/net/socket/socket.c
index 505dbfc0e..6dadf79d3 100644
--- a/nuttx/net/socket/socket.c
+++ b/nuttx/net/socket/socket.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/socket/socket.c
*
- * Copyright (C) 2007-2009, 2012, 2014 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012, 2014-2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -96,66 +96,85 @@
int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
{
+ bool ipdomain = false;
int err;
/* Only PF_INET, PF_INET6 or PF_PACKET domains supported */
- if (
-#if defined(CONFIG_NET_IPv6)
- domain != PF_INET6
-#else
- domain != PF_INET
+ switch (domain)
+ {
+#ifdef CONFIG_NET_IPv4
+ case PF_INET:
+ ipdomain = true;
+ break;
#endif
-#if defined(CONFIG_NET_PKT)
- && domain != PF_PACKET
+
+#ifdef CONFIG_NET_IPv6
+ case PF_INET6:
+ ipdomain = true;
+ break;
#endif
- )
- {
+
+#ifdef CONFIG_NET_PKT
+ case PF_PACKET:
+ break;
+#endif
+
+ default:
err = EAFNOSUPPORT;
goto errout;
}
/* Only SOCK_STREAM, SOCK_DGRAM and possible SOCK_RAW are supported */
- if (
-#if defined(CONFIG_NET_TCP)
- (type == SOCK_STREAM && protocol != 0 && protocol != IPPROTO_TCP) ||
-#endif
-#if defined(CONFIG_NET_UDP)
- (type == SOCK_DGRAM && protocol != 0 && protocol != IPPROTO_UDP) ||
-#endif
- (
-#if defined(CONFIG_NET_TCP)
-#if defined(CONFIG_NET_UDP) || defined(CONFIG_NET_PKT)
- type != SOCK_STREAM &&
-#else
- type != SOCK_STREAM
-#endif
-#endif
-#if defined(CONFIG_NET_UDP)
-#if defined(CONFIG_NET_PKT)
- type != SOCK_DGRAM &&
-#else
- type != SOCK_DGRAM
+ switch (type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ if ((protocol != 0 && protocol != IPPROTO_TCP) || !ipdomain)
+ {
+ err = EPROTONOSUPPORT;
+ goto errout;
+ }
+
+ break;
#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ if ((protocol != 0 && protocol != IPPROTO_UDP) || !ipdomain)
+ {
+ err = EPROTONOSUPPORT;
+ goto errout;
+ }
+
+ break;
#endif
-#if defined(CONFIG_NET_PKT)
- type != SOCK_RAW
+
+#ifdef CONFIG_NET_PKT
+ case SOCK_RAW:
+ if (ipdomain)
+ {
+ err = EPROTONOSUPPORT;
+ goto errout;
+ }
+
+ break;
#endif
- )
- )
- {
- err = EPROTONOSUPPORT;
- goto errout;
+
+ default:
+ err = EPROTONOSUPPORT;
+ goto errout;
}
/* Everything looks good. Initialize the socket structure */
/* Save the protocol type */
- psock->s_type = type;
- psock->s_conn = NULL;
+ psock->s_domain = domain;
+ psock->s_type = type;
+ psock->s_conn = NULL;
#ifdef CONFIG_NET_TCP_WRITE_BUFFERS
- psock->s_sndcb = NULL;
+ psock->s_sndcb = NULL;
#endif
/* Allocate the appropriate connection structure. This reserves the
@@ -166,19 +185,19 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
err = ENOMEM; /* Assume failure to allocate connection instance */
switch (type)
{
-#ifdef CONFIG_NET_PKT
- case SOCK_RAW:
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
{
- /* Allocate the packet socket connection structure and save
- * in the new socket instance.
+ /* Allocate the TCP connection structure and save in the new
+ * socket instance.
*/
- FAR struct pkt_conn_s *conn = pkt_alloc();
+ FAR struct tcp_conn_s *conn = tcp_alloc();
if (!conn)
{
/* Failed to reserve a connection structure */
- goto errout;
+ goto errout; /* With err == ENFILE or ENOMEM */
}
/* Set the reference count on the connection structure. This
@@ -193,14 +212,14 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
break;
#endif
-#ifdef CONFIG_NET_TCP
- case SOCK_STREAM:
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
{
- /* Allocate the TCP connection structure and save in the new
+ /* Allocate the UDP connection structure and save in the new
* socket instance.
*/
- FAR struct tcp_conn_s *conn = tcp_alloc();
+ FAR struct udp_conn_s *conn = udp_alloc();
if (!conn)
{
/* Failed to reserve a connection structure */
@@ -220,19 +239,19 @@ int psock_socket(int domain, int type, int protocol, FAR struct socket *psock)
break;
#endif
-#ifdef CONFIG_NET_UDP
- case SOCK_DGRAM:
+#ifdef CONFIG_NET_PKT
+ case SOCK_RAW:
{
- /* Allocate the UDP connection structure and save in the new
- * socket instance.
+ /* Allocate the packet socket connection structure and save
+ * in the new socket instance.
*/
- FAR struct udp_conn_s *conn = udp_alloc();
+ FAR struct pkt_conn_s *conn = pkt_alloc();
if (!conn)
{
/* Failed to reserve a connection structure */
- goto errout; /* With err == ENFILE or ENOMEM */
+ goto errout;
}
/* Set the reference count on the connection structure. This