summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/fs/Makefile11
-rw-r--r--nuttx/fs/fs_close.c2
-rw-r--r--nuttx/fs/fs_dup.c109
-rw-r--r--nuttx/fs/fs_dup2.c108
-rw-r--r--nuttx/fs/fs_filedup.c124
-rw-r--r--nuttx/fs/fs_filedup2.c121
-rw-r--r--nuttx/include/net/uip/uip-tcp.h1
-rw-r--r--nuttx/include/net/uip/uip-udp.h1
-rw-r--r--nuttx/include/nuttx/fs.h24
-rw-r--r--nuttx/include/nuttx/net.h18
-rw-r--r--nuttx/lib/lib_stdinstream.c7
-rw-r--r--nuttx/net/Makefile2
-rw-r--r--nuttx/net/accept.c13
-rw-r--r--nuttx/net/net_clone.c117
-rw-r--r--nuttx/net/net_close.c80
-rw-r--r--nuttx/net/net_dup.c134
-rw-r--r--nuttx/net/net_dup2.c126
-rw-r--r--nuttx/net/net_internal.h22
-rw-r--r--nuttx/net/socket.c35
-rw-r--r--nuttx/net/uip/uip_tcpbacklog.c6
-rw-r--r--nuttx/net/uip/uip_tcpconn.c1
-rw-r--r--nuttx/net/uip/uip_udpconn.c2
-rw-r--r--nuttx/sched/sched_setupidlefiles.c4
23 files changed, 945 insertions, 123 deletions
diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
index 1fce0e423..30073db9e 100644
--- a/nuttx/fs/Makefile
+++ b/nuttx/fs/Makefile
@@ -45,11 +45,12 @@ CSRCS += fs_close.c fs_write.c fs_ioctl.c fs_poll.c fs_select.c
endif
else
CSRCS += fs_open.c fs_close.c fs_read.c fs_write.c fs_ioctl.c fs_poll.c \
- fs_select.c fs_lseek.c fs_dup.c fs_mmap.c fs_opendir.c fs_closedir.c \
- fs_stat.c fs_readdir.c fs_readdirr.c fs_seekdir.c fs_telldir.c \
- fs_rewinddir.c fs_files.c fs_inode.c fs_inodefind.c fs_inodereserve.c \
- fs_statfs.c fs_inoderemove.c fs_registerdriver.c fs_unregisterdriver.c \
- fs_inodeaddref.c fs_inoderelease.c
+ fs_select.c fs_lseek.c fs_dup.c fs_filedup.c fs_dup2.c fs_filedup2.c \
+ fs_mmap.c fs_opendir.c fs_closedir.c fs_stat.c fs_readdir.c fs_readdirr.c \
+ fs_seekdir.c fs_telldir.c fs_rewinddir.c fs_files.c fs_inode.c \
+ fs_inodefind.c fs_inodereserve.c fs_statfs.c fs_inoderemove.c \
+ fs_registerdriver.c fs_unregisterdriver.c fs_inodeaddref.c \
+ fs_inoderelease.c
CSRCS += fs_registerblockdriver.c fs_unregisterblockdriver.c \
fs_findblockdriver.c fs_openblockdriver.c fs_closeblockdriver.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
diff --git a/nuttx/fs/fs_close.c b/nuttx/fs/fs_close.c
index 4970c459d..a60bc592d 100644
--- a/nuttx/fs/fs_close.c
+++ b/nuttx/fs/fs_close.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_close.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/fs/fs_dup.c b/nuttx/fs/fs_dup.c
index 8f8b332b1..20b7fbf27 100644
--- a/nuttx/fs/fs_dup.c
+++ b/nuttx/fs/fs_dup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_dup.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,16 +43,21 @@
#include <unistd.h>
#include <sched.h>
#include <errno.h>
+
+#include <nuttx/fs.h>
#include "fs_internal.h"
+/* This logic in this applies only when both socket and file descriptors are
+ * in that case, this function descriminates which type of dup is being
+ * performed.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
/****************************************************************************
* Definitions
****************************************************************************/
-#define DUP_ISOPEN(fd, list) \
- ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS && \
- list->fl_files[fd].f_inode != NULL)
-
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -61,82 +66,44 @@
* Global Functions
****************************************************************************/
+/****************************************************************************
+ * Name: dup
+ *
+ * Description:
+ * Clone a file or socket descriptor to an arbitray descriptor number
+ *
+ ****************************************************************************/
+
int dup(int fildes)
{
- FAR struct filelist *list;
- int fildes2;
+ /* Check the range of the descriptor to see if we got a file or a socket
+ * descriptor. */
- /* Get the thread-specific file list */
-
- list = sched_getfiles();
- if (!list)
+ if ((unsigned int)fildes >= CONFIG_NFILE_DESCRIPTORS)
{
- *get_errno_ptr() = EMFILE;
- return ERROR;
- }
-
- /* Verify that fildes is a valid, open file descriptor */
+ /* Not a vailid file descriptor. Did we get a valid socket descriptor? */
- if (!DUP_ISOPEN(fildes, list))
- {
- *get_errno_ptr() = EBADF;
- return ERROR;
- }
+ if ((unsigned int)fildes < (CONFIG_NFILE_DESCRIPTORS+CONFIG_NSOCKET_DESCRIPTORS))
+ {
+ /* Yes.. dup the socket descriptor */
- /* Increment the reference count on the contained inode */
+ return net_dup(fildes);
+ }
+ else
+ {
+ /* No.. then it is a bad descriptor number */
- inode_addref(list->fl_files[fildes].f_inode);
-
- /* Then allocate a new file descriptor for the inode */
-
- fildes2 = files_allocate(list->fl_files[fildes].f_inode,
- list->fl_files[fildes].f_oflags,
- list->fl_files[fildes].f_pos);
- if (fildes2 < 0)
- {
- *get_errno_ptr() = EMFILE;
- inode_release(list->fl_files[fildes].f_inode);
- return ERROR;
+ errno = EBADF;
+ return ERROR;
+ }
}
- return fildes2;
-}
-
-int dup2(int fildes1, int fildes2)
-{
- FAR struct filelist *list;
-
- /* Get the thread-specific file list */
-
- list = sched_getfiles();
- if (!list)
+ else
{
- *get_errno_ptr() = EMFILE;
- return ERROR;
- }
+ /* Its a valid file descriptor.. dup the file descriptor */
- /* Verify that fildes is a valid, open file descriptor */
-
- if (!DUP_ISOPEN(fildes1, list))
- {
- *get_errno_ptr() = EBADF;
- return ERROR;
+ return file_dup(fildes);
}
-
- /* Handle a special case */
-
- if (fildes1 == fildes2)
- {
- return fildes1;
- }
-
- /* Verify fildes2 */
-
- if ((unsigned int)fildes2 >= CONFIG_NFILE_DESCRIPTORS)
- {
- *get_errno_ptr() = EBADF;
- return ERROR;
- }
-
- return files_dup(&list->fl_files[fildes1], &list->fl_files[fildes2]);
}
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 ... */
+
diff --git a/nuttx/fs/fs_dup2.c b/nuttx/fs/fs_dup2.c
new file mode 100644
index 000000000..546c024dc
--- /dev/null
+++ b/nuttx/fs/fs_dup2.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ * fs/fs_dup2.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+#include <sched.h>
+#include <errno.h>
+#include "fs_internal.h"
+
+/* This logic in this applies only when both socket and file descriptors are
+ * in that case, this function descriminates which type of dup2 is being
+ * performed.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: dup2
+ *
+ * Description:
+ * Clone a file descriptor or socket descriptor to a specific descriptor
+ * number
+ *
+ ****************************************************************************/
+
+int dup2(int fildes1, int fildes2)
+{
+ /* Check the range of the descriptor to see if we got a file or a socket
+ * descriptor. */
+
+ if ((unsigned int)fildes1 >= CONFIG_NFILE_DESCRIPTORS)
+ {
+ /* Not a vailid file descriptor. Did we get a valid socket descriptor? */
+
+ if ((unsigned int)fildes1 < (CONFIG_NFILE_DESCRIPTORS+CONFIG_NSOCKET_DESCRIPTORS))
+ {
+ /* Yes.. dup the socket descriptor */
+
+ return net_dup2(fildes1, fildes2);
+ }
+ else
+ {
+ /* No.. then it is a bad descriptor number */
+
+ errno = EBADF;
+ return ERROR;
+ }
+ }
+ else
+ {
+ /* Its a valid file descriptor.. dup the file descriptor */
+
+ return file_dup2(fildes1, fildes2);
+ }
+}
+
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 ... */
+
diff --git a/nuttx/fs/fs_filedup.c b/nuttx/fs/fs_filedup.c
new file mode 100644
index 000000000..71f625877
--- /dev/null
+++ b/nuttx/fs/fs_filedup.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ * fs/fs_filedup.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+#include <sched.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+#include "fs_internal.h"
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define DUP_ISOPEN(fd, list) \
+ ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS && \
+ list->fl_files[fd].f_inode != NULL)
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: file_dup OR dup
+ *
+ * Description:
+ * Clone a file descriptor to an arbitray descriptor number. If socket
+ * descriptors are implemented, then this is called by dup() for the case
+ * of file descriptors. If socket descriptors are not implemented, then
+ * this function IS dup().
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+int file_dup(int fildes)
+#else
+int dup(int fildes)
+#endif
+{
+ FAR struct filelist *list;
+ int fildes2;
+
+ /* Get the thread-specific file list */
+
+ list = sched_getfiles();
+ if (!list)
+ {
+ errno = EMFILE;
+ return ERROR;
+ }
+
+ /* Verify that fildes is a valid, open file descriptor */
+
+ if (!DUP_ISOPEN(fildes, list))
+ {
+ errno = EBADF;
+ return ERROR;
+ }
+
+ /* Increment the reference count on the contained inode */
+
+ inode_addref(list->fl_files[fildes].f_inode);
+
+ /* Then allocate a new file descriptor for the inode */
+
+ fildes2 = files_allocate(list->fl_files[fildes].f_inode,
+ list->fl_files[fildes].f_oflags,
+ list->fl_files[fildes].f_pos);
+ if (fildes2 < 0)
+ {
+ errno = EMFILE;
+ inode_release(list->fl_files[fildes].f_inode);
+ return ERROR;
+ }
+ return fildes2;
+}
+
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */
+
diff --git a/nuttx/fs/fs_filedup2.c b/nuttx/fs/fs_filedup2.c
new file mode 100644
index 000000000..e1c2462d8
--- /dev/null
+++ b/nuttx/fs/fs_filedup2.c
@@ -0,0 +1,121 @@
+/****************************************************************************
+ * fs/fs_filedup2.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+#include <sched.h>
+#include <errno.h>
+#include "fs_internal.h"
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define DUP_ISOPEN(fd, list) \
+ ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS && \
+ list->fl_files[fd].f_inode != NULL)
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: file_dup2
+ *
+ * Description:
+ * Clone a file descriptor or socket descriptor to a specific descriptor
+ * number. If socket descriptors are implemented, then this is called by
+ * dup2() for the case of file descriptors. If socket descriptors are not
+ * implemented, then this function IS dup2().
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+int file_dup2(int fildes1, int fildes2)
+#else
+int dup2(int fildes1, int fildes2)
+#endif
+{
+ FAR struct filelist *list;
+
+ /* Get the thread-specific file list */
+
+ list = sched_getfiles();
+ if (!list)
+ {
+ errno = EMFILE;
+ return ERROR;
+ }
+
+ /* Verify that fildes is a valid, open file descriptor */
+
+ if (!DUP_ISOPEN(fildes1, list))
+ {
+ errno = EBADF;
+ return ERROR;
+ }
+
+ /* Handle a special case */
+
+ if (fildes1 == fildes2)
+ {
+ return fildes1;
+ }
+
+ /* Verify fildes2 */
+
+ if ((unsigned int)fildes2 >= CONFIG_NFILE_DESCRIPTORS)
+ {
+ errno = EBADF;
+ return ERROR;
+ }
+
+ return files_dup(&list->fl_files[fildes1], &list->fl_files[fildes2]);
+}
+
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */
+
diff --git a/nuttx/include/net/uip/uip-tcp.h b/nuttx/include/net/uip/uip-tcp.h
index c574793a9..1fe199e70 100644
--- a/nuttx/include/net/uip/uip-tcp.h
+++ b/nuttx/include/net/uip/uip-tcp.h
@@ -134,6 +134,7 @@ struct uip_conn
* connection */
uint16 initialmss; /* Initial maximum segment size for the
* connection */
+ uint8 crefs; /* Reference counts on this instance */
uint8 sa; /* Retransmission time-out calculation state
* variable */
uint8 sv; /* Retransmission time-out calculation state
diff --git a/nuttx/include/net/uip/uip-udp.h b/nuttx/include/net/uip/uip-udp.h
index 5cc11adb7..69f0ea7f5 100644
--- a/nuttx/include/net/uip/uip-udp.h
+++ b/nuttx/include/net/uip/uip-udp.h
@@ -77,6 +77,7 @@ struct uip_udp_conn
uint16 lport; /* The local port number in network byte order */
uint16 rport; /* The remote port number in network byte order */
uint8 ttl; /* Default time-to-live */
+ uint8 crefs; /* Reference counts on this instance */
/* Defines the list of UDP callbacks */
diff --git a/nuttx/include/nuttx/fs.h b/nuttx/include/nuttx/fs.h
index 1326921df..68733029f 100644
--- a/nuttx/include/nuttx/fs.h
+++ b/nuttx/include/nuttx/fs.h
@@ -342,6 +342,30 @@ EXTERN int files_addreflist(FAR struct filelist *list);
EXTERN int files_releaselist(FAR struct filelist *list);
EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2);
+/* fs_filedup.c **************************************************************/
+
+/* This alternative naming is used when dup could operate on both file and
+ * socket descritors to avoid drawing unused socket support into the link.
+ */
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN int file_dup(int fd);
+#else
+# defile file_dup(fd) dup(fd)
+#endif
+
+/* fs_filedup2.c *************************************************************/
+
+/* This alternative naming is used when dup could operate on both file and
+ * socket descritors to avoid drawing unused socket support into the link.
+ */
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+EXTERN int file_dup2(int fd1, int fd2);
+#else
+# defile file_dup2(fd1, fd2) dup2(fd1, fd2)
+#endif
+
/* fs_openblockdriver.c ******************************************************/
EXTERN int open_blockdriver(FAR const char *pathname, int mountflags,
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index b6bdfbe74..9b83971df 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -1,7 +1,7 @@
/****************************************************************************
* nuttx/net.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -138,14 +138,14 @@ EXTERN FAR struct socketlist *net_alloclist(void);
EXTERN int net_addreflist(FAR struct socketlist *list);
EXTERN int net_releaselist(FAR struct socketlist *list);
-/* net-close.c ***************************************************************/
+/* net_close.c ***************************************************************/
/* The standard close() operation redirects operations on socket descriptors
* to this function.
*/
EXTERN int net_close(int sockfd);
-/* net-ioctl.c ***************************************************************/
+/* net_ioctl.c ***************************************************************/
/* The standard ioctl() operation redirects operations on socket descriptors
* to this function.
*/
@@ -153,7 +153,7 @@ EXTERN int net_close(int sockfd);
struct ifreq; /* Forward reference -- see net/ioctls.h */
EXTERN int netdev_ioctl(int sockfd, int cmd, struct ifreq *req);
-/* net-poll.c ****************************************************************/
+/* net_poll.c ****************************************************************/
/* The standard poll() operation redirects operations on socket descriptors
* to this function.
*/
@@ -163,6 +163,14 @@ struct pollfd; /* Forward reference -- see poll.h */
EXTERN int net_poll(int sockfd, struct pollfd *fds, boolean setup);
#endif
+/* net_dup.c *****************************************************************/
+/* The standard dup() and dup2() operations redirect operations on socket
+ * descriptors to these function.
+ */
+
+EXTERN int net_dup(int sockfd);
+EXTERN int net_dup2(int sockfd1, int sockfd2);
+
/* netdev-register.c *********************************************************/
/* This function is called by network interface device drivers to inform the
* socket layer of their existence. This registration is necesary to support
@@ -172,7 +180,7 @@ EXTERN int net_poll(int sockfd, struct pollfd *fds, boolean setup);
EXTERN int netdev_register(FAR struct uip_driver_s *dev);
-/* net-foreach.c ************************************************************/
+/* net_foreach.c ************************************************************/
/* Enumerates all registered network devices */
EXTERN int netdev_foreach(netdev_callback_t callback, void *arg);
diff --git a/nuttx/lib/lib_stdinstream.c b/nuttx/lib/lib_stdinstream.c
index 182696ead..4f99e4439 100644
--- a/nuttx/lib/lib_stdinstream.c
+++ b/nuttx/lib/lib_stdinstream.c
@@ -50,17 +50,16 @@
static int stdinstream_getc(FAR struct lib_instream_s *this)
{
FAR struct lib_stdinstream_s *sthis = (FAR struct lib_stdinstream_s *)this;
- int ret;
-
if (this)
{
- ret = getc(sthis->stream);
+ int ret = getc(sthis->stream);
if (ret != EOF)
{
this->nget++;
}
+ return ret;
}
- return ret;
+ return EOF;
}
/****************************************************************************
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 7880a974e..8802e01d7 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -38,7 +38,7 @@
ifeq ($(CONFIG_NET),y)
SOCK_ASRCS =
SOCK_CSRCS = socket.c bind.c connect.c sendto.c recv.c recvfrom.c \
- net_sockets.c net_close.c
+ net_sockets.c net_close.c net_dup.c net_dup2.c net_clone.c
ifeq ($(CONFIG_NET_TCP),y)
SOCK_CSRCS += send.c listen.c accept.c
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
index a3a2e067e..a9701b2d5 100644
--- a/nuttx/net/accept.c
+++ b/nuttx/net/accept.c
@@ -149,6 +149,14 @@ static int accept_interrupt(struct uip_conn *listener, struct uip_conn *conn)
pstate->acpt_newconn = conn;
pstate->acpt_result = OK;
+
+ /* Set a reference of one on the new connection */
+
+ DEBUGASSERT(conn->crefs == 0);
+ conn->crefs = 1;
+
+ /* Wake-up the waiting caller thread */
+
sem_post(&pstate->acpt_sem);
/* Stop any further callbacks */
@@ -405,7 +413,10 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
}
irqrestore(save);
- /* Initialize the socket structure and mark the socket as connected */
+ /* Initialize the socket structure and mark the socket as connected.
+ * (The reference count on the new connection structure was set in the
+ * interrupt handler).
+ */
pnewsock->s_type = SOCK_STREAM;
pnewsock->s_conn = state.acpt_newconn;
diff --git a/nuttx/net/net_clone.c b/nuttx/net/net_clone.c
new file mode 100644
index 000000000..e23016073
--- /dev/null
+++ b/nuttx/net/net_clone.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ * net/net_clone.c
+ *
+ * Copyright (C) 2009 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>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_clone
+ *
+ * Description:
+ * Performs the low level, common portion of net_dup() and net_dup2()
+ *
+ ****************************************************************************/
+
+int net_clone(FAR struct socket *psock1, FAR struct socket *psock2)
+{
+ irqstate_t flags;
+ int ret = OK;
+
+ /* Parts of this operation need to be atomic */
+
+ flags = irqsave();
+
+ /* Duplicate the socket state */
+
+ psock2->s_type = psock1->s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
+ psock2->s_flags = psock1->s_flags; /* See _SF_* definitions */
+#ifdef CONFIG_NET_SOCKOPTS
+ psock2->s_options = psock1->s_options; /* Selected socket options */
+#endif
+#ifndef CONFIG_DISABLE_CLOCK
+ psock2->s_rcvtimeo = psock1->s_rcvtimeo; /* Receive timeout value (in deciseconds) */
+ psock2->s_sndtimeo = psock1->s_sndtimeo; /* Send timeout value (in deciseconds) */
+#endif
+ psock2->s_conn = psock1->s_conn; /* UDP or TCP connection structure */
+
+ /* Increment the reference count on the connection */
+
+#ifdef CONFIG_NET_TCP
+ if (psock2->s_type == SOCK_STREAM)
+ {
+ struct uip_conn *conn = psock2->s_conn;
+ DEBUGASSERT(conn->crefs > 0);
+ conn->crefs++;
+ }
+ else
+#endif
+#ifdef CONFIG_NET_UDP
+ if (psock2->s_type == SOCK_DGRAM)
+ {
+ struct uip_udp_conn *conn = psock2->s_conn;
+ DEBUGASSERT(conn->crefs > 0);
+ conn->crefs++;
+ }
+ else
+#endif
+ {
+ ndbg("Unsupported type: %d\n", psock2->s_type);
+ ret = -EBADF;
+ }
+
+ irqrestore(flags);
+ return ret;
+}
+
+#endif /* CONFIG_NET */
+
+
diff --git a/nuttx/net/net_close.c b/nuttx/net/net_close.c
index 7ce1f9fa4..f8de0614a 100644
--- a/nuttx/net/net_close.c
+++ b/nuttx/net/net_close.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_close.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -61,7 +61,7 @@ struct tcp_close_s
{
FAR struct socket *cl_psock; /* Reference to the TCP socket */
FAR struct uip_callback_s *cl_cb; /* Reference to TCP callback instance */
- sem_t cl_sem; /* Semaphore signals disconnect completion */
+ sem_t cl_sem; /* Semaphore signals disconnect completion */
};
#endif
@@ -222,33 +222,75 @@ int net_close(int sockfd)
goto errout;
}
- /* Perform uIP side of the close depending on the protocol type */
+ /* We perform the uIP close operation only if this is the last count on the socket.
+ * (actually, I think the socket crefs only takes the values 0 and 1 right now).
+ */
- switch (psock->s_type)
+ if (psock->s_crefs <= 1)
{
-#ifdef CONFIG_NET_TCP
- case SOCK_STREAM:
+ /* Perform uIP side of the close depending on the protocol type */
+
+ switch (psock->s_type)
{
- struct uip_conn *conn = psock->s_conn;
- uip_unlisten(conn); /* No longer accepting connections */
- netclose_disconnect(psock); /* Break any current connections */
- uip_tcpfree(conn); /* Free uIP resources */
- }
- break;
+#ifdef CONFIG_NET_TCP
+ case SOCK_STREAM:
+ {
+ struct uip_conn *conn = psock->s_conn;
+
+ /* Is this the last reference to the connection structure (there
+ * could be more if the socket was dup'ed.
+ */
+
+ if (conn->crefs <= 1)
+ {
+ /* Yes... free the connection structure */
+
+ uip_unlisten(conn); /* No longer accepting connections */
+ netclose_disconnect(psock); /* Break any current connections */
+ uip_tcpfree(conn); /* Free uIP resources */
+ }
+ else
+ {
+ /* No.. Just decrement the reference count */
+
+ conn->crefs--;
+ }
+ }
+ break;
#endif
#ifdef CONFIG_NET_UDP
- case SOCK_DGRAM:
- uip_udpfree(psock->s_conn); /* Free uIP resources */
- break;
+ case SOCK_DGRAM:
+ {
+ struct uip_udp_conn *conn = psock->s_conn;
+
+ /* Is this the last reference to the connection structure (there
+ * could be more if the socket was dup'ed.
+ */
+
+ if (conn->crefs <= 1)
+ {
+ /* Yes... free the connection structure */
+
+ uip_udpfree(psock->s_conn); /* Free uIP resources */
+ }
+ else
+ {
+ /* No.. Just decrement the reference count */
+
+ conn->crefs--;
+ }
+ }
+ break;
#endif
- default:
- err = EBADF;
- goto errout;
+ default:
+ err = EBADF;
+ goto errout;
+ }
}
- /* Then release the socket structure containing the connection */
+ /* Then release our reference on the socket structure containing the connection */
sockfd_release(sockfd);
return OK;
diff --git a/nuttx/net/net_dup.c b/nuttx/net/net_dup.c
new file mode 100644
index 000000000..f4ee15abe
--- /dev/null
+++ b/nuttx/net/net_dup.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * net/net_dup.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dup OR dup
+ *
+ * Description:
+ * Clone a socket descriptor to an arbitray descriptor number. If file
+ * descriptors are implemented, then this is called by dup() for the case
+ * of socket file descriptors. If file descriptors are not implemented,
+ * then this function IS dup().
+ *
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTOR > 0
+int net_dup(int sockfd)
+#else
+int dup(int sockfd)
+#endif
+{
+ FAR struct socket *psock1 = sockfd_socket(sockfd);
+ FAR struct socket *psock2;
+ int sockfd2;
+ int err;
+ int ret;
+
+ /* Lock the scheduler throughout the following */
+
+ sched_lock();
+
+ /* Get the socket structure underlying sockfd */
+
+ psock1 = sockfd_socket(sockfd);
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock1 || psock1->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Allocate a new socket descriptor */
+
+ sockfd2 = sockfd_allocate();
+ if (sockfd2 < 0)
+ {
+ err = ENFILE;
+ goto errout;
+ }
+
+ /* Get the socket structure underlying the new descriptor */
+
+ psock2 = sockfd_socket(sockfd2);
+ if (!psock2)
+ {
+ err = ENOSYS; /* should not happen */
+ goto errout;
+ }
+
+ /* Duplicate the socket state */
+
+ ret = net_clone(psock1, psock2);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+
+ }
+
+ sched_unlock();
+ return sockfd2;
+
+errout:
+ sched_unlock();
+ errno = err;
+ return ERROR;
+}
+
+#endif /* defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
+
diff --git a/nuttx/net/net_dup2.c b/nuttx/net/net_dup2.c
new file mode 100644
index 000000000..8992ec226
--- /dev/null
+++ b/nuttx/net/net_dup2.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ * net/net_dup2.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "net_internal.h"
+
+#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dup2
+ *
+ * Description:
+ * Clone a socket descriptor to an arbitray descriptor number. If file
+ * descriptors are implemented, then this is called by dup2() for the case
+ * of socket file descriptors. If file descriptors are not implemented,
+ * then this function IS dup2().
+ *
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTOR > 0
+int net_dup2(int sockfd1, int sockfd2)
+#else
+int dup2(int sockfd1, int sockfd2)
+#endif
+{
+ FAR struct socket *psock1;
+ FAR struct socket *psock2;
+ int err;
+ int ret;
+
+ /* Lock the scheduler throughout the following */
+
+ sched_lock();
+
+ /* Get the socket structures underly both descriptors */
+
+ psock1 = sockfd_socket(sockfd1);
+ psock2 = sockfd_socket(sockfd2);
+
+ /* Verify that the sockfd1 and sockfd2 both refer to valid socket
+ * descriptors and that sockfd2 corresponds to allocated socket
+ */
+
+ if (!psock1 || !psock2 || psock1->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* If sockfd2 also valid, allocated socket, then we will have to
+ * close it!
+ */
+
+ if (psock2->s_crefs > 0)
+ {
+ net_close(sockfd2);
+ }
+
+ /* Duplicate the socket state */
+
+ ret = net_clone(psock1, psock2);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+
+ sched_unlock();
+ return OK;
+
+errout:
+ sched_unlock();
+ errno = err;
+ return ERROR;
+}
+
+#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
+
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index ebef372f9..ea3fdd5a6 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * net/net-internal.h
+ * net/net_internal.h
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -142,7 +142,7 @@ extern "C" {
#define EXTERN extern
#endif
-/* net-sockets.c *************************************************************/
+/* net_sockets.c *************************************************************/
EXTERN int sockfd_allocate(void);
EXTERN void sockfd_release(int sockfd);
@@ -156,38 +156,42 @@ EXTERN socktimeo_t net_timeval2dsec(struct timeval *tv);
EXTERN void net_dsec2timeval(uint16 dsec, struct timeval *tv);
#endif
-/* net-register.c ************************************************************/
+/* net_clone.c ***************************************************************/
+
+EXTERN int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
+
+/* net_register.c ************************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
EXTERN void netdev_semtake(void);
# define netdev_semgive() sem_post(&g_netdev_sem)
#endif
-/* net-findbyname.c **********************************************************/
+/* net_findbyname.c **********************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
EXTERN FAR struct uip_driver_s *netdev_findbyname(const char *ifname);
#endif
-/* net-findbyaddr.c **********************************************************/
+/* net_findbyaddr.c **********************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
EXTERN FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr);
#endif
-/* net-txnotify.c ************************************************************/
+/* net_txnotify.c ************************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
EXTERN void netdev_txnotify(const uip_ipaddr_t *raddr);
#endif
-/* net-count.c ***************************************************************/
+/* net_count.c ***************************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
EXTERN int netdev_count(void);
#endif
-/* net-arptimer.c ************************************************************/
+/* net_arptimer.c ************************************************************/
EXTERN void arptimer_init(void);
diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c
index 161866272..fddff2ccc 100644
--- a/nuttx/net/socket.c
+++ b/nuttx/net/socket.c
@@ -43,6 +43,7 @@
#include <sys/types.h>
#include <sys/socket.h>
#include <errno.h>
+#include <assert.h>
#include <debug.h>
#include "net_internal.h"
@@ -155,13 +156,43 @@ int socket(int domain, int type, int protocol)
{
#ifdef CONFIG_NET_TCP
case SOCK_STREAM:
- psock->s_conn = uip_tcpalloc();
+ {
+ /* Allocate the TCP connection structure and save in the new
+ * socket instance.
+ */
+
+ struct uip_conn *conn = uip_tcpalloc();
+ psock->s_conn = conn;
+
+ /* Set the reference count on the connection structure. This
+ * reference count will be increment only if the socket is
+ * dup'ed
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+ conn->crefs = 1;
+ }
break;
#endif
#ifdef CONFIG_NET_UDP
case SOCK_DGRAM:
- psock->s_conn = uip_udpalloc();
+ {
+ /* Allocate the UDP connection structure and save in the new
+ * socket instance.
+ */
+
+ struct uip_udp_conn *conn = uip_udpalloc();
+ psock->s_conn = conn;
+
+ /* Set the reference count on the connection structure. This
+ * reference count will be increment only if the socket is
+ * dup'ed
+ */
+
+ DEBUGASSERT(conn->crefs == 0);
+ conn->crefs = 1;
+ }
break;
#endif
diff --git a/nuttx/net/uip/uip_tcpbacklog.c b/nuttx/net/uip/uip_tcpbacklog.c
index 1eecdf9ad..e27c70a51 100644
--- a/nuttx/net/uip/uip_tcpbacklog.c
+++ b/nuttx/net/uip/uip_tcpbacklog.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_tcpbacklog.c
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,7 +68,7 @@
*
* Description:
* Called from the listen() logic to setup the backlog as specified in the
- * the listen arguments *.
+ * the listen arguments.
*
* Assumptions:
* Called from normal user code. Interrupts may be disabled.
@@ -213,7 +213,7 @@ int uip_backlogdestroy(FAR struct uip_conn *conn)
*
* Description:
* Called uip_listen when a new connection is made with a listener socket
- * but when there is not accept() in place to receive the connection. This
+ * but when there is no accept() in place to receive the connection. This
* function adds the new connection to the backlog.
*
* Assumptions:
diff --git a/nuttx/net/uip/uip_tcpconn.c b/nuttx/net/uip/uip_tcpconn.c
index af61bab46..12451a47f 100644
--- a/nuttx/net/uip/uip_tcpconn.c
+++ b/nuttx/net/uip/uip_tcpconn.c
@@ -294,6 +294,7 @@ void uip_tcpfree(struct uip_conn *conn)
* operation.
*/
+ DEBUGASSERT(conn->crefs == 0);
flags = irqsave();
/* UIP_ALLOCATED means that that the connection is not in the active list
diff --git a/nuttx/net/uip/uip_udpconn.c b/nuttx/net/uip/uip_udpconn.c
index ce23d2504..061f7dd78 100644
--- a/nuttx/net/uip/uip_udpconn.c
+++ b/nuttx/net/uip/uip_udpconn.c
@@ -271,6 +271,8 @@ void uip_udpfree(struct uip_udp_conn *conn)
* is protected by a semaphore (that behaves like a mutex).
*/
+ DEBUGASSERT(conn->crefs == 0);
+
_uip_semtake(&g_free_sem);
conn->lport = 0;
dq_addlast(&conn->node, &g_free_udp_connections);
diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c
index d1451ffd5..abe5e0d32 100644
--- a/nuttx/sched/sched_setupidlefiles.c
+++ b/nuttx/sched/sched_setupidlefiles.c
@@ -111,8 +111,8 @@ int sched_setupidlefiles(FAR _TCB *tcb)
fd = open("/dev/console", O_RDWR);
if (fd == 0)
{
- (void)dup2(0, 1);
- (void)dup2(0, 2);
+ (void)file_dup2(0, 1);
+ (void)file_dup2(0, 2);
}
else
{