summaryrefslogtreecommitdiff
path: root/nuttx/lib
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-06 01:29:23 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-06 01:29:23 +0000
commita26dad80f4d004a4a0f6effedc803b3902389b39 (patch)
tree419248121e228b55362eb1b9b2b98a85e3d96c4c /nuttx/lib
parentc58518aeb7694de1e53d17f228cb84c401e82bb4 (diff)
downloadpx4-nuttx-a26dad80f4d004a4a0f6effedc803b3902389b39.tar.gz
px4-nuttx-a26dad80f4d004a4a0f6effedc803b3902389b39.tar.bz2
px4-nuttx-a26dad80f4d004a4a0f6effedc803b3902389b39.zip
fflush(NULL) returns error
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@636 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/lib')
-rw-r--r--nuttx/lib/Makefile6
-rw-r--r--nuttx/lib/lib_fflush.c170
-rw-r--r--nuttx/lib/lib_internal.h4
-rw-r--r--nuttx/lib/lib_libfflush.c195
-rw-r--r--nuttx/lib/lib_libflushall.c140
-rw-r--r--nuttx/lib/lib_libfwrite.c2
-rw-r--r--nuttx/lib/lib_wrflush.c35
7 files changed, 373 insertions, 179 deletions
diff --git a/nuttx/lib/Makefile b/nuttx/lib/Makefile
index 6e852d9d0..840ea0779 100644
--- a/nuttx/lib/Makefile
+++ b/nuttx/lib/Makefile
@@ -61,9 +61,9 @@ 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_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
+ 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
endif
diff --git a/nuttx/lib/lib_fflush.c b/nuttx/lib/lib_fflush.c
index 929597ea8..d73217437 100644
--- a/nuttx/lib/lib_fflush.c
+++ b/nuttx/lib/lib_fflush.c
@@ -41,11 +41,10 @@
* Included Files
****************************************************************************/
-#include <nuttx/config.h> /* for CONFIG_STDIO_BUFFER_SIZE */
+#include <nuttx/config.h>
#include <sys/types.h>
#include <stdio.h>
-#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
@@ -82,167 +81,10 @@
****************************************************************************/
/****************************************************************************
- * Name: fflush_internal
- *
- * Description:
- * The function fflush() forces a write of all user-space buffered data for
- * the given output or update stream via the stream's underlying write
- * function. The open status of the stream is unaffected.
- *
- * Parmeters:
- * stream - the stream to flush
- * bforce - flush must be complete.
- *
- * Return:
- * ERROR on failure, otherwise the number of bytes remaining in the buffer.
- * If bforce is set, then only the values ERROR and 0 will be returned.
- *
- ****************************************************************************/
-
-ssize_t fflush_internal(FILE *stream, boolean bforce)
-{
-#if CONFIG_STDIO_BUFFER_SIZE > 0
- const unsigned char *src;
- size_t bytes_written;
- size_t nbuffer;
-
- /* Return EBADF if the file is not opened for writing */
-
- if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0)
- {
- *get_errno_ptr() = EBADF;
- return ERROR;
- }
-
- /* Make sure that we have exclusive access to the stream */
-
- lib_take_semaphore(stream);
-
- /* Make sure tht the buffer holds valid data */
-
- if (stream->fs_bufpos != stream->fs_bufstart)
- {
- /* Make sure that the buffer holds buffered write data. We do not
- * support concurrent read/write buffer usage.
- */
-
- if (stream->fs_bufread != stream->fs_bufstart)
- {
- /* The buffer holds read data... just return zero */
-
- return 0;
- }
-
- /* How many bytes of write data are used in the buffer now */
-
- nbuffer = stream->fs_bufpos - stream->fs_bufstart;
-
- /* Try to write that amount */
-
- src = stream->fs_bufstart;
- do
- {
- /* Perform the write */
-
- bytes_written = write(stream->fs_filedes, src, nbuffer);
- if (bytes_written < 0)
- {
- lib_give_semaphore(stream);
- return ERROR;
- }
-
- /* Handle partial writes. fflush() must either return with
- * an error condition or with the data successfully flushed
- * from the buffer.
- */
-
- src += bytes_written;
- nbuffer -= bytes_written;
- }
- while (bforce && nbuffer > 0);
-
- /* Reset the buffer position to the beginning of the buffer */
-
- stream->fs_bufpos = stream->fs_bufstart;
-
- /* For the case of an incomplete write, nbuffer will be non-zero
- * It will hold the number of bytes that were not written.
- * Move the data down in the buffer to handle this (rare) case
- */
-
- while (nbuffer)
- {
- *stream->fs_bufpos++ = *src++;
- --nbuffer;
- }
- }
-
- /* Restore normal access to the stream and return the number of bytes
- * remaining in the buffer.
- */
-
- lib_give_semaphore(stream);
- return stream->fs_bufpos - stream->fs_bufstart;
-#else
- /* Return no bytes remaining in the buffer */
-
- return 0;
-#endif
-}
-
-/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
- * Name: lib_fflushall
- *
- * Description:
- * Called either (1) by the OS when a task exits, or (2) from fflush()
- * when a NULL stream argument is provided.
- *
- ****************************************************************************/
-
-int lib_flushall(FAR struct streamlist *list)
-{
- int lasterrno = OK;
- int ret;
-
- /* Make sure that there are streams associated with this thread */
-
- if (list)
- {
- int i;
-
- /* Process each stream in the thread's stream list */
-
- stream_semtake(list);
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
- {
- /* If the stream is open (i.e., assigned a non-negative file
- * descriptor), then flush all of the pending write data in the
- * stream.
- */
-
- if (list->sl_streams[i].fs_filedes >= 0)
- {
- if (fflush_internal(&list->sl_streams[i], TRUE) != 0)
- {
- lasterrno = *get_errno_ptr();
- ret = ERROR;
- }
- }
- }
- stream_semgive(list);
- }
-
- /* If any flush failed, return that last failed flush */
-
- *get_errno_ptr() = lasterrno;
- return ret;
-}
-
-/****************************************************************************
* Name: fflush
*
* Description:
@@ -259,12 +101,20 @@ int lib_flushall(FAR struct streamlist *list)
int fflush(FILE *stream)
{
+ /* Is the stream argument NULL? */
+
if (!stream)
{
+ /* Yes... then this is a request to flush all streams */
+
return lib_flushall(sched_getstreams());
}
- else if (fflush_internal(stream, TRUE) != 0)
+ else if (lib_fflush(stream, TRUE) != 0)
{
+ /* An error occurred during the flush AND/OR we were unable to flush all
+ * of the buffered write data. Return EOF on failure.
+ */
+
return EOF;
}
return OK;
diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h
index 4e3a508a8..d45d0ba03 100644
--- a/nuttx/lib/lib_internal.h
+++ b/nuttx/lib/lib_internal.h
@@ -160,9 +160,9 @@ extern ssize_t lib_fwrite(const void *ptr, size_t count, FILE *stream);
extern ssize_t lib_fread(void *ptr, size_t count, FILE *stream);
-/* Defined in lib_fflush.c */
+/* Defined in lib_libfflush.c */
-extern ssize_t fflush_internal(FILE *stream, boolean bforce);
+extern ssize_t lib_fflush(FILE *stream, boolean bforce);
/* Defined in lib_rdflush.c */
diff --git a/nuttx/lib/lib_libfflush.c b/nuttx/lib/lib_libfflush.c
new file mode 100644
index 000000000..52af91c8d
--- /dev/null
+++ b/nuttx/lib/lib_libfflush.c
@@ -0,0 +1,195 @@
+/****************************************************************************
+ * lib/lib_libfflush.c
+ *
+ * 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
+ * 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 <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lib_fflush
+ *
+ * Description:
+ * The function lib_fflush() forces a write of all user-space buffered data for
+ * the given output or update stream via the stream's underlying write
+ * function. The open status of the stream is unaffected.
+ *
+ * Parmeters:
+ * stream - the stream to flush
+ * bforce - flush must be complete.
+ *
+ * Return:
+ * ERROR on failure, otherwise the number of bytes remaining in the buffer.
+ * If bforce is set, then only the values ERROR and 0 will be returned.
+ *
+ ****************************************************************************/
+
+ssize_t lib_fflush(FILE *stream, boolean bforce)
+{
+#if CONFIG_STDIO_BUFFER_SIZE > 0
+ const unsigned char *src;
+ size_t bytes_written;
+ size_t nbuffer;
+
+ /* Return EBADF if the file is not opened for writing */
+
+ if (stream->fs_filedes < 0 || (stream->fs_oflags & O_WROK) == 0)
+ {
+ *get_errno_ptr() = EBADF;
+ return ERROR;
+ }
+
+ /* Make sure that we have exclusive access to the stream */
+
+ lib_take_semaphore(stream);
+
+ /* Make sure tht the buffer holds valid data */
+
+ if (stream->fs_bufpos != stream->fs_bufstart)
+ {
+ /* Make sure that the buffer holds buffered write data. We do not
+ * support concurrent read/write buffer usage.
+ */
+
+ if (stream->fs_bufread != stream->fs_bufstart)
+ {
+ /* The buffer holds read data... just return zero */
+
+ return 0;
+ }
+
+ /* How many bytes of write data are used in the buffer now */
+
+ nbuffer = stream->fs_bufpos - stream->fs_bufstart;
+
+ /* Try to write that amount */
+
+ src = stream->fs_bufstart;
+ do
+ {
+ /* Perform the write */
+
+ bytes_written = write(stream->fs_filedes, src, nbuffer);
+ if (bytes_written < 0)
+ {
+ lib_give_semaphore(stream);
+ return ERROR;
+ }
+
+ /* Handle partial writes. fflush() must either return with
+ * an error condition or with the data successfully flushed
+ * from the buffer.
+ */
+
+ src += bytes_written;
+ nbuffer -= bytes_written;
+ }
+ while (bforce && nbuffer > 0);
+
+ /* Reset the buffer position to the beginning of the buffer */
+
+ stream->fs_bufpos = stream->fs_bufstart;
+
+ /* For the case of an incomplete write, nbuffer will be non-zero
+ * It will hold the number of bytes that were not written.
+ * Move the data down in the buffer to handle this (rare) case
+ */
+
+ while (nbuffer)
+ {
+ *stream->fs_bufpos++ = *src++;
+ --nbuffer;
+ }
+ }
+
+ /* Restore normal access to the stream and return the number of bytes
+ * remaining in the buffer.
+ */
+
+ lib_give_semaphore(stream);
+ return stream->fs_bufpos - stream->fs_bufstart;
+#else
+ /* Return no bytes remaining in the buffer */
+
+ return 0;
+#endif
+}
+
diff --git a/nuttx/lib/lib_libflushall.c b/nuttx/lib/lib_libflushall.c
new file mode 100644
index 000000000..7ba72dc7a
--- /dev/null
+++ b/nuttx/lib/lib_libflushall.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * lib/lib_libflushall.c
+ *
+ * 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
+ * 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 <fcntl.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lib_flushall
+ *
+ * Description:
+ * Called either (1) by the OS when a task exits, or (2) from fflush()
+ * when a NULL stream argument is provided.
+ *
+ ****************************************************************************/
+
+int lib_flushall(FAR struct streamlist *list)
+{
+ int lasterrno = OK;
+ int ret;
+
+ /* Make sure that there are streams associated with this thread */
+
+ if (list)
+ {
+ int i;
+
+ /* Process each stream in the thread's stream list */
+
+ stream_semtake(list);
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ FILE *stream = &list->sl_streams[i];
+
+ /* If the stream is open (i.e., assigned a non-negative file
+ * descriptor) and opened for writing, then flush all of the pending
+ * write data in the stream.
+ */
+
+ if (stream->fs_filedes >= 0 && (stream->fs_oflags & O_WROK) != 0)
+ {
+ /* Flush the writable FILE */
+
+ if (lib_fflush(stream, TRUE) != 0)
+ {
+ /* An error occurred during the flush AND/OR we were unable
+ * to flush all of the buffered write data. Return EOF on failure.
+ */
+
+ lasterrno = *get_errno_ptr();
+ ret = ERROR;
+ }
+ }
+ }
+ stream_semgive(list);
+ }
+
+ /* If any flush failed, return that last failed flush */
+
+ *get_errno_ptr() = lasterrno;
+ return ret;
+}
diff --git a/nuttx/lib/lib_libfwrite.c b/nuttx/lib/lib_libfwrite.c
index 01bc3c285..b7f681051 100644
--- a/nuttx/lib/lib_libfwrite.c
+++ b/nuttx/lib/lib_libfwrite.c
@@ -155,7 +155,7 @@ ssize_t lib_fwrite(const void *ptr, size_t count, FILE *stream)
{
/* Flush the buffered data to the IO stream */
- int bytes_buffered = fflush_internal(stream, FALSE);
+ int bytes_buffered = lib_fflush(stream, FALSE);
if (bytes_buffered < 0)
{
goto errout_with_semaphore;
diff --git a/nuttx/lib/lib_wrflush.c b/nuttx/lib/lib_wrflush.c
index cc2f65543..73e24afec 100644
--- a/nuttx/lib/lib_wrflush.c
+++ b/nuttx/lib/lib_wrflush.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * lib/lib_wrlush.c
+ * lib/lib_wrflush.c
*
* Copyright (C) 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -90,22 +90,31 @@
*
****************************************************************************/
-/****************************************************************************
- * Name: lib_wrflush
- ****************************************************************************/
-
int lib_wrflush(FILE *stream)
{
-#if CONFIG_STDIO_BUFFER_SIZE > 0
- /* Verify that the stream is opened for writing... flush will return an
- * error if it is called for a stream that is not opened for writing.
- */
+ /* Verify that we were passed a valid (i.e., non-NULL) stream */
- if (stream && (stream->fs_oflags & O_WROK) != 0)
+#if CONFIG_STDIO_BUFFER_SIZE > 0
+ if (stream)
{
- return fflush(stream);
+ /* Verify that the stream is opened for writing... lib_fflush will
+ * return an error if it is called for a stream that is not opened for
+ * writing.
+ */
+
+ if ((stream->fs_oflags & O_WROK) == 0 ||
+ lib_fflush(stream, TRUE) == 0)
+ {
+ /* Return success if there is no buffered write data -- i.e., that
+ * the stream is not opened for writing or, if it is, that all of
+ * the buffered write data was successfully flushed.
+ */
+
+ return OK;
+ }
}
+ return ERROR;
+#else
+ return stream ? OK : ERROR;
#endif
- return OK;
}
-