summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xapps/ChangeLog.txt4
-rw-r--r--apps/netutils/telnetd/telnetd_driver.c37
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/include/net/psock.h312
-rw-r--r--nuttx/include/nuttx/net.h38
-rw-r--r--nuttx/net/net_clone.c4
-rw-r--r--nuttx/net/net_internal.h1
-rw-r--r--nuttx/net/net_sockets.c16
8 files changed, 80 insertions, 335 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index 248e6b5fe..9c13aeda2 100755
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -174,3 +174,7 @@
"wrapped" as character devices and mapped to stdin, stdout, and stderr.
Now the telnet session can be inherited by spawned tasks.
* examples/telnetd: Add a test for the new telnet daemon.
+ * examplex/telnetd/telnetd_driver.c: Move the internal socket structure from
+ the daemon's socket array into the driver's state data so that it will be
+ independent from the the telnetd daemon.
+
diff --git a/apps/netutils/telnetd/telnetd_driver.c b/apps/netutils/telnetd/telnetd_driver.c
index f74a97d4e..991f43705 100644
--- a/apps/netutils/telnetd/telnetd_driver.c
+++ b/apps/netutils/telnetd/telnetd_driver.c
@@ -62,7 +62,7 @@
#include <nuttx/fs.h>
#include <debug.h>
-#include <net/psock.h>
+#include <nuttx/net.h>
#include <apps/netutils/telnetd.h>
#include <apps/netutils/uiplib.h>
@@ -106,7 +106,7 @@ struct telnetd_dev_s
uint8_t td_pending; /* Number of valid, pending bytes in the rxbuffer */
uint8_t td_offset; /* Offset to the valid, pending bytes in the rxbuffer */
uint8_t td_crefs; /* The number of open references to the session */
- FAR struct socket *td_psock; /* A reference to the internal socket structure */
+ FAR struct socket td_psock; /* A clone of the internal socket structure */
char td_rxbuffer[CONFIG_TELNETD_RXBUFFER_SIZE];
char td_txbuffer[CONFIG_TELNETD_TXBUFFER_SIZE];
};
@@ -387,7 +387,7 @@ static void telnetd_sendopt(struct telnetd_dev_s *priv, uint8_t option,
optbuf[3] = 0;
telnetd_dumpbuffer("Send optbuf", optbuf, 4);
- if (psock_send(priv->td_psock, optbuf, 4, 0) < 0)
+ if (psock_send(&priv->td_psock, optbuf, 4, 0) < 0)
{
ndbg("Failed to send TELNET_IAC\n");
}
@@ -481,7 +481,7 @@ static int telnetd_close(FAR struct file *filep)
}
else
{
- psock_close(priv->td_psock);
+ psock_close(&priv->td_psock);
sem_post(&priv->td_exclsem);
sem_destroy(&priv->td_exclsem);
free(priv);
@@ -517,7 +517,7 @@ static ssize_t telnetd_read(FAR struct file *filep, FAR char *buffer, size_t len
else
{
- ret = psock_recv(priv->td_psock, priv->td_rxbuffer,
+ ret = psock_recv(&priv->td_psock, priv->td_rxbuffer,
CONFIG_TELNETD_RXBUFFER_SIZE, 0);
if (ret > 0)
{
@@ -566,7 +566,7 @@ static ssize_t telnetd_write(FAR struct file *filep, FAR const char *buffer, siz
{
/* Yes... send the data now */
- ret = psock_send(priv->td_psock, priv->td_txbuffer, ncopied, 0);
+ ret = psock_send(&priv->td_psock, priv->td_txbuffer, ncopied, 0);
if (ret < 0)
{
ndbg("Failed to send response: %s\n", priv->td_txbuffer);
@@ -585,7 +585,7 @@ static ssize_t telnetd_write(FAR struct file *filep, FAR const char *buffer, siz
if (ncopied > 0)
{
- ret = psock_send(priv->td_psock, priv->td_txbuffer, ncopied, 0);
+ ret = psock_send(&priv->td_psock, priv->td_txbuffer, ncopied, 0);
if (ret < 0)
{
ndbg("Failed to send response: %s\n", priv->td_txbuffer);
@@ -661,6 +661,7 @@ static int telnetd_poll(FAR struct file *filep, FAR struct pollfd *fds,
FAR char *telnetd_driver(int sd, FAR struct telnetd_s *daemon)
{
FAR struct telnetd_dev_s *priv;
+ FAR struct socket *psock;
FAR char *devpath = NULL;
int minor;
int ret;
@@ -676,18 +677,34 @@ FAR char *telnetd_driver(int sd, FAR struct telnetd_s *daemon)
/* Initialize the allocated driver instance */
- priv->td_psock = sockfd_socket(sd);
priv->td_state = STATE_NORMAL;
priv->td_crefs = 0;
priv->td_pending = 0;
priv->td_offset = 0;
- if (!priv->td_psock)
+ /* Clone the internal socket structure. We do this so that it will be
+ * independent of threads and of socket descriptors (the original socket
+ * instance resided in the daemon's socket array).
+ */
+
+ psock = sockfd_socket(sd);
+ if (!psock)
{
- ndbg("Failed to convert sd=%d to a socket structure\n");
+ ndbg("Failed to convert sd=%d to a socket structure\n", sd);
goto errout_with_dev;
}
+ ret = net_clone(psock, &priv->td_psock);
+ if (ret < 0)
+ {
+ ndbg("net_clone failed: %d\n", ret);
+ goto errout_with_dev;
+ }
+
+ /* And close the original */
+
+ psock_close(psock);
+
/* Allocation a unique minor device number of the telnet drvier */
do
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index f5d211d26..476ef113e 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2410,3 +2410,6 @@
(submitted by Mike Smith).
* include/net/psock.h: Added a new low level socket interface that allows the
OS to use the socket interface without having a socket descriptor.
+ * include/net/psock.h: Removed psock.h. The new interfaces are moved into
+ nuttx/net.h which already has similar logic.
+
diff --git a/nuttx/include/net/psock.h b/nuttx/include/net/psock.h
deleted file mode 100644
index 26691d5df..000000000
--- a/nuttx/include/net/psock.h
+++ /dev/null
@@ -1,312 +0,0 @@
-/****************************************************************************
- * include/net/psock.h
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __NET_PSOCK_H
-#define __NET_PSOCK_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <sys/types.h>
-
-#ifdef CONFIG_NET
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/****************************************************************************
- * Function: sockfd_socket
- *
- * Description:
- * Given a socket descriptor, return the underly NuttX-specific socket
- * structure.
- *
- * Parameters:
- * psock Socket instance
- *
- * Returned Value:
- * 0 on success; -1 on error with errno set appropriately.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-struct socket;
-EXTERN FAR struct socket *sockfd_socket(int sockfd);
-
-/****************************************************************************
- * Function: psock_close
- *
- * Description:
- * Performs the close operation on a socket instance
- *
- * Parameters:
- * psock Socket instance
- *
- * Returned Value:
- * 0 on success; -1 on error with errno set appropriately.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-struct socket;
-EXTERN int psock_close(FAR struct socket *psock);
-
-/****************************************************************************
- * Function: psock_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(sockfd,buf,len,flags) is
- * equivalent to sendto(sockfd,buf,len,flags,NULL,0).
- *
- * Parameters:
- * psock And instance of the internal socket structure.
- * 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:
- *
- ****************************************************************************/
-
-struct socket;
-EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
- size_t len, int flags);
-
-/****************************************************************************
- * Function: psock_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:
- * psock A pointer to a NuttX-specific, internal socket structure
- * 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:
- *
- ****************************************************************************/
-
-struct socket;
-struct sockaddr;
-EXTERN ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
- size_t len, int flags, FAR const struct sockaddr *to,
- socklen_t tolen);
-
-/****************************************************************************
- * Function: psock_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:
- * psock A pointer to a NuttX-specific, internal socket structure
- * buf Buffer to receive data
- * len Length of buffer
- * flags Receive flags
- * from Address of source (may be NULL)
- * 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.
- * 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:
- *
- ****************************************************************************/
-
-struct socket;
-struct sockaddr;
-EXTERN ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf,
- size_t len, int flags,FAR struct sockaddr *from,
- FAR socklen_t *fromlen);
-
-#define psock_recv(psock,buf,len,flags) psock_recvfrom(psock,buf,len,flags,NULL,0)
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* CONFIG_NET */
-#endif /* __NET_PSOCK_H */
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index c04d12069..64d9cdc56 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -1,8 +1,8 @@
/****************************************************************************
* nuttx/net.h
*
- * Copyright (C) 2007, 2009-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2007, 2009-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -144,6 +144,12 @@ EXTERN FAR struct socketlist *net_alloclist(void);
EXTERN int net_addreflist(FAR struct socketlist *list);
EXTERN int net_releaselist(FAR struct socketlist *list);
+/* Given a socket descriptor, return the underly NuttX-specific socket
+ * structure.
+ */
+
+EXTERN FAR struct socket *sockfd_socket(int sockfd);
+
/* net_close.c ***************************************************************/
/* The standard close() operation redirects operations on socket descriptors
* to this function.
@@ -151,6 +157,34 @@ EXTERN int net_releaselist(FAR struct socketlist *list);
EXTERN int net_close(int sockfd);
+/* Performs the close operation on a socket instance */
+
+EXTERN int psock_close(FAR struct socket *psock);
+
+/* send.c ********************************************************************/
+/* Send using underlying socket structure */
+
+EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
+ size_t len, int flags);
+
+/* sendto.c ******************************************************************/
+/* Sendto using underlying socket structure */
+
+EXTERN ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
+ size_t len, int flags, FAR const struct sockaddr *to,
+ socklen_t tolen);
+
+/* recvfrom.c ****************************************************************/
+/* recvfrom using the underlying socket structure */
+
+EXTERN ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf,
+ size_t len, int flags,FAR struct sockaddr *from,
+ FAR socklen_t *fromlen);
+
+/* recv using the underlying socket structure */
+
+#define psock_recv(psock,buf,len,flags) psock_recvfrom(psock,buf,len,flags,NULL,0)
+
/* net_ioctl.c ***************************************************************/
/* The standard ioctl() operation redirects operations on socket descriptors
* to this function.
diff --git a/nuttx/net/net_clone.c b/nuttx/net/net_clone.c
index 8100e63d2..ada223484 100644
--- a/nuttx/net/net_clone.c
+++ b/nuttx/net/net_clone.c
@@ -1,8 +1,8 @@
/****************************************************************************
* net/net_clone.c
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index 4046070ab..190d57815 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -48,7 +48,6 @@
#include <time.h>
#include <nuttx/net.h>
-#include <net/psock.h>
#include <net/uip/uip.h>
/****************************************************************************
diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c
index 31c1709d7..0ff4b57ad 100644
--- a/nuttx/net/net_sockets.c
+++ b/nuttx/net/net_sockets.c
@@ -185,20 +185,20 @@ int net_releaselist(FAR struct socketlist *list)
if (crefs <= 0)
{
- /* Close each open socket in the list
- * REVISIT: psock_close() will attempt to use semaphores.
- * If we actually are in the IDLE thread, then could this cause
- * problems? Probably not, it the task has exited and crefs is
- * zero, then there probably could not be a contender for the
- * semaphore.
- */
+ /* Close each open socket in the list
+ * REVISIT: psock_close() will attempt to use semaphores.
+ * If we actually are in the IDLE thread, then could this cause
+ * problems? Probably not, if the task has exited and crefs is
+ * zero, then there probably could not be a contender for the
+ * semaphore.
+ */
for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++)
{
FAR struct socket *psock = &list->sl_sockets[ndx];
if (psock->s_crefs > 0)
{
- (void)psock_close(psock);
+ (void)psock_close(psock);
}
}