aboutsummaryrefslogtreecommitdiff
path: root/nuttx/libc
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/libc')
-rw-r--r--nuttx/libc/lib.csv6
-rw-r--r--nuttx/libc/misc/lib_dbg.c36
-rw-r--r--nuttx/libc/misc/lib_dumpbuffer.c8
-rw-r--r--nuttx/libc/misc/lib_init.c134
-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
12 files changed, 102 insertions, 152 deletions
diff --git a/nuttx/libc/lib.csv b/nuttx/libc/lib.csv
index 171f64e9b..29cdf39a6 100644
--- a/nuttx/libc/lib.csv
+++ b/nuttx/libc/lib.csv
@@ -16,7 +16,6 @@
"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t"
"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t"
"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..."
-"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool"
"dirname","libgen.h","","FAR char","FAR char *"
"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
@@ -59,11 +58,10 @@
"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
"labs","stdlib.h","","long int","long int"
"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int"
-"lib_lowprintf","debug.h","","int","FAR const char *","..."
-"lib_rawprintf","debug.h","","int","FAR const char *","..."
"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int"
"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
+"lowsyslog","syslog.h","","int","FAR const char *","..."
"match","","","int","const char *","const char *"
"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t"
"memchr","string.h","","FAR void","FAR const void *","int c","size_t"
@@ -154,6 +152,8 @@
"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base"
"strtoul","stdlib.h","","unsigned long","const char *","char **","int"
"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int"
+"syslog","syslog.h","","int","FAR const char *","..."
+"syslog_enable","syslog.h","defined(CONFIG_SYSLOG_ENABLE)","void","bool"
"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int"
"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *"
"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *"
diff --git a/nuttx/libc/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c
index 5605ff828..921a4e24d 100644
--- a/nuttx/libc/misc/lib_dbg.c
+++ b/nuttx/libc/misc/lib_dbg.c
@@ -50,8 +50,8 @@
/* Debug output is initially disabled */
-#ifdef CONFIG_DEBUG_ENABLE
-bool g_dbgenable;
+#ifdef CONFIG_SYSLOG_ENABLE
+bool g_syslogenable;
#endif
/****************************************************************************
@@ -59,17 +59,17 @@ bool g_dbgenable;
****************************************************************************/
/****************************************************************************
- * Name: dbg_enable
+ * Name: syslog_enable
*
* Description:
* Enable or disable debug output.
*
****************************************************************************/
-#ifdef CONFIG_DEBUG_ENABLE
-void dbg_enable(bool enable)
+#ifdef CONFIG_SYSLOG_ENABLE
+void syslog_enable(bool enable)
{
- g_dbgenable = enable;
+ g_syslogenable = enable;
}
#endif
@@ -89,13 +89,13 @@ int dbg(const char *format, ...)
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, format);
- ret = lib_rawvprintf(format, ap);
+ ret = vsyslog(format, ap);
va_end(ap);
}
@@ -108,13 +108,13 @@ int lldbg(const char *format, ...)
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, format);
- ret = lib_lowvprintf(format, ap);
+ ret = lowvsyslog(format, ap);
va_end(ap);
}
@@ -128,13 +128,13 @@ int vdbg(const char *format, ...)
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, format);
- ret = lib_rawvprintf(format, ap);
+ ret = vsyslog(format, ap);
va_end(ap);
}
@@ -147,13 +147,13 @@ int llvdbg(const char *format, ...)
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, format);
- ret = lib_lowvprintf(format, ap);
+ ret = lowvsyslog(format, ap);
va_end(ap);
}
diff --git a/nuttx/libc/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c
index 52158b220..5194560fd 100644
--- a/nuttx/libc/misc/lib_dumpbuffer.c
+++ b/nuttx/libc/misc/lib_dumpbuffer.c
@@ -51,15 +51,15 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_ARCH_LOWPUTC
-# define message(format, arg...) lib_lowprintf(format, ##arg)
+# define message(format, arg...) lowsyslog(format, ##arg)
# else
-# define message(format, arg...) lib_rawprintf(format, ##arg)
+# define message(format, arg...) syslog(format, ##arg)
# endif
#else
# ifdef CONFIG_ARCH_LOWPUTC
-# define message lib_lowprintf
+# define message lowsyslog
# else
-# define message lib_rawprintf
+# define message syslog
# endif
#endif
diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c
index 6a120f7b1..434c46505 100644
--- a/nuttx/libc/misc/lib_init.c
+++ b/nuttx/libc/misc/lib_init.c
@@ -1,7 +1,7 @@
/************************************************************
* libc/misc/lib_init.c
*
- * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -76,69 +76,35 @@ void weak_const_function lib_initialize(void)
}
#if CONFIG_NFILE_STREAMS > 0
-/* The following function is called when a new TCB is allocated. It
- * creates the streamlist instance that is stored in the TCB.
+/* The following function is called when a new task is allocated. It
+ * intializes the streamlist instance that is stored in the task group.
*/
-FAR struct streamlist *lib_alloclist(void)
+void lib_streaminit(FAR struct streamlist *list)
{
- FAR struct streamlist *list;
- list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist));
- if (list)
- {
- int i;
-
- /* Start with a reference count of one */
-
- list->sl_crefs = 1;
+ int i;
- /* Initialize the list access mutex */
+ /* Initialize the list access mutex */
- (void)sem_init(&list->sl_sem, 0, 1);
+ (void)sem_init(&list->sl_sem, 0, 1);
- /* Initialize each FILE structure */
+ /* Initialize each FILE structure */
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
- {
- /* Clear the IOB */
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ /* Clear the IOB */
- memset(&list->sl_streams[i], 0, sizeof(FILE));
+ memset(&list->sl_streams[i], 0, sizeof(FILE));
- /* Indicate not opened */
+ /* Indicate not opened */
- list->sl_streams[i].fs_filedes = -1;
+ list->sl_streams[i].fs_filedes = -1;
- /* Initialize the stream semaphore to one to support one-at-
- * a-time access to private data sets.
- */
-
- lib_sem_initialize(&list->sl_streams[i]);
- }
- }
- return list;
+ /* Initialize the stream semaphore to one to support one-at-
+ * a-time access to private data sets.
+ */
-}
-
-/* This function is called when a TCB is closed (such as with
- * pthread_create(). It increases the reference count on the stream
- * list.
- */
-
-void lib_addreflist(FAR struct streamlist *list)
-{
- if (list)
- {
- /* Increment the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- list->sl_crefs++;
- irqrestore(flags);
+ lib_sem_initialize(&list->sl_streams[i]);
}
}
@@ -149,57 +115,33 @@ void lib_addreflist(FAR struct streamlist *list)
void lib_releaselist(FAR struct streamlist *list)
{
- int crefs;
- if (list)
- {
- /* Decrement the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- crefs = --(list->sl_crefs);
- irqrestore(flags);
-
- /* If the count decrements to zero, then there is no reference
- * to the structure and it should be deallocated. Since there
- * are references, it would be an error if any task still held
- * a reference to the list's semaphore.
- */
-
- if (crefs <= 0)
- {
#if CONFIG_STDIO_BUFFER_SIZE > 0
- int i;
+ int i;
#endif
- /* Destroy the semaphore and release the filelist */
- (void)sem_destroy(&list->sl_sem);
+ DEBUGASSERT(list);
+
+ /* Destroy the semaphore and release the filelist */
- /* Release each stream in the list */
+ (void)sem_destroy(&list->sl_sem);
+
+ /* Release each stream in the list */
#if CONFIG_STDIO_BUFFER_SIZE > 0
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
- {
- /* Destroy the semaphore that protects the IO buffer */
-
- (void)sem_destroy(&list->sl_streams[i].fs_sem);
-
- /* Release the IO buffer */
- if (list->sl_streams[i].fs_bufstart)
- {
- sched_free(list->sl_streams[i].fs_bufstart);
- }
- }
-#endif
- /* Finally, release the list itself */
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ /* Destroy the semaphore that protects the IO buffer */
- sched_free(list);
- }
- }
+ (void)sem_destroy(&list->sl_streams[i].fs_sem);
+
+ /* Release the IO buffer */
+
+ if (list->sl_streams[i].fs_bufstart)
+ {
+ sched_free(list->sl_streams[i].fs_bufstart);
+ }
+ }
+#endif
}
#endif /* CONFIG_NFILE_STREAMS */
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);
}
/****************************************************************************