From a5b189950ec66b46f019fa3f3de54576f30e04d9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 1 Nov 2012 15:00:26 +0000 Subject: [PATCH] Add support for ferror(), feof(), and clearerr() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5290 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/include/nuttx/fs/fs.h | 15 ++++-- nuttx/include/stdio.h | 7 ++- nuttx/lib/stdio/Make.defs | 34 ++++++++----- nuttx/lib/stdio/lib_clearerr.c | 69 ++++++++++++++++++++++++++ nuttx/lib/stdio/lib_feof.c | 77 +++++++++++++++++++++++++++++ nuttx/lib/stdio/lib_ferror.c | 90 ++++++++++++++++++++++++++++++++++ nuttx/lib/stdio/lib_libfread.c | 31 ++++++++++-- 8 files changed, 307 insertions(+), 21 deletions(-) create mode 100644 nuttx/lib/stdio/lib_clearerr.c create mode 100644 nuttx/lib/stdio/lib_feof.c create mode 100644 nuttx/lib/stdio/lib_ferror.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index d4d840243b..e14cac1e2a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3541,4 +3541,7 @@ * configs/sim/ostest: Converted to use the mconfig configuration tool. * configs/sim/cxxtest: New test that will be used to verify the uClibc++ port (eventually). - + * include/nuttx/fs/fs.h, lib/stdio/lib_libfread.c, lib_ferror.c, + lib_feof.c, and lib_clearerr.c: Add support for ferror(), feof(), + and clearerror(). ferror() support is bogus at the moment (it + is equivalent to !feof()); the others should be good. diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 81f81622f6..aab4ae4be8 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -51,6 +51,10 @@ /**************************************************************************** * Definitions ****************************************************************************/ +/* Stream flags for the fs_flags field of in struct file_struct */ + +#define __FS_FLAG_EOF (1 << 0) /* EOF detected by a read operation */ +#define __FS_FLAG_ERROR (1 << 1) /* Error detected by any operation */ /**************************************************************************** * Type Definitions @@ -270,11 +274,6 @@ struct filelist struct file_struct { int fs_filedes; /* File descriptor associated with stream */ - uint16_t fs_oflags; /* Open mode flags */ -#if CONFIG_NUNGET_CHARS > 0 - uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ - unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; -#endif #if CONFIG_STDIO_BUFFER_SIZE > 0 sem_t fs_sem; /* For thread safety */ pid_t fs_holder; /* Holder of sem */ @@ -283,6 +282,12 @@ struct file_struct FAR unsigned char *fs_bufend; /* Pointer to 1 past end of buffer */ FAR unsigned char *fs_bufpos; /* Current position in buffer */ FAR unsigned char *fs_bufread; /* Pointer to 1 past last buffered read char. */ +#endif + uint16_t fs_oflags; /* Open mode flags */ + uint8_t fs_flags; /* Stream flags */ +#if CONFIG_NUNGET_CHARS > 0 + uint8_t fs_nungotten; /* The number of characters buffered for ungetc */ + unsigned char fs_ungotten[CONFIG_NUNGET_CHARS]; #endif }; diff --git a/nuttx/include/stdio.h b/nuttx/include/stdio.h index e9218046c5..8796861a40 100644 --- a/nuttx/include/stdio.h +++ b/nuttx/include/stdio.h @@ -102,6 +102,9 @@ extern "C" { /* ANSI-like File System Interfaces */ +/* Operations on streams (FILE) */ + +EXTERN void clearerr(register FILE *stream); EXTERN int fclose(FAR FILE *stream); EXTERN int fflush(FAR FILE *stream); EXTERN int feof(FAR FILE *stream); @@ -120,6 +123,9 @@ EXTERN int fsetpos(FAR FILE *stream, FAR fpos_t *pos); EXTERN long ftell(FAR FILE *stream); EXTERN size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream); EXTERN FAR char *gets(FAR char *s); +EXTERN int ungetc(int c, FAR FILE *stream); + +/* Operations on the stdout stream, buffers, paths, and the whole printf-family */ EXTERN int printf(const char *format, ...); EXTERN int puts(FAR const char *s); @@ -130,7 +136,6 @@ EXTERN int snprintf(FAR char *buf, size_t size, const char *format, ...); EXTERN int sscanf(const char *buf, const char *fmt, ...); EXTERN void perror(FAR const char *s); -EXTERN int ungetc(int c, FAR FILE *stream); EXTERN int vprintf(FAR const char *format, va_list ap); EXTERN int vfprintf(FAR FILE *stream, const char *format, va_list ap); EXTERN int vsprintf(FAR char *buf, const char *format, va_list ap); diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs index f88a5edd9e..e4ee5e9699 100644 --- a/nuttx/lib/stdio/Make.defs +++ b/nuttx/lib/stdio/Make.defs @@ -34,27 +34,39 @@ ############################################################################ # Add the stdio C files to the build +# This first group of C files do not depend on having file descriptors or +# C streams. CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \ - lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ - lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ - lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ - lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ - lib_nulloutstream.c lib_sscanf.c + lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \ + lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \ + lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \ + lib_lowoutstream.c lib_zeroinstream.c lib_nullinstream.c \ + lib_nulloutstream.c lib_sscanf.c + +# The remaining sources files depend upon file descriptors ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) + CSRCS += lib_rawinstream.c lib_rawoutstream.c + +# And these depend upon both file descriptors and C streams + ifneq ($(CONFIG_NFILE_STREAMS),0) + CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.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_stdinstream.c lib_stdoutstream.c \ - lib_perror.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_stdinstream.c lib_stdoutstream.c \ + lib_perror.c lib_feof.c lib_ferror.c lib_clearerr.c + endif endif +# Other support that depends on specific, configured features. + ifeq ($(CONFIG_SYSLOG),y) CSRCS += lib_syslogstream.c endif diff --git a/nuttx/lib/stdio/lib_clearerr.c b/nuttx/lib/stdio/lib_clearerr.c new file mode 100644 index 0000000000..7f7ded5bb4 --- /dev/null +++ b/nuttx/lib/stdio/lib_clearerr.c @@ -0,0 +1,69 @@ +/**************************************************************************** + * lib/stdio/lib_clearerr.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: Functions + * + * Description: + * Clear any end-of-file or error conditions. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void clearerr(FILE *stream) +{ + stream->fs_flags = 0; +} +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_feof.c b/nuttx/lib/stdio/lib_feof.c new file mode 100644 index 0000000000..e44c6a3c92 --- /dev/null +++ b/nuttx/lib/stdio/lib_feof.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * lib/stdio/lib_feof.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: feof + * + * Description: + * The feof() function shall test if the currently file pointer for the + * stream is at the end of file. + * + * Returned Value: + * This function will return non-zero if the the file pointer is positioned + * at the end of file. + * + ****************************************************************************/ + +int feof(FILE *stream) +{ + /* If the end-of-file condition is encountered by any of the C-buffered + * I/O functions that perform read operations, they should set the + * __FS_FLAG_EOF in the fs_flags field of struct file_struct. + */ + + return (stream->fs_flags & __FS_FLAG_EOF) != 0; +} + +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_ferror.c b/nuttx/lib/stdio/lib_ferror.c new file mode 100644 index 0000000000..4ad7d8cfca --- /dev/null +++ b/nuttx/lib/stdio/lib_ferror.c @@ -0,0 +1,90 @@ +/**************************************************************************** + * lib/stdio/lib_ferror.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: ferror + * + * Description: + * This function will test if the last operation resulted in an eror. This + * is used to disambiguate EOF and error conditions. + * + * Return Value: + * A non-zero value is returned to indicate the error condition. + * + ****************************************************************************/ + +int ferror(FILE *stream) +{ +#if 0 + /* If an error is encountered by any of the C-buffered I/O functions, they + * should set the __FS_FLAG_ERROR in the fs_flags field of struct + * file_struct. + */ + + return (stream->fs_flags & __FS_FLAG_ERROR) != 0; +#else + /* However, nothing currenlty sets the __FS_FLAG_ERROR flag (that is a job + * for another day). The __FS_FLAG_EOF is set by operations that perform + * read operations. Since ferror() is probably only called to disambiguate + * the meaning of other functions that return EOF, to indicate either EOF or + * an error, just testing for not EOF is probably sufficient for now. + * + * This approach would not work if ferror() is called in other contexts. In + * those cases, ferror() will always report an error. + */ + + return (stream->fs_flags & __FS_FLAG_EOF) == 0; +#endif +} + +#endif /* CONFIG_NFILE_STREAMS */ + diff --git a/nuttx/lib/stdio/lib_libfread.c b/nuttx/lib/stdio/lib_libfread.c index 03b47eda66..5585acbaea 100644 --- a/nuttx/lib/stdio/lib_libfread.c +++ b/nuttx/lib/stdio/lib_libfread.c @@ -187,7 +187,10 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { - /* We are at the end of the file */ + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ goto shortread; } @@ -232,7 +235,10 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { - /* We are at the end of the file */ + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ goto shortread; } @@ -261,6 +267,11 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } else if (bytes_read == 0) { + /* We are at the end of the file. But we may already + * have buffered data. In that case, we will report + * the EOF indication later. + */ + break; } else @@ -270,12 +281,26 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) } } #endif - /* Here after a successful (but perhaps short) read */ + /* Here after a successful (but perhaps short) read */ #if CONFIG_STDIO_BUFFER_SIZE > 0 shortread: #endif bytes_read = dest - (unsigned char*)ptr; + + /* Set or clear the EOF indicator. If we get here because of a + * short read and the total number of* bytes read is zero, then + * we must be at the end-of-file. + */ + + if (bytes_read > 0) + { + stream->fs_flags &= ~__FS_FLAG_EOF; + } + else + { + stream->fs_flags |= __FS_FLAG_EOF; + } } lib_give_semaphore(stream);