summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-30 14:26:04 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-30 14:26:04 +0000
commit808f3c791f8bc9742a6e42a12a1b235c1c3642c8 (patch)
tree08b58e4127a77e0726ddcaa8d0ee0c98de34e824 /nuttx/net
parent7913d4b1fa7d380e350babb15377174bc38b7726 (diff)
downloadpx4-nuttx-808f3c791f8bc9742a6e42a12a1b235c1c3642c8.tar.gz
px4-nuttx-808f3c791f8bc9742a6e42a12a1b235c1c3642c8.tar.bz2
px4-nuttx-808f3c791f8bc9742a6e42a12a1b235c1c3642c8.zip
Add getsockname()
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3650 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile4
-rw-r--r--nuttx/net/getsockname.c216
2 files changed, 218 insertions, 2 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index fb6b327dc..d252b036f 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -37,8 +37,8 @@
ifeq ($(CONFIG_NET),y)
SOCK_ASRCS =
-SOCK_CSRCS = socket.c bind.c connect.c sendto.c recv.c recvfrom.c \
- net_sockets.c net_close.c net_dup.c net_dup2.c net_clone.c \
+SOCK_CSRCS = bind.c connect.c getsockname.c recv.c recvfrom.c socket.c \
+ sendto.c net_sockets.c net_close.c net_dup.c net_dup2.c net_clone.c \
net_vfcntl.c
ifeq ($(CONFIG_NET_TCP),y)
diff --git a/nuttx/net/getsockname.c b/nuttx/net/getsockname.c
new file mode 100644
index 000000000..a77a31b71
--- /dev/null
+++ b/nuttx/net/getsockname.c
@@ -0,0 +1,216 @@
+/****************************************************************************
+ * net/getsockname.c
+ *
+ * Copyright (C) 2011 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>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+#include <errno.h>
+
+#include <nuttx/net.h>
+#include <net/uip/uip-arch.h>
+
+#include "net_internal.h"
+
+#ifdef CONFIG_NET
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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);
+ FAR struct uip_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
+#endif
+
+ 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
+
+ /* Check if enough space has been provided for the full address */
+
+#ifdef CONFIG_NET_IPv6
+ if (addr->sa_family != AF_INET6 || *addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (addr->sa_family != AF_INET || *addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ /* 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;
+ }
+
+ /* Set the port number */
+
+ switch (psock->s_type)
+ {
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ struct uip_conn *tcp_conn = (struct uip_conn *)psock->s_conn;
+ outaddr->sin_port = tcp_conn->lport; /* Already in network byte order */
+ }
+ break;
+#endif
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ {
+ struct uip_udp_conn *udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ outaddr->sin_port = udp_conn->lport; /* Already in network byte order */
+ }
+ break;
+#endif
+
+ default:
+ err = EOPNOTSUPP;
+ 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.
+ */
+
+ netdev_semtake();
+ dev = g_netdevices;
+ if (!dev)
+ {
+ netdev_semgive();
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Set the address family and the IP address */
+
+#ifdef CONFIG_NET_IPv6
+#error "Not big enough for IPv6 address"
+ 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
+ netdev_semgive();
+
+ /* Return success */
+
+ return OK;
+
+errout:
+ set_errno(err);
+ return ERROR;
+}
+
+#endif /* CONFIG_NET */