summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile2
-rw-r--r--nuttx/net/bind.c58
-rw-r--r--nuttx/net/connect.c126
-rw-r--r--nuttx/net/net_internal.h3
-rw-r--r--nuttx/net/net_sockets.c83
-rw-r--r--nuttx/net/socket.c81
-rw-r--r--nuttx/net/uip/uip.c44
7 files changed, 368 insertions, 29 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 3f5103872..9caa4f8ff 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -39,7 +39,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
ifeq ($(CONFIG_NET),y)
STD_ASRCS =
-STD_CSRCS = socket.c bind.c net_sockets.c
+STD_CSRCS = socket.c bind.c connect.c net_sockets.c
include uip/Make.defs
endif
diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c
index 56d96bb4c..daeb70a87 100644
--- a/nuttx/net/bind.c
+++ b/nuttx/net/bind.c
@@ -38,10 +38,14 @@
****************************************************************************/
#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
#include <sys/types.h>
#include <sys/socket.h>
#include <errno.h>
+#include "net_internal.h"
+
/****************************************************************************
* Global Functions
****************************************************************************/
@@ -50,10 +54,10 @@
* Function: bind
*
* Description:
- * bind() gives the socket sockfd the local address my_addr. my_addr is
- * addrlen bytes long. Traditionally, this is called “assigning a name to a
- * socket.” When a socket is created with socket(2), it exists in a name space
- * (address family) but has no name assigned.
+ * bind() gives the socket sockfd the local address my_addr. my_addr is
+ * addrlen bytes long. Traditionally, this is called “assigning a name to
+ * a socket.” When a socket is created with socket(2), it exists in a name
+ * space (address family) but has no name assigned.
*
* Parameters:
* sockfd Socket descriptor from socket
@@ -63,13 +67,57 @@
* Returned Value:
* 0 on success; -1 on error with errno set appropriately
*
+ * EACCES
+ * The address is protected, and the user is not the superuser.
+ * EADDRINUSE
+ * The given address is already in use.
+ * EBADF
+ * sockfd is not a valid descriptor.
+ * EINVAL
+ * The socket is already bound to an address.
+ * ENOTSOCK
+ * sockfd is a descriptor for a file, not a socket.
+ *
* Assumptions:
*
****************************************************************************/
int bind(int sockfd, const struct sockaddr *my_addr, socklen_t addrlen)
{
- *get_errno_ptr() = ENOSYS;
+ FAR struct socket *psock = sockfd_socket(sockfd);
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Perform the binding depending on the protocol type */
+ switch (psock->s_type)
+ {
+ case SOCK_STREAM:
+ /* Put TCP/IP binding logic here */
+ break;
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+ /* Put UDP binding logic here */
+ break;
+#endif
+ default:
+ err = EBADF;
+ goto errout;
+ }
+
+ err = ENOSYS;
+ /*return OK;*/
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
new file mode 100644
index 000000000..5cff6210e
--- /dev/null
+++ b/nuttx/net/connect.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ * connect.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>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: connect
+ *
+ * Description:
+ * connect() connects the socket referred to by the file descriptor sockfd
+ * to the address specified by serv_addr. The addrlen argument specifies
+ * the size of serv_addr. The format of the address in serv_addr is
+ * determined by the address space of the socket sockfd.
+ *
+ * If the socket sockfd is of type SOCK_DGRAM then serv_addr is the address
+ * to which datagrams are sent by default, and the only address from which
+ * datagrams are received. If the socket is of type SOCK_STREAM or
+ * SOCK_SEQPACKET, this call attempts to make a connection to the socket
+ * that is bound to the address specified by serv_addr.
+ *
+ * Generally, connection-based protocol sockets may successfully connect()
+ * only once; connectionless protocol sockets may use connect() multiple
+ * times to change their association. Connectionless sockets may dissolve
+ * the association by connecting to an address with the sa_family member of
+ * sockaddr set to AF_UNSPEC.
+ *
+ * Parameters:
+ * sockfd Socket descriptor returned by socket()
+ * serv_addr Server address (form depends on type of socket)
+ * addrlen Lenght of actual serv_addr
+ *
+ * Returned Value:
+ * 0 on success; -1 on error with errno set appropriately
+ *
+ * EACCES, EPERM
+ * The user tried to connect to a broadcast address without having the
+ * socket broadcast flag enabled or the connection request failed
+ * because of a local firewall rule.
+ * EADDRINUSE
+ * Local address is already in use.
+ * EAFNOSUPPORT
+ * The passed address didn't have the correct address family in its
+ * sa_family field.
+ * EAGAIN
+ * No more free local ports or insufficient entries in the routing
+ * cache. For PF_INET.
+ * EALREADY
+ * The socket is non-blocking and a previous connection attempt has
+ * not yet been completed.
+ * EBADF
+ * The file descriptor is not a valid index in the descriptor table.
+ * ECONNREFUSED
+ * No one listening on the remote address.
+ * EFAULT
+ * The socket structure address is outside the user's address space.
+ * EINPROGRESS
+ * The socket is non-blocking and the connection cannot be completed
+ * immediately.
+ * EINTR
+ * The system call was interrupted by a signal that was caught.
+ * EISCONN
+ * The socket is already connected.
+ * ENETUNREACH
+ * Network is unreachable.
+ * ENOTSOCK
+ * The file descriptor is not associated with a socket.
+ * ETIMEDOUT
+ * Timeout while attempting connection. The server may be too busy
+ * to accept new connections.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int connect(int sockfd, const struct sockaddr *serv_addr, socklen_t addrlen)
+{
+ *get_errno_ptr() = ENOSYS;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index 6d388d44f..d45dcef7d 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -72,6 +72,9 @@ extern "C" {
/* net_sockets.c *************************************************************/
EXTERN void weak_function net_initialize(void);
+EXTERN int sockfd_allocate(void);
+EXTERN void sockfd_release(int sockfd);
+EXTERN FAR struct socket *sockfd_socket(int sockfd);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c
index fb4927e72..d2be221a8 100644
--- a/nuttx/net/net_sockets.c
+++ b/nuttx/net/net_sockets.c
@@ -169,3 +169,86 @@ int net_releaselist(FAR struct socketlist *list)
return OK;
}
+int sockfd_allocate(void)
+{
+ FAR struct socketlist *list;
+ int i;
+
+ /* Get the socket list for this task/thread */
+
+ list = sched_getsockets();
+ if (list)
+ {
+ /* Search for a socket structure with no references */
+
+ _net_semtake(list);
+ for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
+ {
+ /* Are there references on this socket? */
+ if (!list->sl_sockets[i].s_crefs)
+ {
+ /* No take the reference and return the index + an offset
+ * as the socket descriptor.
+ */
+ memset(&list->sl_sockets[i], 0, sizeof(struct socket));
+ list->sl_sockets[i].s_crefs = 1;
+ _net_semgive(list);
+ return i + __SOCKFD_OFFSET;
+ }
+ }
+ _net_semgive(list);
+ }
+ return ERROR;
+}
+
+void sockfd_release(int sockfd)
+{
+ FAR struct socket *psock;
+
+ /* Get the socket structure for this sockfd */
+
+ psock = sockfd_socket(sockfd);
+ if (psock)
+ {
+ /* Take the list semaphore so that there will be no accesses
+ * to this socket structure.
+ */
+
+ FAR struct socketlist *list = sched_getsockets();
+ if (list)
+ {
+ /* Decrement the count if there the socket will persist
+ * after this.
+ */
+
+ _net_semtake(list);
+ if (psock && psock->s_crefs > 1)
+ {
+ psock->s_crefs--;
+ }
+ else
+ {
+ /* The socket will not persist... reset it */
+
+ memset(psock, 0, sizeof(struct socket));
+ }
+ _net_semgive(list);
+ }
+ }
+}
+
+FAR struct socket *sockfd_socket(int sockfd)
+{
+ FAR struct socketlist *list;
+ int ndx = sockfd - __SOCKFD_OFFSET;
+
+ if (ndx >=0 && ndx < CONFIG_NSOCKET_DESCRIPTORS)
+ {
+ list = sched_getsockets();
+ if (list)
+ {
+ return &list->sl_sockets[ndx];
+ }
+ }
+ return NULL;
+} \ No newline at end of file
diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c
index 2fecee3f7..8fe3e395a 100644
--- a/nuttx/net/socket.c
+++ b/nuttx/net/socket.c
@@ -38,10 +38,14 @@
****************************************************************************/
#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
#include <sys/types.h>
#include <sys/socket.h>
#include <errno.h>
+#include "net_internal.h"
+
/****************************************************************************
* Global Functions
****************************************************************************/
@@ -60,13 +64,88 @@
* Returned Value:
* 0 on success; -1 on error with errno set appropriately
*
+ * EACCES
+ * Permission to create a socket of the specified type and/or protocol
+ * is denied.
+ * EAFNOSUPPORT
+ * The implementation does not support the specified address family.
+ * EINVAL
+ * Unknown protocol, or protocol family not available.
+ * EMFILE
+ * Process file table overflow.
+ * ENFILE
+ * The system limit on the total number of open files has been reached.
+ * ENOBUFS or ENOMEM
+ * Insufficient memory is available. The socket cannot be created until
+ * sufficient resources are freed.
+ * EPROTONOSUPPORT
+ * The protocol type or the specified protocol is not supported within
+ * this domain.
+ *
* Assumptions:
*
****************************************************************************/
int socket(int domain, int type, int protocol)
{
- *get_errno_ptr() = ENOSYS;
+#ifdef CONFIG_NET_UDP
+ FAR struct socket *psock;
+#endif
+ int sockfd;
+ int err;
+
+ /* Only PF_INET or PF_INET6 domains supported */
+
+#ifdef CONFIG_NET_IPv6
+ if ( domain != PF_INET6)
+#else
+ if ( domain != PF_INET)
+#endif
+ {
+ err = EAFNOSUPPORT;
+ goto errout;
+ }
+
+ /* Only SOCK_STREAM and possible SOCK_DRAM are supported */
+
+#ifdef CONFIG_NET_UDP
+ if (protocol != 0 || (type != SOCK_STREAM && type != SOCK_DGRAM))
+#else
+ if (protocol != 0 || type != SOCK_STREAM)
+#endif
+ {
+ err = EPROTONOSUPPORT;
+ goto errout;
+ }
+
+ /* Everything looks good. Allocate a socket descriptor */
+
+ sockfd = sockfd_allocate();
+ if (sockfd < 0)
+ {
+ err = ENFILE;
+ goto errout;
+ }
+
+ /* Initialize the socket structure */
+
+#ifdef CONFIG_NET_UDP
+ psock = sockfd_socket(sockfd);
+ if (psock)
+ {
+ /* Save the protocol type */
+
+ psock->s_type = type;
+ }
+#endif
+
+ return sockfd;
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
+#endif /* CONFIG_NET */
+
+
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index 81208a8b5..f997072d9 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -179,10 +179,10 @@ struct uip_conn uip_conns[UIP_CONNS];
/* The uip_conns array holds all TCP connections. */
uint16 uip_listenports[UIP_LISTENPORTS];
/* The uip_listenports list all currently listning ports. */
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_conn;
struct uip_udp_conn uip_udp_conns[UIP_UDP_CONNS];
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
/* Temporary variables. */
uint8 uip_acc32[4];
@@ -367,7 +367,7 @@ struct uip_conn *uip_find_conn( uint16 portno )
return NULL;
}
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_find_udp_conn( uint16 portno )
{
struct uip_udp_conn *conn;
@@ -383,7 +383,7 @@ struct uip_udp_conn *uip_find_udp_conn( uint16 portno )
return NULL;
}
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
/****************************************************************************
* Public Functions
@@ -426,7 +426,7 @@ uint16 uip_tcpchksum(void)
/* Calculate the UDP checksum of the packet in uip_buf and uip_appdata. */
-#if UIP_UDP_CHECKSUMS
+ #ifdef CONFIG_NET_UDP_CHECKSUMS
uint16 uip_udpchksum(void)
{
return upper_layer_chksum(UIP_PROTO_UDP);
@@ -447,12 +447,12 @@ void uip_init(void)
}
lastport = 1024;
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
for (c = 0; c < UIP_UDP_CONNS; ++c)
{
uip_udp_conns[c].lport = 0;
}
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
/* IPv4 initialization. */
#if UIP_FIXEDADDR == 0
@@ -469,7 +469,7 @@ struct uip_conn *uip_connect(uip_ipaddr_t *ripaddr, uint16 rport)
* number that is not being used by any other connection.
*/
- do
+ do
{
/* Guess that the next available port number will be the one after
* the last port number assigned.
@@ -537,7 +537,7 @@ struct uip_conn *uip_connect(uip_ipaddr_t *ripaddr, uint16 rport)
return conn;
}
-#if UIP_UDP
+#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
{
struct uip_udp_conn *conn;
@@ -547,7 +547,7 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
* number that is not being used by any other connection.
*/
- do
+ do
{
/* Guess that the next available port number will be the one after
* the last port number assigned.
@@ -600,7 +600,7 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
return conn;
}
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
void uip_unlisten(uint16 port)
{
@@ -768,12 +768,12 @@ void uip_interrupt(uint8 flag)
{
register struct uip_conn *uip_connr = uip_conn;
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
if (flag == UIP_UDP_SEND_CONN)
{
goto udp_send;
}
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
uip_sappdata = uip_appdata = &uip_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
@@ -935,7 +935,7 @@ void uip_interrupt(uint8 flag)
goto drop;
}
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
if (flag == UIP_UDP_TIMER)
{
if (uip_udp_conn->lport != 0)
@@ -1105,12 +1105,12 @@ void uip_interrupt(uint8 flag)
goto tcp_input;
}
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
if (BUF->proto == UIP_PROTO_UDP)
{
goto udp_input;
}
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
#ifndef CONFIG_NET_IPv6
/* ICMPv4 processing code follows. */
@@ -1247,14 +1247,14 @@ void uip_interrupt(uint8 flag)
#endif /* !CONFIG_NET_IPv6 */
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
/* UDP input processing. */
udp_input:
/* UDP processing is really just a hack. We don't do anything to the
UDP/IP headers, but let the UDP application do all the hard
work. If the application sets uip_slen, it has a packet to
send. */
-#if UIP_UDP_CHECKSUMS
+ #ifdef CONFIG_NET_UDP_CHECKSUMS
uip_len = uip_len - UIP_IPUDPH_LEN;
uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
if (UDPBUF->udpchksum != 0 && uip_udpchksum() != 0xffff)
@@ -1336,7 +1336,7 @@ void uip_interrupt(uint8 flag)
uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
-#if UIP_UDP_CHECKSUMS
+ #ifdef CONFIG_NET_UDP_CHECKSUMS
/* Calculate UDP checksum. */
UDPBUF->udpchksum = ~(uip_udpchksum());
if (UDPBUF->udpchksum == 0)
@@ -1346,7 +1346,7 @@ void uip_interrupt(uint8 flag)
#endif /* UIP_UDP_CHECKSUMS */
goto ip_send_nolen;
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
/* TCP input processing. */
tcp_input:
@@ -2119,9 +2119,9 @@ void uip_interrupt(uint8 flag)
BUF->tcpchksum = 0;
BUF->tcpchksum = ~(uip_tcpchksum());
-#if UIP_UDP
+ #ifdef CONFIG_NET_UDP
ip_send_nolen:
-#endif /* UIP_UDP */
+#endif /* CONFIG_NET_UDP */
#ifdef CONFIG_NET_IPv6
BUF->vtc = 0x60;