summaryrefslogtreecommitdiff
path: root/nuttx/lib
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-22 23:38:33 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-22 23:38:33 +0000
commitb0c7d2e83b464bc3b620dd389de1bceba453909d (patch)
tree30bf114247b468440ddf59a026c6a205cde6b5f0 /nuttx/lib
parentab92a9dd0a6a84517ec966e5c79e4e692970ba16 (diff)
downloadpx4-nuttx-b0c7d2e83b464bc3b620dd389de1bceba453909d.tar.gz
px4-nuttx-b0c7d2e83b464bc3b620dd389de1bceba453909d.tar.bz2
px4-nuttx-b0c7d2e83b464bc3b620dd389de1bceba453909d.zip
Add chdir() and getcwd()
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@837 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/lib')
-rw-r--r--nuttx/lib/Makefile2
-rw-r--r--nuttx/lib/lib_chdir.c131
-rw-r--r--nuttx/lib/lib_cwdsem.c86
-rw-r--r--nuttx/lib/lib_getcwd.c139
-rw-r--r--nuttx/lib/lib_internal.h44
-rw-r--r--nuttx/lib/lib_strlen.c22
6 files changed, 395 insertions, 29 deletions
diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
index 4f0eddb7a..cf35a0541 100644
--- a/nuttx/lib/Makefile
+++ b/nuttx/lib/Makefile
@@ -57,7 +57,7 @@ STDIO_SRCS = lib_printf.c lib_rawprintf.c lib_lowprintf.c lib_dbg.c \
lib_lowstream.c lib_nullstream.c lib_sscanf.c
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-STDIO_SRCS += lib_rawstream.c
+STDIO_SRCS += lib_rawstream.c lib_chdir.c lib_getcwd.c lib_cwdsem.c
ifneq ($(CONFIG_NFILE_STREAMS),0)
STDIO_SRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \
lib_fgetc.c lib_fgets.c lib_gets.c lib_fwrite.c lib_libfwrite.c \
diff --git a/nuttx/lib/lib_chdir.c b/nuttx/lib/lib_chdir.c
new file mode 100644
index 000000000..008e923ec
--- /dev/null
+++ b/nuttx/lib/lib_chdir.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * lib/lib_chdir.c
+ *
+ * Copyright (C) 2008 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 <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <errno.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+char *g_cwd = NULL;
+char *g_prevcwd = NULL;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: chdir
+ *
+ * Description:
+ * The chdir() function causes the directory named by the pathname pointed
+ * to by the 'path' argument to become the current working directory; that
+ * is, the starting point for path searches for pathnames not beginning
+ * with '/'.
+ *
+ * Input Parmeters:
+ * path - A pointer to a directory to use as the new current working
+ * directory
+ *
+ * Returned Value:
+ * 0(OK) on success; -1(ERROR) on failure with errno set appropriately:
+ *
+ * EACCES
+ * Search permission is denied for any component of the pathname.
+ * ELOOP
+ * A loop exists in symbolic links encountered during resolution of the
+ * 'path' argument OR more that SYMLOOP_MAX symbolic links in the
+ * resolution of the 'path' argument.
+ * ENAMETOOLONG
+ * The length of the path argument exceeds PATH_MAX or a pathname component
+ * is longer than NAME_MAX.
+ * ENOENT
+ * A component of 'path' does not name an existing directory or path is
+ * an empty string.
+ * ENOTDIR
+ * A component of the pathname is not a directory.
+ *
+ ****************************************************************************/
+
+int chdir(FAR const char *path)
+{
+ char *duppath;
+
+ /* Verify the input parameters */
+
+ if (!path)
+ {
+ errno = ENOENT;
+ return ERROR;
+ }
+
+ /* Verify that 'path' refers to a directory */
+ /* (To be provided) */
+
+ /* Make a persistent copy of 'path' */
+
+ duppath = strdup(path);
+
+ /* Free any preceding cwd and set the previous to the cwd (this
+ * is to support 'cd -' in NSH
+ */
+
+ cwd_semtake();
+ if (g_prevcwd)
+ {
+ free(g_prevcwd);
+ }
+ g_prevcwd = g_cwd;
+
+ /* Set the cwd to a persistent copy of the input 'path' */
+
+ g_cwd = duppath;
+ cwd_semgive();
+ return OK;
+}
+#endif /* CONFIG_NFILE_DESCRIPTORS */
diff --git a/nuttx/lib/lib_cwdsem.c b/nuttx/lib/lib_cwdsem.c
new file mode 100644
index 000000000..d06487890
--- /dev/null
+++ b/nuttx/lib/lib_cwdsem.c
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * lib/lib_cwdsem.c
+ *
+ * Copyright (C) 2008 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 <assert.h>
+#include <semaphore.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+static sem_t g_cwdsem = { 1 };
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: cwd_semtake
+ ****************************************************************************/
+
+void cwd_semtake(void)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&g_cwdsem) != 0)
+ {
+ /* The only case that an error should occr here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+/****************************************************************************
+ * Name: cwd_semgive
+ ****************************************************************************/
+
+void cwd_semgive(void)
+{
+ /* Give the semaphore */
+
+ (void)sem_post(&g_cwdsem);
+}
+#endif /* CONFIG_NFILE_DESCRIPTORS */
diff --git a/nuttx/lib/lib_getcwd.c b/nuttx/lib/lib_getcwd.c
new file mode 100644
index 000000000..a0db05c09
--- /dev/null
+++ b/nuttx/lib/lib_getcwd.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * lib/lib_getcwd.c
+ *
+ * Copyright (C) 2008 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 <string.h>
+#include <unistd.h>
+#include <errno.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: getwcd
+ *
+ * Description:
+ * getcwd() function places the absolute pathname of the current working
+ * directory in the array pointed to by 'buf', and returns 'buf.' The
+ * pathname copied to the array shall contain no components that are
+ * symbolic links. The 'size' argument is the size in bytes of the
+ * character array pointed to by the 'buf' argument.
+ *
+ * Input Parmeters:
+ * buf - a pointer to the location in which the current working directory
+ * pathaname is returned.
+ * size - The size in bytes avaiable at 'buf'
+ *
+ * Returned Value:
+ * Upon successful completion, getcwd() returns the 'buf' argument.
+ * Otherwise, getcwd() returns a null pointer and sets errno to indicate
+ * the error:
+ *
+ * EINVAL
+ * The 'size' argument is 0 or the 'buf' argument is NULL.
+ * ERANGE
+ * The size argument is greater than 0, but is smaller than the length
+ * of the currrent working directory pathname +1.
+ * EACCES
+ * Read or search permission was denied for a component of the pathname.
+ * ENOMEM
+ * Insufficient storage space is available.
+ *
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+FAR char *getcwd(FAR char *buf, size_t size)
+{
+ const char *ptr;
+ int err;
+
+ /* Verify input parameters */
+
+ if (!buf || !size)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* If no working directory is defined, then default to the home directory */
+
+ cwd_semtake();
+ if (g_cwd)
+ {
+ ptr = g_cwd;
+ }
+ else
+ {
+ ptr = CONFIG_LIB_HOMEDIR;
+ }
+
+ /* Verify that the cwd will fit into the user-provided buffer */
+
+ if (strlen(ptr) + 1 > size)
+ {
+ err = ERANGE;
+ goto errout_with_sem;
+ }
+
+ /* Copy the cwd to the user buffer */
+
+ strcpy(buf, ptr);
+ cwd_semgive();
+ return buf;
+
+errout_with_sem:
+ cwd_semgive();
+errout:
+ errno = err;
+ return NULL;
+}
+#endif /* CONFIG_NFILE_DESCRIPTORS */
diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h
index 95dca3de8..067b64c24 100644
--- a/nuttx/lib/lib_internal.h
+++ b/nuttx/lib/lib_internal.h
@@ -1,7 +1,7 @@
-/************************************************************
- * lib_internal.h
+/****************************************************************************
+ * lib/lib_internal.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,22 +31,26 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __LIB_INTERNAL_H
#define __LIB_INTERNAL_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <semaphore.h>
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
+
+#ifndef CONFIG_LIB_HOMEDIR
+# define CONFIG_LIB_HOMEDIR "/"
+#endif
#if CONFIG_STDIO_BUFFER_SIZE <= 0
# define lib_sem_initialize(s)
@@ -56,9 +60,9 @@
#define LIB_BUFLEN_UNKNOWN (0x7fffffff)
-/************************************************************
+/****************************************************************************
* Public Types
- ************************************************************/
+ ****************************************************************************/
/* This is the generic for of a stream used by the library
* to manage variable sized output.
@@ -94,13 +98,18 @@ struct lib_rawstream_s
int fd;
};
-/************************************************************
+/****************************************************************************
* Public Variables
- ************************************************************/
+ ****************************************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+extern char *g_cwd; /* Defined in lib_chdir.c */
+extern char *g_prevcwd; /* Defined in lib_chdir.c */
+#endif
-/************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************/
+ ****************************************************************************/
/* Defined in lib_streamsem.c */
@@ -184,4 +193,9 @@ extern void lib_give_semaphore(FAR struct file_struct *stream);
extern int lib_getbase(const char *nptr, const char **endptr);
+/* Defined in lib_cwdsem.c */
+
+extern void cwd_semtake(void);
+extern void cwd_semgive(void);
+
#endif /* __LIB_INTERNAL_H */
diff --git a/nuttx/lib/lib_strlen.c b/nuttx/lib/lib_strlen.c
index f2cf6f227..9c829c61f 100644
--- a/nuttx/lib/lib_strlen.c
+++ b/nuttx/lib/lib_strlen.c
@@ -1,7 +1,7 @@
-/************************************************************
- * lib_strlen.c
+/****************************************************************************
+ * lib/lib_strlen.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,23 +31,19 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
- * Compilation Switches
- ************************************************************/
-
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <string.h>
-/************************************************************
+/****************************************************************************
* Global Functions
- ************************************************************/
+ ****************************************************************************/
#ifndef CONFIG_ARCH_STRLEN
size_t strlen(const char *s)