From c96d656001914b495f54e7a25d54079e41af86ce Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 3 Sep 2007 20:34:44 +0000 Subject: Add send, sendto, rec, recvfrom git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@328 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/net/Makefile | 7 +- nuttx/net/bind.c | 21 +++- nuttx/net/connect.c | 3 +- nuttx/net/net-close.c | 112 +++++++++++++++++++ nuttx/net/net_sockets.c | 2 +- nuttx/net/recv.c | 77 +++++++++++++ nuttx/net/recvfrom.c | 239 +++++++++++++++++++++++++++++++++++++++ nuttx/net/send.c | 150 +++++++++++++++++++++++++ nuttx/net/sendto.c | 257 ++++++++++++++++++++++++++++++++++++++++++ nuttx/net/socket.c | 21 +++- nuttx/net/uip/uip-internal.h | 5 +- nuttx/net/uip/uip-tcpconn.c | 222 ++++++++++++++++++++++++++++-------- nuttx/net/uip/uip-udpconn.c | 260 ++++++++++++++++++++++++++----------------- nuttx/net/uip/uip.c | 46 ++++---- 14 files changed, 1224 insertions(+), 198 deletions(-) create mode 100644 nuttx/net/net-close.c create mode 100644 nuttx/net/recv.c create mode 100644 nuttx/net/recvfrom.c create mode 100644 nuttx/net/send.c create mode 100644 nuttx/net/sendto.c (limited to 'nuttx/net') diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile index 25b5c46df..089d45513 100644 --- a/nuttx/net/Makefile +++ b/nuttx/net/Makefile @@ -1,4 +1,4 @@ -############################################################ +############################################################################ # Makefile # # Copyright (C) 2007 Gregory Nutt. All rights reserved. @@ -31,7 +31,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # -############################################################ +############################################################################ -include $(TOPDIR)/Make.defs CFLAGS += -I./uip @@ -40,7 +40,8 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh ifeq ($(CONFIG_NET),y) STD_ASRCS = -STD_CSRCS = socket.c bind.c connect.c net_sockets.c +STD_CSRCS = socket.c bind.c connect.c send.c sendto.c recv.c recvfrom.c \ + net_sockets.c net-close.c include uip/Make.defs endif diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c index 332214d33..97ff479b4 100644 --- a/nuttx/net/bind.c +++ b/nuttx/net/bind.c @@ -61,7 +61,7 @@ * * Parameters: * sockfd Socket descriptor from socket - * my_addr Socket local address + * addr Socket local address * addrlen Length of my_addr * * Returned Value: @@ -91,6 +91,7 @@ int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen) FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr; #endif int err; + int ret; /* Verify that the sockfd corresponds to valid, allocated socket */ @@ -113,24 +114,32 @@ int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen) } /* Perform the binding depending on the protocol type */ + switch (psock->s_type) { case SOCK_STREAM: -#warning Put TCP/IP binding logic here + ret = uip_tcpbind(psock->s_conn, inaddr); break; #ifdef CONFIG_NET_UDP case SOCK_DGRAM: -#warning Put UDP binding logic here + ret = uip_udpbind(psock->s_conn, inaddr); break; #endif default: - err = EBADF; + err = -EBADF; goto errout; } - err = ENOSYS; - /*return OK;*/ + /* Was the bind successful */ + + if (ret < 0) + { + err = -ret; + goto errout; + } + + return OK; errout: *get_errno_ptr() = err; diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c index 2fcb8bc79..bbc112f19 100644 --- a/nuttx/net/connect.c +++ b/nuttx/net/connect.c @@ -149,7 +149,8 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen) goto errout; } - /* Perform the binding depending on the protocol type */ + /* Perform the connection depending on the protocol type */ + switch (psock->s_type) { case SOCK_STREAM: diff --git a/nuttx/net/net-close.c b/nuttx/net/net-close.c new file mode 100644 index 000000000..294a4f7b7 --- /dev/null +++ b/nuttx/net/net-close.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * net/net-close.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#ifdef CONFIG_NET + +#include +#include +#include + +#include "net_internal.h" + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: net_close + * + * Description: + * Performs the close operation on socket descriptors + * + * Parameters: + * sockfd Socket descriptor of socket + * + * Returned Value: + * 0 on success; -1 on error with errno set appropriately. + * + * Assumptions: + * + ****************************************************************************/ + +int net_close(int sockfd) +{ + 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 close depending on the protocol type */ + + switch (psock->s_type) + { + case SOCK_STREAM: + uip_tcpfree(psock->s_conn); + break; + +#ifdef CONFIG_NET_UDP + case SOCK_DGRAM: + uip_udpfree(psock->s_conn); + break; +#endif + default: + err = -EBADF; + goto errout; + } + + /* Save the protocol type */ + + psock->s_type = 0; + psock->s_conn = NULL; + + return OK; + +errout: + *get_errno_ptr() = err; + return ERROR; +} + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c index d2be221a8..bed48ffe3 100644 --- a/nuttx/net/net_sockets.c +++ b/nuttx/net/net_sockets.c @@ -251,4 +251,4 @@ FAR struct socket *sockfd_socket(int sockfd) } } return NULL; -} \ No newline at end of file +} diff --git a/nuttx/net/recv.c b/nuttx/net/recv.c new file mode 100644 index 000000000..70cd4d995 --- /dev/null +++ b/nuttx/net/recv.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * net/recv.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#ifdef CONFIG_NET + +#include +#include +#include + +#include "net_internal.h" + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: recv + * + * Description: + * The recv() call is identical to recvfrom() with a NULL from parameter. + * + * Parameters: + * sockfd Socket descriptor of socket + * buf Buffer to receive data + * len Length of buffer + * flags Receive flags + * + * Returned Value: + * (see recvfrom) + * + * Assumptions: + * + ****************************************************************************/ + +ssize_t recv(int sockfd, void *buf, size_t len, int flags) +{ + return recvfrom(sockfd, buf, len, flags, NULL, 0); +} + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c new file mode 100644 index 000000000..9632b5ca0 --- /dev/null +++ b/nuttx/net/recvfrom.c @@ -0,0 +1,239 @@ +/**************************************************************************** + * net/recvfrom.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#ifdef CONFIG_NET + +#include +#include +#include +#include +#include + +#include "net_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct recvfrom_s +{ + sem_t rf_sem; + uint16 rf_buflen; + char * rf_buffer; +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +void recvfrom_interrupt(void *private) +{ + struct recvfrom_s *pstate = (struct recvfrom_s *)private; + size_t recvlen; + + if (uip_newdata() && private) + { + /* Get the length of the data to return */ + if (uip_len > pstate-> rf_buflen) + { + recvlen = pstate-> rf_buflen; + } + else + { + recvlen = uip_len; + } + + /* Copy the appdate into the user data and send it */ + + memcpy(pstate->rf_buffer, uip_appdata, recvlen); + + /* Don't allow any furhter call backs. */ + + uip_conn->private = NULL; + uip_conn->callback = NULL; + + /* Wake up the waiting thread */ + + pstate->rf_buflen = recvlen; + sem_post(&pstate-> rf_sem); + } +} + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: recvfrom + * + * Description: + * recvfrom() receives messages from a socket, and may be used to receive + * data on a socket whether or not it is connection-oriented. + * + * If from is not NULL, and the underlying protocol provides the source + * address, this source address is filled in. The argument fromlen + * initialized to the size of the buffer associated with from, and modified + * on return to indicate the actual size of the address stored there. + * + * Parameters: + * sockfd Socket descriptor of socket + * buf Buffer to receive data + * len Length of buffer + * flags Receive flags + * from Address of source + * fromlen The length of the address structure + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately: + * + * EAGAIN + * The socket is marked non-blocking and the receive operation would block, + * or a receive timeout had been set and the timeout expired before data + * was received. + * EBADF + * The argument sockfd is an invalid descriptor. + * ECONNREFUSED + * A remote host refused to allow the network connection (typically because + * it is not running the requested service). + * EFAULT + * The receive buffer pointer(s) point outside the process's address space. + * EINTR + * The receive was interrupted by delivery of a signal before any data were + * available. + * EINVAL + * Invalid argument passed. + * ENOMEM + * Could not allocate memory for recvmsg(). + * ENOTCONN + * The socket is associated with a connection-oriented protocol and has + * not been connected. + * ENOTSOCK + * The argument sockfd does not refer to a socket. + * + * Assumptions: + * + ****************************************************************************/ + +ssize_t recvfrom(int sockfd, void *buf, size_t len, int flags, struct sockaddr *from, + socklen_t *fromlen) +{ + FAR struct socket *psock; +#ifdef CONFIG_NET_IPv6 + FAR const struct sockaddr_in6 *infrom = (const struct sockaddr_in6 *)from; +#else + FAR const struct sockaddr_in *infrom = (const struct sockaddr_in *)from; +#endif +#ifdef CONFIG_NET_UDP + struct uip_udp_conn *udp_conn; + struct recvfrom_s state; + irqstate_t save; +#endif + int err; + int ret; + + /* Get the underlying socket structure */ + /* Verify that the sockfd corresponds to valid, allocated socket */ + + psock = sockfd_socket(sockfd); + if (!psock || psock->s_crefs <= 0) + { + err = EBADF; + goto errout; + } + + /* Perform the TCP/IP recv() operation */ + + if (psock->s_type == SOCK_STREAM) + { +#warning "TCP/IP recv not implemented" + err = ENOSYS; + goto errout; + } + + /* Perform the UDP recvfrom() operation */ + +#ifdef CONFIG_NET_UDP + /* Initialize the state structure. This is done with interrupts + * disabled because we don't want anything to happen until we + * are ready. + */ + + save = irqsave(); + memset(&state, 0, sizeof(struct recvfrom_s)); + sem_init(&state. rf_sem, 0, 0); + state. rf_buflen = len; + state. rf_buffer = buf; + + /* Setup the UDP socket */ + + ret = uip_udpconnect(psock->s_conn, NULL); + if (ret < 0) + { + irqrestore(save); + err = -ret; + goto errout; + } + + /* Set up the callback in the connection */ + + udp_conn = (struct uip_udp_conn *)psock->s_conn; + udp_conn->private = (void*)&state; + udp_conn->callback = recvfrom_interrupt; + irqrestore(save); + + sem_wait(&state. rf_sem); + sem_destroy(&state. rf_sem); + return state.rf_buflen; +#warning "Needs to return server address" +#else + err = ENOSYS; +#endif + +errout: + *get_errno_ptr() = err; + return ERROR; +} + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/send.c b/nuttx/net/send.c new file mode 100644 index 000000000..cb93995a7 --- /dev/null +++ b/nuttx/net/send.c @@ -0,0 +1,150 @@ +/**************************************************************************** + * net/send.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#ifdef CONFIG_NET + +#include +#include +#include + +#include "net_internal.h" + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: send + * + * Description: + * The send() call may be used only when the socket is in a connected state + * (so that the intended recipient is known). The only difference between + * send() and write() is the presence of flags. With zero flags parameter, + * send() is equivalent to write(). Also, send(s,buf,len,flags) is + * equivalent to sendto(s,buf,len,flags,NULL,0). + * + * Parameters: + * sockfd Socket descriptor of socket + * buf Data to send + * len Length of data to send + * flags Send flags + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately: + * + * EAGAIN or EWOULDBLOCK + * The socket is marked non-blocking and the requested operation + * would block. + * EBADF + * An invalid descriptor was specified. + * ECONNRESET + * Connection reset by peer. + * EDESTADDRREQ + * The socket is not connection-mode, and no peer address is set. + * EFAULT + * An invalid user space address was specified for a parameter. + * EINTR + * A signal occurred before any data was transmitted. + * EINVAL + * Invalid argument passed. + * EISCONN + * The connection-mode socket was connected already but a recipient + * was specified. (Now either this error is returned, or the recipient + * specification is ignored.) + * EMSGSIZE + * The socket type requires that message be sent atomically, and the + * size of the message to be sent made this impossible. + * ENOBUFS + * The output queue for a network interface was full. This generally + * indicates that the interface has stopped sending, but may be + * caused by transient congestion. + * ENOMEM + * No memory available. + * ENOTCONN + * The socket is not connected, and no target has been given. + * ENOTSOCK + * The argument s is not a socket. + * EOPNOTSUPP + * Some bit in the flags argument is inappropriate for the socket + * type. + * EPIPE + * The local end has been shut down on a connection oriented socket. + * In this case the process will also receive a SIGPIPE unless + * MSG_NOSIGNAL is set. + * + * Assumptions: + * + ****************************************************************************/ + +ssize_t send(int sockfd, const void *buf, size_t len, int flags) +{ + 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; + } + + /* If this is a connected socket, then return ENOTCONN */ + + if (psock->s_type != SOCK_STREAM) + { + err = ENOTCONN; + goto errout; + } + + /* Perform the TCP send operation */ + +#warning "send() not implemented" + err = ENOSYS; + +errout: + *get_errno_ptr() = ENOSYS; + return ERROR; + *get_errno_ptr() = ENOSYS; + return ERROR; +} + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c new file mode 100644 index 000000000..86be9968b --- /dev/null +++ b/nuttx/net/sendto.c @@ -0,0 +1,257 @@ +/**************************************************************************** + * net/sendto.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#ifdef CONFIG_NET + +#include +#include +#include +#include +#include + +#include "net_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct sendto_s +{ + sem_t st_sem; + uint16 st_buflen; + const char *st_buffer; +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +void sendto_interrupt(void *private) +{ + struct sendto_s *pstate = (struct sendto_s *)private; + if (private) + { + /* Copy the user data into appdata and send it */ + + memcpy(uip_appdata, pstate->st_buffer, pstate->st_buflen); + uip_udp_send(pstate->st_buflen); + + /* Don't allow any furhter call backs. */ + + uip_conn->private = NULL; + uip_conn->callback = NULL; + + /* Wake up the waiting thread */ + + sem_post(&pstate->st_sem); + } +} + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: sendto + * + * Description: + * If sendto() is used on a connection-mode (SOCK_STREAM, SOCK_SEQPACKET) + * socket, the parameters to and tolen are ignored (and the error EISCONN + * may be returned when they are not NULL and 0), and the error ENOTCONN is + * returned when the socket was not actually connected. + * + * Parameters: + * sockfd Socket descriptor of socket + * buf Data to send + * len Length of data to send + * flags Send flags + * to Address of recipient + * tolen The length of the address structure + * + * Returned Value: + * On success, returns the number of characters sent. On error, + * -1 is returned, and errno is set appropriately: + * + * EAGAIN or EWOULDBLOCK + * The socket is marked non-blocking and the requested operation + * would block. + * EBADF + * An invalid descriptor was specified. + * ECONNRESET + * Connection reset by peer. + * EDESTADDRREQ + * The socket is not connection-mode, and no peer address is set. + * EFAULT + * An invalid user space address was specified for a parameter. + * EINTR + * A signal occurred before any data was transmitted. + * EINVAL + * Invalid argument passed. + * EISCONN + * The connection-mode socket was connected already but a recipient + * was specified. (Now either this error is returned, or the recipient + * specification is ignored.) + * EMSGSIZE + * The socket type requires that message be sent atomically, and the + * size of the message to be sent made this impossible. + * ENOBUFS + * The output queue for a network interface was full. This generally + * indicates that the interface has stopped sending, but may be + * caused by transient congestion. + * ENOMEM + * No memory available. + * ENOTCONN + * The socket is not connected, and no target has been given. + * ENOTSOCK + * The argument s is not a socket. + * EOPNOTSUPP + * Some bit in the flags argument is inappropriate for the socket + * type. + * EPIPE + * The local end has been shut down on a connection oriented socket. + * In this case the process will also receive a SIGPIPE unless + * MSG_NOSIGNAL is set. + * + * Assumptions: + * + ****************************************************************************/ + +ssize_t sendto(int sockfd, const void *buf, size_t len, int flags, + const struct sockaddr *to, socklen_t tolen) +{ + FAR struct socket *psock; +#ifdef CONFIG_NET_IPv6 + FAR const struct sockaddr_in6 *into = (const struct sockaddr_in6 *)to; +#else + FAR const struct sockaddr_in *into = (const struct sockaddr_in *)to; +#endif +#ifdef CONFIG_NET_UDP + struct uip_udp_conn *udp_conn; + struct sendto_s state; + irqstate_t save; +#endif + int err; + int ret; + + /* If to is NULL or tolen is zero, then this function is same as send */ + + if (!to || !tolen) + { + return send(sockfd, buf, len, flags); + } + + /* Verify that a valid address has been provided */ + +#ifdef CONFIG_NET_IPv6 + if (to->sa_family != AF_INET6 || tolen < sizeof(struct sockaddr_in6)) +#else + if (to->sa_family != AF_INET || tolen < sizeof(struct sockaddr_in)) +#endif + { + err = EBADF; + goto errout; + } + + /* Get the underlying socket structure */ + /* Verify that the sockfd corresponds to valid, allocated socket */ + + psock = sockfd_socket(sockfd); + if (!psock || psock->s_crefs <= 0) + { + err = EBADF; + goto errout; + } + + /* If this is a connected socket, then return EISCONN */ + + if (psock->s_type != SOCK_DGRAM) + { + err = EISCONN; + goto errout; + } + + /* Perform the UDP sendto operation */ + +#ifdef CONFIG_NET_UDP + /* Initialize the state structure. This is done with interrupts + * disabled because we don't want anything to happen until we + * are ready. + */ + + save = irqsave(); + memset(&state, 0, sizeof(struct sendto_s)); + sem_init(&state.st_sem, 0, 0); + state.st_buflen = len; + state.st_buffer = buf; + + /* Setup the UDP socket */ + + ret = uip_udpconnect(psock->s_conn, into); + if (ret < 0) + { + irqrestore(save); + err = -ret; + goto errout; + } + + /* Set up the callback in the connection */ + + udp_conn = (struct uip_udp_conn *)psock->s_conn; + udp_conn->private = (void*)&state; + udp_conn->callback = sendto_interrupt; + irqrestore(save); + + sem_wait(&state.st_sem); + sem_destroy(&state.st_sem); + return len; +#else + err = ENOSYS; +#endif + +errout: + *get_errno_ptr() = err; + return ERROR; +} + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c index ad3ef1e92..43d4645fd 100644 --- a/nuttx/net/socket.c +++ b/nuttx/net/socket.c @@ -135,10 +135,27 @@ int socket(int domain, int type, int protocol) /* Save the protocol type */ psock->s_type = type; + psock->s_conn = NULL; - /* Allocate a TCP connection structure */ + /* Allocate the appropriate connection structure */ + + switch (type) + { + case SOCK_STREAM: + psock->s_conn = uip_tcpalloc(); + break; + +#ifdef CONFIG_NET_UDP + case SOCK_DGRAM: + psock->s_conn = uip_udpalloc(); + break; +#endif + default: + break; + } + + /* Did we succesfully allocate some kind of connection structure? */ - psock->s_conn = uip_tcpalloc(); if (!psock->s_conn) { /* Failed to reserve a connection structure */ diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h index 0f47fbc52..f8613c63a 100644 --- a/nuttx/net/uip/uip-internal.h +++ b/nuttx/net/uip/uip-internal.h @@ -57,10 +57,6 @@ * Public Data ****************************************************************************/ -/* g_tcp_sequence[] is used to generate TCP sequence numbers */ - -extern uint8 g_tcp_sequence[4]; - extern const uip_ipaddr_t all_ones_addr; extern const uip_ipaddr_t all_zeroes_addr; @@ -79,6 +75,7 @@ extern "C" { EXTERN void uip_tcpinit(void); EXTERN struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf); +EXTERN struct uip_conn *uip_tcplistener(struct uip_tcpip_hdr *buf); EXTERN void uip_tcpnextsequence(void); /* Defined in uip_udpconn.c *************************************************/ diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c index 2c6d0cd02..9d1380f6b 100644 --- a/nuttx/net/uip/uip-tcpconn.c +++ b/nuttx/net/uip/uip-tcpconn.c @@ -62,10 +62,6 @@ * Public Data ****************************************************************************/ -/* g_tcp_sequence[] is used to generate TCP sequence numbers */ - -uint8 g_tcp_sequence[4]; - /**************************************************************************** * Private Data ****************************************************************************/ @@ -74,17 +70,34 @@ uint8 g_tcp_sequence[4]; static struct uip_conn g_tcp_connections[UIP_CONNS]; +/* A list of all free TCP connections */ + +static dq_queue_t g_free_tcp_connections; + +/* A list of all connected TCP connections */ + +static dq_queue_t g_active_tcp_connections; + /* Last port used by a TCP connection connection. */ static uint16 g_last_tcp_port; +/* g_tcp_sequence[] is used to generate TCP sequence numbers */ + +static uint8 g_tcp_sequence[4]; + /**************************************************************************** * Private Functions ****************************************************************************/ -/* Given a port number, find the socket bound to the port number. - * Primary use: to determine if a port number is available. - */ +/**************************************************************************** + * Name: uip_find_conn() + * + * Description: + * Given a port number, find the socket bound to the port number. + * Primary use: to determine if a port number is available. + * + ****************************************************************************/ static struct uip_conn *uip_find_conn(uint16 portno) { @@ -118,16 +131,27 @@ static struct uip_conn *uip_find_conn(uint16 portno) * * Description: * Initialize the TCP/IP connection structures. Called only once and only - * from the UIP layer. + * from the UIP layer at startup in normal user mode. * ****************************************************************************/ void uip_tcpinit(void) { int i; + + /* Initialize the queues */ + + dq_init(&g_free_tcp_connections); + dq_init(&g_active_tcp_connections); + + /* Now initialize each connection structure */ + for (i = 0; i < UIP_CONNS; i++) { + /* Mark the connection closed and move it to the free list */ + g_tcp_connections[i].tcpstateflags = UIP_CLOSED; + dq_addlast(&g_tcp_connections[i].node, &g_free_tcp_connections); } g_last_tcp_port = 1024; @@ -146,60 +170,67 @@ void uip_tcpinit(void) struct uip_conn *uip_tcpalloc(void) { -#if 0 /* Revisit */ - struct uip_conn *oldest = NULL; -#endif + struct uip_conn *conn; irqstate_t flags; - unsigned int i; /* Because this routine is called from both interrupt level and * and from user level, we have not option but to disable interrupts - * while accessing g_tcp_connections[]; + * while accessing g_free_tcp_connections[]; */ flags = irqsave(); - /* Check if there are any available connections. */ - - for (i = 0; i < UIP_CONNS; i++) - { - /* First, check if any connections structures are marked as - * CLOSED in the table of pre-allocated connection structures. - */ - - if (g_tcp_connections[i].tcpstateflags == UIP_CLOSED) - { - /* We found an unused structure. Mark as allocated, but not - * initialized. - */ + /* Return the entry from the head of the free list */ - memset(&g_tcp_connections[i], 0, sizeof(struct uip_conn)); - g_tcp_connections[i].tcpstateflags = UIP_ALLOCATED; - - irqrestore(flags); - return &g_tcp_connections[i]; - } + conn = (struct uip_conn *)dq_remfirst(&g_free_tcp_connections); #if 0 /* Revisit */ + /* Is the free list empty? */ + + if (!conn) + { /* As a fallback, check for connection structures in the TIME_WAIT * state. If no CLOSED connections are found, then take the oldest */ - if (g_tcp_connections[i].tcpstateflags == UIP_TIME_WAIT) + struct uip_conn *tmp = g_active_tcp_connections.head; + while (tmp) { - if (!oldest || g_tcp_connections[i].timer > oldest->timer) + /* Is this connectin in the UIP_TIME_WAIT state? */ + + if (tmp->tcpstateflags == UIP_TIME_WAIT) { - oldest = &g_tcp_connections[i]; + /* Is it the oldest one we have seen so far? */ + + if (!conn || tmp->timer > conn->timer) + { + /* Yes.. remember it */ + + conn = tmp; + } } + + /* Look at the next active connection */ + + tmp = tmp->node.flink; } + + /* If we found one, remove it from the active connection list */ + + dq_rem(&conn->node, &g_active_tcp_connections); } - return oldest; -#else - } +#endif irqrestore(flags); - return NULL; -#endif + + /* Mark the connection allocated */ + + if (conn) + { + conn->tcpstateflags = UIP_ALLOCATED; + } + + return conn; } /**************************************************************************** @@ -213,9 +244,31 @@ struct uip_conn *uip_tcpalloc(void) void uip_tcpfree(struct uip_conn *conn) { - /* this action is atomic and should require no special protetion */ + irqstate_t flags; + + /* Because g_free_tcp_connections is accessed from user level and interrupt + * level, code, it is necessary to keep interrupts disabled during this + * operation. + */ + + flags = irqsave(); + + /* UIP_ALLOCATED means that that the connection is not in the active list + * yet. + */ + + if (conn->tcpstateflags != UIP_ALLOCATED) + { + /* Remove the connection from the active list */ + + dq_rem(&conn->node, &g_free_tcp_connections); + } + + /* Mark the connection available and put it into the free list */ conn->tcpstateflags = UIP_CLOSED; + dq_addlast(&conn->node, &g_free_tcp_connections); + irqrestore(flags); } /**************************************************************************** @@ -232,8 +285,8 @@ void uip_tcpfree(struct uip_conn *conn) struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf) { - struct uip_conn *conn; - for (conn = g_tcp_connections; conn <= &g_tcp_connections[UIP_CONNS - 1]; conn++) + struct uip_conn *conn = (struct uip_conn *)g_active_tcp_connections.head; + while (conn) { /* Find an open connection matching the tcp input */ @@ -241,15 +294,64 @@ struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf) buf->destport == conn->lport && buf->srcport == conn->rport && uip_ipaddr_cmp(buf->srcipaddr, conn->ripaddr)) { - /* Matching connection found.. return a reference to it */ + /* Matching connection found.. break out of the loop and return a + * reference to it. + */ - return conn; + break; } + + /* Look at the next active connection */ + + conn = (struct uip_conn *)conn->node.flink; } - /* No match found */ + return conn; +} - return NULL; +/**************************************************************************** + * Name: uip_tcpactive() + * + * Description: + * Called when uip_interupt matches the incoming packet with a connection + * in LISTEN. In that case, this function will create a new connection and + * initialize it to send a SYNACK in return. + * + * Assumptions: + * This function is called from UIP logic at interrupt level + * + ****************************************************************************/ + +struct uip_conn *uip_tcplistener(struct uip_tcpip_hdr *buf) +{ + struct uip_conn *conn = uip_tcpalloc(); + if (conn) + { + /* Fill in the necessary fields for the new connection. */ + + conn->rto = conn->timer = UIP_RTO; + conn->sa = 0; + conn->sv = 4; + conn->nrtx = 0; + conn->lport = buf->destport; + conn->rport = buf->srcport; + uip_ipaddr_copy(conn->ripaddr, buf->srcipaddr); + conn->tcpstateflags = UIP_SYN_RCVD; + + conn->snd_nxt[0] = g_tcp_sequence[0]; + conn->snd_nxt[1] = g_tcp_sequence[1]; + conn->snd_nxt[2] = g_tcp_sequence[2]; + conn->snd_nxt[3] = g_tcp_sequence[3]; + conn->len = 1; + + /* rcv_nxt should be the seqno from the incoming packet + 1. */ + + conn->rcv_nxt[3] = buf->seqno[3]; + conn->rcv_nxt[2] = buf->seqno[2]; + conn->rcv_nxt[1] = buf->seqno[1]; + conn->rcv_nxt[0] = buf->seqno[0]; + } + return conn; } /**************************************************************************** @@ -345,13 +447,24 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr) ****************************************************************************/ #ifdef CONFIG_NET_IPv6 -int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr ) +int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr) #else -int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr ) +int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr) #endif { + irqstate_t flags; uint16 port; + /* The connection is expected to be in the UIP_ALLOCATED state.. i.e., + * allocated via up_tcpalloc(), but not yet put into the active connections + * list. + */ + + if (!conn || conn->tcpstateflags != UIP_ALLOCATED) + { + return -EISCONN; + } + /* If the TCP port has not alread been bound to a local port, then select * one now. */ @@ -407,6 +520,17 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr ) /* The sockaddr address is 32-bits in network order. */ uip_ipaddr_copy(&conn->ripaddr, addr->sin_addr.s_addr); + + /* And, finally, put the connection structure into the active + * list. Because g_active_tcp_connections is accessed from user level and + * interrupt level, code, it is necessary to keep interrupts disabled during + * this operation. + */ + + flags = irqsave(); + dq_addlast(&conn->node, &g_active_tcp_connections); + irqrestore(flags); + return OK; } diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c index 1738e5d5a..24739bee1 100644 --- a/nuttx/net/uip/uip-udpconn.c +++ b/nuttx/net/uip/uip-udpconn.c @@ -1,4 +1,4 @@ -/************************************************************ +/**************************************************************************** * uip-udpconn.c * * Copyright (C) 2007 Gregory Nutt. All rights reserved. @@ -34,21 +34,23 @@ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Compilation Switches - ************************************************************/ + ****************************************************************************/ -/************************************************************ +/**************************************************************************** * Included Files - ************************************************************/ + ****************************************************************************/ #include #if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) #include #include +#include +#include #include #include @@ -58,43 +60,93 @@ #include "uip-internal.h" -/************************************************************ +/**************************************************************************** * Private Data - ************************************************************/ + ****************************************************************************/ /* The array containing all uIP UDP connections. */ -struct uip_udp_conn uip_udp_conns[UIP_UDP_CONNS]; +struct uip_udp_conn g_udp_connections[UIP_UDP_CONNS]; + +/* A list of all free UDP connections */ + +static dq_queue_t g_free_udp_connections; +static sem_t g_free_sem; + +/* A list of all allocated UDP connections */ + +static dq_queue_t g_active_udp_connections; /* Last port used by a UDP connection connection. */ static uint16 g_last_udp_port; -/************************************************************ +/**************************************************************************** * Private Functions - ************************************************************/ + ****************************************************************************/ -#ifdef CONFIG_NET_UDP -struct uip_udp_conn *uip_find_udp_conn( uint16 portno ) +/**************************************************************************** + * Name: _uip_semtake() and _uip_semgive() + * + * Description: + * Take/give semaphore + * + ****************************************************************************/ + +static inline void _uip_semtake(sem_t *sem) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(sem) != 0) + { + /* The only case that an error should occr here is if + * the wait was awakened by a signal. + */ + + ASSERT(*get_errno_ptr() == EINTR); + } +} + +#define _uip_semgive(sem) sem_post(sem) + +/**************************************************************************** + * Name: uip_find_conn() + * + * Description: + * Find the UDP connection that uses this local port number. Called only + * from user, non-interrupt level logic. + * + ****************************************************************************/ + +struct uip_udp_conn *uip_find_conn( uint16 portno ) { struct uip_udp_conn *conn; - int i; + uint16 nlastport = htons(g_last_udp_port); + irqstate_t flags; - for (i = 0; i < UIP_UDP_CONNS; i++) + /* Now search each active connection structure. This list is modifiable + * from interrupt level, we we must diable interrupts to access it safely. + */ + + flags = irqsave(); + conn = (struct uip_udp_conn *)g_active_udp_connections.head; + while (conn) { - if (uip_udp_conns[i].lport == htons(g_last_udp_port)) + if (conn->lport == nlastport) { - return conn; + break; } + + conn = (struct uip_udp_conn *)conn->node.flink; } - return NULL; + irqrestore(flags); + return conn; } -#endif /* CONFIG_NET_UDP */ -/************************************************************ +/**************************************************************************** * Public Functions - ************************************************************/ + ****************************************************************************/ /**************************************************************************** * Name: uip_udpinit() @@ -108,9 +160,19 @@ struct uip_udp_conn *uip_find_udp_conn( uint16 portno ) void uip_udpinit(void) { int i; + + /* Initialize the queues */ + + dq_init(&g_free_udp_connections); + dq_init(&g_active_udp_connections); + sem_init(&g_free_sem, 0, 1); + for (i = 0; i < UIP_UDP_CONNS; i++) { - uip_udp_conns[i].lport = 0; + /* Mark the connection closed and move it to the free list */ + + g_udp_connections[i].lport = 0; + dq_addlast(&g_udp_connections[i].node, &g_free_udp_connections); } g_last_udp_port = 1024; @@ -120,15 +182,28 @@ void uip_udpinit(void) * Name: uip_udpalloc() * * Description: - * Find a free UDP connection structure and allocate it for use. This is - * normally something done by the implementation of the socket() API. + * Alloc a new, uninitialized UDP connection structure. * ****************************************************************************/ struct uip_udp_conn *uip_udpalloc(void) { -#warning "Need to implement allocation logic" - return NULL; + struct uip_udp_conn *conn; + + /* The free list is only accessed from user, non-interrupt level and + * is protected by a semaphore (that behaves like a mutex). + */ + + _uip_semtake(&g_free_sem); + conn = (struct uip_udp_conn *)dq_remfirst(&g_free_udp_connections); + if (conn) + { + /* Make sure that the connectin is marked as uninitialized */ + + conn->lport = 0; + } + _uip_semgive(&g_free_sem); + return conn; } /**************************************************************************** @@ -142,7 +217,27 @@ struct uip_udp_conn *uip_udpalloc(void) void uip_udpfree(struct uip_udp_conn *conn) { -#warning "Need to implement release logic" + irqstate_t flags; + + /* The active list is accessed from the interrupt level and me must be + * certain that no interrupts occur while the active list is modified. + */ + + flags = irqsave(); + if (conn->lport != 0) + { + dq_rem(&conn->node, &g_active_udp_connections); + } + irqrestore(flags); + + /* The free list is only accessed from user, non-interrupt level and + * is protected by a semaphore (that behaves like a mutex). + */ + + _uip_semtake(&g_free_sem); + conn->lport = 0; + dq_addlast(&conn->node, &g_free_udp_connections); + _uip_semgive(&g_free_sem); } /**************************************************************************** @@ -159,8 +254,8 @@ void uip_udpfree(struct uip_udp_conn *conn) struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf) { - struct uip_udp_conn *conn; - for (conn = &uip_udp_conns[0]; conn < &uip_udp_conns[UIP_UDP_CONNS]; conn++) + struct uip_udp_conn *conn = (struct uip_udp_conn *)g_active_udp_connections.head; + while (conn) { /* If the local UDP port is non-zero, the connection is considered * to be used. If so, the local port number is checked against the @@ -179,11 +274,13 @@ struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf) { /* Matching connection found.. return a reference to it */ - return conn; + break; } - } - /* No match found */ + /* Look at the next active connection */ + + conn = (struct uip_udp_conn *)conn->node.flink; + } return NULL; } @@ -207,63 +304,26 @@ struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf) void uip_udppoll(unsigned int conn) { - uip_udp_conn = &uip_udp_conns[conn]; + uip_udp_conn = &g_udp_connections[conn]; uip_interrupt(UIP_UDP_TIMER); } -/**************************************************************************** - * Name: uip_tcpbind() - * - * Description: - * This function implements the UIP specific parts of the standard TCP - * bind() operation. - * - * Assumptions: - * This function is called from normal user level code. - * - ****************************************************************************/ - -#ifdef CONFIG_NET_IPv6 -int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr) -#else -int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr) -#endif -{ -#warning "Need to implement bind logic" - return -ENOSYS; -} - -/* Set up a new UDP connection. - * - * This function sets up a new UDP connection. The function will +/* This function sets up a new UDP connection. The function will * automatically allocate an unused local port for the new * connection. However, another port can be chosen by using the - * uip_udp_bind() call, after the uip_udp_new() function has been + * uip_udpbind() call, after the uip_udpconnect() function has been * called. * - * Example: - * - * uip_ipaddr_t addr; - * struct uip_udp_conn *c; - * - * uip_ipaddr(&addr, 192,168,2,1); - * c = uip_udp_new(&addr, HTONS(12345)); - * if(c != NULL) { - * uip_udp_bind(c, HTONS(12344)); - * } - * - * ripaddr The IP address of the remote host. - * - * rport The remote port number in network byte order. - * - * Return: The uip_udp_conn structure for the new connection or NULL - * if no connection could be allocated. + * addr The address of the remote host. */ -struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport) +#ifdef CONFIG_NET_IPv6 +int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr) +#else +int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr) +#endif { - struct uip_udp_conn *conn; - int i; + irqstate_t flags; /* Find an unused local port number. Loop until we find a valid listen port * number that is not being used by any other connection. @@ -283,42 +343,32 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport) g_last_udp_port = 4096; } } - while (uip_find_udp_conn(g_last_udp_port)); - - /* Now find an available UDP connection structure */ - - conn = 0; - for (i = 0; i < UIP_UDP_CONNS; i++) - { - if (uip_udp_conns[i].lport == 0) - { - conn = &uip_udp_conns[i]; - break; - } - } - - /* Return an error if no connection is available */ - - if (conn == 0) - { - return 0; - } + while (uip_find_conn(g_last_udp_port)); /* Initialize and return the connection structure, bind it to the port number */ conn->lport = HTONS(g_last_udp_port); - conn->rport = rport; - if (ripaddr == NULL) + if (addr) { - memset(conn->ripaddr, 0, sizeof(uip_ipaddr_t)); + conn->rport = addr->sin_port; + uip_ipaddr_copy(&conn->ripaddr, &addr->sin_addr.s_addr); } else { - uip_ipaddr_copy(&conn->ripaddr, ripaddr); - } + conn->rport = 0; + uip_ipaddr_copy(&conn->ripaddr, &all_zeroes_addr); + } + conn->ttl = UIP_TTL; + + /* Now add the connection structure to the active connectionlist. This list + * is modifiable from interrupt level, we we must diable interrupts to + * access it safely. + */ - conn->ttl = UIP_TTL; + flags = irqsave(); + dq_addlast(&conn->node, &g_active_udp_connections); + irqrestore(flags); return conn; } diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c index e45e0e560..44403af84 100644 --- a/nuttx/net/uip/uip.c +++ b/nuttx/net/uip/uip.c @@ -17,6 +17,7 @@ * 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 @@ -587,6 +588,18 @@ static void uip_add_rcv_nxt(uint16 n) uip_conn->rcv_nxt[3] = uip_acc32[3]; } +static uip_udp_callback(void) +{ + /* Some sanity checking */ + + if (uip_udp_conn && uip_udp_conn->callback) + { + /* Perform the callback */ + + uip_udp_conn->callback(uip_udp_conn->private); + } +} + void uip_interrupt(uint8 flag) { register struct uip_conn *uip_connr = uip_conn; @@ -759,7 +772,7 @@ void uip_interrupt(uint8 flag) uip_len = uip_slen = 0; uip_flags = UIP_POLL; uip_event_signal(); - uip_interrupt_udp_event(); + up_udp_callback(); goto udp_send; } else @@ -1099,7 +1112,7 @@ void uip_interrupt(uint8 flag) uip_sappdata = uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; uip_slen = 0; uip_event_signal(); - uip_interrupt_udp_event(); + up_udp_callback(); udp_send: if (uip_slen == 0) @@ -1256,7 +1269,7 @@ found_listen: /* First allocate a new connection structure */ - uip_connr = uip_tcpalloc(); + uip_connr = uip_tcplistener(BUF); if (!uip_connr) { /* All connections are used already, we drop packet and hope that @@ -1268,33 +1281,12 @@ found_listen: UIP_LOG("tcp: found no unused connections."); goto drop; } - uip_conn = uip_connr; - /* Fill in the necessary fields for the new connection. */ - - uip_connr->rto = uip_connr->timer = UIP_RTO; - uip_connr->sa = 0; - uip_connr->sv = 4; - uip_connr->nrtx = 0; - uip_connr->lport = BUF->destport; - uip_connr->rport = BUF->srcport; - uip_ipaddr_copy(uip_connr->ripaddr, BUF->srcipaddr); - uip_connr->tcpstateflags = UIP_SYN_RCVD; - - uip_connr->snd_nxt[0] = g_tcp_sequence[0]; - uip_connr->snd_nxt[1] = g_tcp_sequence[1]; - uip_connr->snd_nxt[2] = g_tcp_sequence[2]; - uip_connr->snd_nxt[3] = g_tcp_sequence[3]; - uip_connr->len = 1; - - /* rcv_nxt should be the seqno from the incoming packet + 1. */ - uip_connr->rcv_nxt[3] = BUF->seqno[3]; - uip_connr->rcv_nxt[2] = BUF->seqno[2]; - uip_connr->rcv_nxt[1] = BUF->seqno[1]; - uip_connr->rcv_nxt[0] = BUF->seqno[0]; uip_add_rcv_nxt(1); + uip_conn = uip_connr; /* Parse the TCP MSS option, if present. */ + if ((BUF->tcpoffset & 0xf0) > 0x50) { for (c = 0; c < ((BUF->tcpoffset >> 4) - 5) << 2 ;) @@ -1338,7 +1330,7 @@ found_listen: } /* Our response will be a SYNACK. */ - tcp_send_synack: +tcp_send_synack: BUF->flags = TCP_ACK; tcp_send_syn: -- cgit v1.2.3