summaryrefslogtreecommitdiff
path: root/nuttx/lib
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/lib')
-rw-r--r--nuttx/lib/Makefile5
-rw-r--r--nuttx/lib/lib_fgetpos.c125
-rw-r--r--nuttx/lib/lib_fseek.c28
-rw-r--r--nuttx/lib/lib_fsetpos.c116
-rw-r--r--nuttx/lib/lib_ftell.c129
-rw-r--r--nuttx/lib/lib_ungetc.c62
6 files changed, 428 insertions, 37 deletions
diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
index a56cde66f..d35abb129 100644
--- a/nuttx/lib/Makefile
+++ b/nuttx/lib/Makefile
@@ -60,8 +60,9 @@ ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
STDIO_SRCS += lib_rawstream.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 \
- lib_fflush.c lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \
+ lib_ftell.c lib_fsetpos.c lib_fgetpos.c lib_fgetc.c lib_fgets.c \
+ lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \
+ lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \
lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \
lib_fprintf.c lib_vfprintf.c lib_stdstream.c
endif
diff --git a/nuttx/lib/lib_fgetpos.c b/nuttx/lib/lib_fgetpos.c
new file mode 100644
index 000000000..92044a54c
--- /dev/null
+++ b/nuttx/lib/lib_fgetpos.c
@@ -0,0 +1,125 @@
+/****************************************************************************
+ * lib/lib_fgetpos.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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdio.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: fgetpos
+ *
+ * Description:
+ * fgetpos() function is an alternate interfaces equivalent to ftell().
+ * It gets the current value of the file offset and store it in the location
+ * referenced by pos. On some non-UNIX systems an fpos_t object may be a
+ * complex object and fsetpos may be the only way to portably reposition a
+ * stream.
+ *
+ * Returned Value:
+ * Zero on succes; -1 on failure with errno set appropriately.
+ *
+ ****************************************************************************/
+
+int fgetpos(FILE *stream, fpos_t *pos)
+{
+ long position;
+
+#if CONFIG_DEBUG
+ if (!stream || !pos)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ position = ftell(stream, (off_t)*pos, SEEK_SET);
+ if (position == -1)
+ {
+ return ERROR;
+ }
+
+ *pos = (fpos_t)pos;
+ return OK;
+}
diff --git a/nuttx/lib/lib_fseek.c b/nuttx/lib/lib_fseek.c
index 18781b6e3..379e5c322 100644
--- a/nuttx/lib/lib_fseek.c
+++ b/nuttx/lib/lib_fseek.c
@@ -89,11 +89,25 @@
/****************************************************************************
* Name: fseek
+ *
+ * Description:
+ * The fseek() function sets the file position indicator for the stream
+ * pointed to by stream. The new position, measured in bytes, is obtained
+ * by adding offset bytes to the position specified by whence. If whence is
+ * set to SEEK_SET, SEEK_CUR, or SEEK_END, the offset is relative to the
+ * start of the file, the current position indicator, or end-of-file,
+ * respectively. A successful call to the fseek() function clears the
+ * end-of-file indicator for the stream and undoes any effects of the ungetc(3)
+ * function on the same stream.
+ *
+ * Returned Value:
+ * Zero on succes; -1 on failure with errno set appropriately.
+ *
****************************************************************************/
-int fseek(FILE *stream, long int offset, int whence)
+int fseek(FAR FILE *stream, long int offset, int whence)
{
-#if CONFIG_STDIO_BUFFER_SIZE > 0
+ #if CONFIG_STDIO_BUFFER_SIZE > 0
/* Flush any valid read/write data in the buffer (also verifies stream) */
if (lib_rdflush(stream) < 0 || lib_wrflush(stream) < 0)
@@ -105,14 +119,20 @@ int fseek(FILE *stream, long int offset, int whence)
if (!stream)
{
- *get_errno_ptr() = EBADF;
+ errno = EBADF;
return ERROR;
}
#endif
+ /* On success or failure, discard any characters saved by ungetc() */
+
+#if CONFIG_NUNGET_CHARS > 0
+ stream->fs_nungotten = 0;
+#endif
+
/* Perform the fseek on the underlying file descriptor */
- return lseek(stream->fs_filedes, offset, whence) >= 0 ? OK : ERROR;
+ return lseek(stream->fs_filedes, offset, whence) == (off_t)-1 ? ERROR : OK;
}
diff --git a/nuttx/lib/lib_fsetpos.c b/nuttx/lib/lib_fsetpos.c
new file mode 100644
index 000000000..6a5fc7e9f
--- /dev/null
+++ b/nuttx/lib/lib_fsetpos.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * lib/lib_fsetpos.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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdio.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: fsetpos
+ *
+ * Description:
+ * fsetpos() function is an alternate interfaces equivalent to fseek()
+ * (with whence set to SEEK_SET). It sets the current value of the file
+ * offset to value in the location referenced by pos. On some non-UNIX
+ * systems an fpos_t object may be a complex object and fsetpos may be the
+ * only way to portably reposition a stream.
+ *
+ * Returned Value:
+ * Zero on succes; -1 on failure with errno set appropriately.
+ *
+ ****************************************************************************/
+
+int fsetpos(FILE *stream, fpos_t *pos)
+{
+#if CONFIG_DEBUG
+ if (!stream || !pos)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ return fseek(stream, (off_t)*pos, SEEK_SET);
+}
diff --git a/nuttx/lib/lib_ftell.c b/nuttx/lib/lib_ftell.c
new file mode 100644
index 000000000..3b3bee775
--- /dev/null
+++ b/nuttx/lib/lib_ftell.c
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * lib/lib_ftell.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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdio.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ftell
+ *
+ * Description:
+ * ftell() returns the current value of the file position indicator for the
+ * stream pointed to by stream.
+ *
+ * Returned Value:
+ * Zero on succes; -1 on failure with errno set appropriately.
+ *
+ ****************************************************************************/
+
+long ftell(FAR FILE *stream)
+{
+ off_t position;
+
+ /* Verify that we were provided with a stream */
+
+ if (!stream)
+ {
+ errno = EBADF;
+ return ERROR;
+ }
+
+ /* Perform the lseek to the current position. This will not move the
+ * file pointer, but will return its current setting
+ */
+
+ position = lseek(stream->fs_filedes, 0, SEEK_CUR);
+ if (position != (off_t)-1)
+ {
+ return (long)position;
+ }
+ else
+ {
+ return ERROR;
+ }
+}
+
+
diff --git a/nuttx/lib/lib_ungetc.c b/nuttx/lib/lib_ungetc.c
index 34f760aa2..9831244d8 100644
--- a/nuttx/lib/lib_ungetc.c
+++ b/nuttx/lib/lib_ungetc.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* lib_ungetc.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,15 +31,15 @@
* 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 <stdio.h>
@@ -48,45 +48,45 @@
#include <nuttx/fs.h>
#include "lib_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/**********************************************************
+/**************************************************************************
* Global Constant Data
- **********************************************************/
+ **************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/**********************************************************
+/**************************************************************************
* Private Constant Data
- **********************************************************/
+ **************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- **********************************************************/
+ **************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Functions
- **********************************************************/
+ **************************************************************************/
-/************************************************************
- * fgetc
- **********************************************************/
+/****************************************************************************
+ * Name: ungetc
+ **************************************************************************/
int ungetc(int c, FILE *stream)
{
@@ -99,7 +99,7 @@ int ungetc(int c, FILE *stream)
if ((stream && stream->fs_filedes < 0) ||
((stream->fs_oflags & O_RDOK) == 0))
{
- *get_errno_ptr() = EBADF;
+ errno = EBADF;
return EOF;
}
@@ -114,7 +114,7 @@ int ungetc(int c, FILE *stream)
else
#endif
{
- *get_errno_ptr() = ENOMEM;
+ errno = ENOMEM;
return EOF;
}
}