aboutsummaryrefslogtreecommitdiff
path: root/nuttx/libc/stdio
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/libc/stdio')
-rw-r--r--nuttx/libc/stdio/Make.defs2
-rw-r--r--nuttx/libc/stdio/lib_fgets.c2
-rw-r--r--nuttx/libc/stdio/lib_libflushall.c2
-rw-r--r--nuttx/libc/stdio/lib_libfread.c4
-rw-r--r--nuttx/libc/stdio/lib_lowsyslog.c (renamed from nuttx/libc/stdio/lib_lowprintf.c)18
-rw-r--r--nuttx/libc/stdio/lib_printf.c4
-rw-r--r--nuttx/libc/stdio/lib_syslog.c (renamed from nuttx/libc/stdio/lib_rawprintf.c)23
-rw-r--r--nuttx/libc/stdio/lib_syslogstream.c15
8 files changed, 39 insertions, 31 deletions
diff --git a/nuttx/libc/stdio/Make.defs b/nuttx/libc/stdio/Make.defs
index 0670724da..32502f32c 100644
--- a/nuttx/libc/stdio/Make.defs
+++ b/nuttx/libc/stdio/Make.defs
@@ -37,7 +37,7 @@
# 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 \
+CSRCS += lib_fileno.c lib_printf.c lib_syslog.c lib_lowsyslog.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 \
diff --git a/nuttx/libc/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c
index 35d024ebb..87eed285d 100644
--- a/nuttx/libc/stdio/lib_fgets.c
+++ b/nuttx/libc/stdio/lib_fgets.c
@@ -150,7 +150,7 @@ char *fgets(FAR char *buf, int buflen, FILE *stream)
if (ch == '\n')
#elif defined(CONFIG_EOL_IS_CR)
if (ch == '\r')
-#else /* elif CONFIG_EOL_IS_EITHER_CRLF */
+#else /* elif defined(CONFIG_EOL_IS_EITHER_CRLF) */
if (ch == '\n' || ch == '\r')
#endif
{
diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c
index 7ac3da7e0..22baed968 100644
--- a/nuttx/libc/stdio/lib_libflushall.c
+++ b/nuttx/libc/stdio/lib_libflushall.c
@@ -1,7 +1,7 @@
/****************************************************************************
* libc/stdio/lib_libflushall.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/libc/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c
index 3e851bf17..f8cf0f40a 100644
--- a/nuttx/libc/stdio/lib_libfread.c
+++ b/nuttx/libc/stdio/lib_libfread.c
@@ -1,7 +1,7 @@
/****************************************************************************
* libc/stdio/lib_libfread.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -88,7 +88,9 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream)
{
unsigned char *dest = (unsigned char*)ptr;
ssize_t bytes_read;
+#if CONFIG_STDIO_BUFFER_SIZE > 0
int ret;
+#endif
/* Make sure that reading from this stream is allowed */
diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowsyslog.c
index f7d4ffe2f..bfe6a2cce 100644
--- a/nuttx/libc/stdio/lib_lowprintf.c
+++ b/nuttx/libc/stdio/lib_lowsyslog.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * libc/stdio/lib_lowprintf.c
+ * libc/stdio/lib_lowsyslog.c
*
* Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -38,8 +38,10 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <stdio.h>
#include <debug.h>
+
#include "lib_internal.h"
/* This interface can only be used from within the kernel */
@@ -83,12 +85,12 @@
****************************************************************************/
/****************************************************************************
- * Name: lib_lowvprintf
+ * Name: lowvsyslog
****************************************************************************/
#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG)
-int lib_lowvprintf(const char *fmt, va_list ap)
+int lowvsyslog(const char *fmt, va_list ap)
{
struct lib_outstream_s stream;
@@ -103,21 +105,21 @@ int lib_lowvprintf(const char *fmt, va_list ap)
}
/****************************************************************************
- * Name: lib_lowprintf
+ * Name: lowsyslog
****************************************************************************/
-int lib_lowprintf(const char *fmt, ...)
+int lowsyslog(const char *fmt, ...)
{
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, fmt);
- ret = lib_lowvprintf(fmt, ap);
+ ret = lowvsyslog(fmt, ap);
va_end(ap);
}
diff --git a/nuttx/libc/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c
index 0e90c7ca5..b035aa14f 100644
--- a/nuttx/libc/stdio/lib_printf.c
+++ b/nuttx/libc/stdio/lib_printf.c
@@ -93,9 +93,9 @@ int printf(const char *fmt, ...)
#if CONFIG_NFILE_STREAMS > 0
ret = vfprintf(stdout, fmt, ap);
#elif CONFIG_NFILE_DESCRIPTORS > 0
- ret = lib_rawvprintf(fmt, ap);
+ ret = vsyslog(fmt, ap);
#elif defined(CONFIG_ARCH_LOWPUTC)
- ret = lib_lowvprintf(fmt, ap);
+ ret = lowvsyslog(fmt, ap);
#else
# ifdef CONFIG_CPP_HAVE_WARNING
# warning "printf has no data sink"
diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_syslog.c
index ddbb84f94..661c3b61e 100644
--- a/nuttx/libc/stdio/lib_rawprintf.c
+++ b/nuttx/libc/stdio/lib_syslog.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * libc/stdio/lib_rawprintf.c
+ * libc/stdio/lib_syslog.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -37,8 +37,11 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#include <stdio.h>
-#include <debug.h>
+#include <syslog.h>
+
#include "lib_internal.h"
/****************************************************************************
@@ -85,10 +88,10 @@
****************************************************************************/
/****************************************************************************
- * Name: lib_rawvprintf
+ * Name: vsyslog
****************************************************************************/
-int lib_rawvprintf(const char *fmt, va_list ap)
+int vsyslog(const char *fmt, va_list ap)
{
#if defined(CONFIG_SYSLOG)
@@ -129,21 +132,21 @@ int lib_rawvprintf(const char *fmt, va_list ap)
}
/****************************************************************************
- * Name: lib_rawprintf
+ * Name: syslog
****************************************************************************/
-int lib_rawprintf(const char *fmt, ...)
+int syslog(const char *fmt, ...)
{
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, fmt);
- ret = lib_rawvprintf(fmt, ap);
+ ret = vsyslog(fmt, ap);
va_end(ap);
}
diff --git a/nuttx/libc/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c
index 5529c5de8..e29c5ca3d 100644
--- a/nuttx/libc/stdio/lib_syslogstream.c
+++ b/nuttx/libc/stdio/lib_syslogstream.c
@@ -71,22 +71,23 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch)
do
{
- /* Write the character to the supported logging device */
+ /* Write the character to the supported logging device. On failure,
+ * syslog_putc returns EOF with the errno value set;
+ */
ret = syslog_putc(ch);
- if (ret == OK)
+ if (ret != EOF)
{
this->nput++;
return;
}
- /* On failure syslog_putc will return a negated errno value. The
- * errno variable will not be set. The special value -EINTR means that
- * syslog_putc() was awakened by a signal. This is not a real error and
- * must be ignored in this context.
+ /* The special errno value -EINTR means that syslog_putc() was
+ * awakened by a signal. This is not a real error and must be
+ * ignored in this context.
*/
}
- while (ret == -EINTR);
+ while (errno == -EINTR);
}
/****************************************************************************