aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/assert.h21
-rw-r--r--nuttx/include/debug.h37
-rw-r--r--nuttx/include/nuttx/fs/fs.h90
-rw-r--r--nuttx/include/nuttx/lib.h9
-rw-r--r--nuttx/include/nuttx/net/net.h87
-rw-r--r--nuttx/include/nuttx/sched.h199
-rw-r--r--nuttx/include/nuttx/serial/serial.h76
-rw-r--r--nuttx/include/nuttx/syslog.h6
-rw-r--r--nuttx/include/nuttx/usb/cdcacm.h12
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h5
-rw-r--r--nuttx/include/syslog.h94
11 files changed, 431 insertions, 205 deletions
diff --git a/nuttx/include/assert.h b/nuttx/include/assert.h
index 31c9edf48..62ffb3a6e 100644
--- a/nuttx/include/assert.h
+++ b/nuttx/include/assert.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/assert.h
*
- * 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
@@ -100,23 +100,28 @@
****************************************************************************/
/****************************************************************************
- * Global Function Prototypes
+ * Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
#ifdef CONFIG_HAVE_FILENAME
-EXTERN void up_assert(FAR const uint8_t *filename, int linenum);
-EXTERN void up_assert_code(FAR const uint8_t *filename, int linenum,
- int errcode);
+void up_assert(FAR const uint8_t *filename, int linenum) noreturn_function;
+void up_assert_code(FAR const uint8_t *filename, int linenum, int errcode)
+ noreturn_function;
#else
-EXTERN void up_assert(void);
-EXTERN void up_assert_code(int errcode);
+void up_assert(void) noreturn_function;
+void up_assert_code(int errcode) noreturn_function;
#endif
#undef EXTERN
diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h
index aa5efd432..70ae2ee18 100644
--- a/nuttx/include/debug.h
+++ b/nuttx/include/debug.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/debug.h
*
- * 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
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
-#include <stdint.h>
+#include <syslog.h>
/****************************************************************************
* Pre-processor Definitions
@@ -104,22 +104,22 @@
#ifdef CONFIG_DEBUG
# define dbg(format, arg...) \
- lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ syslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# ifdef CONFIG_ARCH_LOWPUTC
# define lldbg(format, arg...) \
- lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# else
# define lldbg(x...)
# endif
# ifdef CONFIG_DEBUG_VERBOSE
# define vdbg(format, arg...) \
- lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ syslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# ifdef CONFIG_ARCH_LOWPUTC
# define llvdbg(format, arg...) \
- lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# else
# define llvdbg(x...)
# endif
@@ -576,29 +576,16 @@ extern "C"
{
#endif
-/* These low-level debug APIs are provided by the NuttX library. If the
- * cross-compiler's pre-processor supports a variable number of macro
- * arguments, then the macros below will map all debug statements to one
- * or the other of the following.
- */
-
-int lib_rawprintf(FAR const char *format, ...);
-
-#ifdef CONFIG_ARCH_LOWPUTC
-int lib_lowprintf(FAR const char *format, ...);
-#endif
-
/* Dump a buffer of data */
void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen);
-/* Enable or disable debug output */
-
-#ifdef CONFIG_DEBUG_ENABLE
-void dbg_enable(bool enable);
-#endif
-
-/* If the cross-compiler's pre-processor does not support variable length
+/* The system logging interfaces are pnormally accessed via the macros
+ * provided above. If the cross-compiler's C pre-processor supports a
+ * variable number of macro arguments, then those macros below will map all
+ * debug statements to the logging interfaces declared in syslog.h.
+ *
+ * If the cross-compiler's pre-processor does not support variable length
* arguments, then these additional APIs will be built.
*/
diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h
index 327bf37ca..93ca2a334 100644
--- a/nuttx/include/nuttx/fs/fs.h
+++ b/nuttx/include/nuttx/fs/fs.h
@@ -240,7 +240,6 @@ struct file
struct filelist
{
sem_t fl_sem; /* Manage access to the file list */
- int16_t fl_crefs; /* Reference count */
struct file fl_files[CONFIG_NFILE_DESCRIPTORS];
};
#endif
@@ -294,7 +293,6 @@ struct file_struct
struct streamlist
{
- int sl_crefs; /* Reference count */
sem_t sl_sem; /* For thread safety */
struct file_struct sl_streams[CONFIG_NFILE_STREAMS];
};
@@ -318,7 +316,8 @@ typedef int (*foreach_mountpoint_t)(FAR const char *mountpoint,
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -333,7 +332,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN void weak_function fs_initialize(void);
+void weak_function fs_initialize(void);
/* fs_foreachmountpoint.c ***************************************************/
/****************************************************************************
@@ -357,7 +356,7 @@ EXTERN void weak_function fs_initialize(void);
****************************************************************************/
#ifndef CONFIG_DISABLE_MOUNTPOUNT
-EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
+int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
#endif
/* fs_registerdriver.c ******************************************************/
@@ -384,9 +383,8 @@ EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
*
****************************************************************************/
-EXTERN int register_driver(const char *path,
- const struct file_operations *fops,
- mode_t mode, void *priv);
+int register_driver(FAR const char *path, FAR const struct file_operations *fops,
+ mode_t mode, FAR void *priv);
/* fs_registerblockdriver.c *************************************************/
/****************************************************************************
@@ -412,9 +410,9 @@ EXTERN int register_driver(const char *path,
*
****************************************************************************/
-EXTERN int register_blockdriver(const char *path,
- const struct block_operations *bops,
- mode_t mode, void *priv);
+int register_blockdriver(FAR const char *path,
+ FAR const struct block_operations *bops, mode_t mode,
+ FAR void *priv);
/* fs_unregisterdriver.c ****************************************************/
/****************************************************************************
@@ -425,7 +423,7 @@ EXTERN int register_blockdriver(const char *path,
*
****************************************************************************/
-EXTERN int unregister_driver(const char *path);
+int unregister_driver(const char *path);
/* fs_unregisterblockdriver.c ***********************************************/
/****************************************************************************
@@ -436,7 +434,7 @@ EXTERN int unregister_driver(const char *path);
*
****************************************************************************/
-EXTERN int unregister_blockdriver(const char *path);
+int unregister_blockdriver(const char *path);
/* fs_open.c ****************************************************************/
/****************************************************************************
@@ -447,30 +445,19 @@ EXTERN int unregister_blockdriver(const char *path);
*
****************************************************************************/
-EXTERN int inode_checkflags(FAR struct inode *inode, int oflags);
+int inode_checkflags(FAR struct inode *inode, int oflags);
/* fs_files.c ***************************************************************/
/****************************************************************************
- * Name: files_alloclist
- *
- * Description: Allocate a list of files for a new task
- *
- ****************************************************************************/
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN FAR struct filelist *files_alloclist(void);
-#endif
-
-/****************************************************************************
- * Name: files_addreflist
+ * Name: files_initlist
*
* Description:
- * Increase the reference count on a file list
+ * Initializes the list of files for a new task
*
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_addreflist(FAR struct filelist *list);
+void files_initlist(FAR struct filelist *list);
#endif
/****************************************************************************
@@ -482,7 +469,7 @@ EXTERN int files_addreflist(FAR struct filelist *list);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_releaselist(FAR struct filelist *list);
+void files_releaselist(FAR struct filelist *list);
#endif
/****************************************************************************
@@ -495,7 +482,7 @@ EXTERN int files_releaselist(FAR struct filelist *list);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2);
+int files_dup(FAR struct file *filep1, FAR struct file *filep2);
#endif
/* fs_filedup.c *************************************************************/
@@ -515,7 +502,7 @@ EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int file_dup(int fd, int minfd);
+int file_dup(int fd, int minfd);
#endif
/* fs_filedup2.c ************************************************************/
@@ -535,7 +522,7 @@ EXTERN int file_dup(int fd, int minfd);
#if CONFIG_NFILE_DESCRIPTORS > 0
#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
-EXTERN int file_dup2(int fd1, int fd2);
+int file_dup2(int fd1, int fd2);
#else
# define file_dup2(fd1, fd2) dup2(fd1, fd2)
#endif
@@ -566,8 +553,8 @@ EXTERN int file_dup2(int fd1, int fd2);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int open_blockdriver(FAR const char *pathname, int mountflags,
- FAR struct inode **ppinode);
+int open_blockdriver(FAR const char *pathname, int mountflags,
+ FAR struct inode **ppinode);
#endif
/* fs_closeblockdriver.c ****************************************************/
@@ -589,7 +576,7 @@ EXTERN int open_blockdriver(FAR const char *pathname, int mountflags,
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int close_blockdriver(FAR struct inode *inode);
+int close_blockdriver(FAR struct inode *inode);
#endif
/* fs_fdopen.c **************************************************************/
@@ -609,7 +596,7 @@ typedef struct _TCB _TCB;
#define __TCB_DEFINED__
#endif
-EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
+FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
#endif
/* lib/stdio/lib_fflush.c **************************************************/
@@ -623,7 +610,7 @@ EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
****************************************************************************/
#if CONFIG_NFILE_STREAMS > 0
-EXTERN int lib_flushall(FAR struct streamlist *list);
+int lib_flushall(FAR struct streamlist *list);
#endif
/* drivers/dev_null.c *******************************************************/
@@ -635,7 +622,7 @@ EXTERN int lib_flushall(FAR struct streamlist *list);
*
****************************************************************************/
-EXTERN void devnull_register(void);
+void devnull_register(void);
/* drivers/dev_zero.c *******************************************************/
/****************************************************************************
@@ -646,7 +633,7 @@ EXTERN void devnull_register(void);
*
****************************************************************************/
-EXTERN void devzero_register(void);
+void devzero_register(void);
/* drivers/loop.c ***********************************************************/
/****************************************************************************
@@ -658,8 +645,8 @@ EXTERN void devzero_register(void);
*
****************************************************************************/
-EXTERN int losetup(FAR const char *devname, FAR const char *filename,
- uint16_t sectsize, off_t offset, bool readonly);
+int losetup(FAR const char *devname, FAR const char *filename,
+ uint16_t sectsize, off_t offset, bool readonly);
/****************************************************************************
* Name: loteardown
@@ -669,7 +656,7 @@ EXTERN int losetup(FAR const char *devname, FAR const char *filename,
*
****************************************************************************/
-EXTERN int loteardown(FAR const char *devname);
+int loteardown(FAR const char *devname);
/* drivers/bch/bchdev_register.c ********************************************/
/****************************************************************************
@@ -681,8 +668,8 @@ EXTERN int loteardown(FAR const char *devname);
*
****************************************************************************/
-EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
- bool readonly);
+int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
+ bool readonly);
/* drivers/bch/bchdev_unregister.c ******************************************/
/****************************************************************************
@@ -694,7 +681,7 @@ EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
*
****************************************************************************/
-EXTERN int bchdev_unregister(FAR const char *chardev);
+int bchdev_unregister(FAR const char *chardev);
/* Low level, direct access. NOTE: low-level access and character driver access
* are incompatible. One and only one access method should be implemented.
@@ -710,8 +697,7 @@ EXTERN int bchdev_unregister(FAR const char *chardev);
*
****************************************************************************/
-EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly,
- FAR void **handle);
+int bchlib_setup(FAR const char *blkdev, bool readonly, FAR void **handle);
/* drivers/bch/bchlib_teardown.c ********************************************/
/****************************************************************************
@@ -723,7 +709,7 @@ EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly,
*
****************************************************************************/
-EXTERN int bchlib_teardown(FAR void *handle);
+int bchlib_teardown(FAR void *handle);
/* drivers/bch/bchlib_read.c ************************************************/
/****************************************************************************
@@ -735,8 +721,8 @@ EXTERN int bchlib_teardown(FAR void *handle);
*
****************************************************************************/
-EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
- size_t len);
+ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
+ size_t len);
/* drivers/bch/bchlib_write.c ***********************************************/
/****************************************************************************
@@ -748,8 +734,8 @@ EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
*
****************************************************************************/
-EXTERN ssize_t bchlib_write(FAR void *handle, FAR const char *buffer,
- size_t offset, size_t len);
+ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset,
+ size_t len);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h
index 220af2030..3bc581e18 100644
--- a/nuttx/include/nuttx/lib.h
+++ b/nuttx/include/nuttx/lib.h
@@ -2,7 +2,7 @@
* include/nuttx/lib.h
* Non-standard, internal APIs available in lib/.
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,11 +67,10 @@ extern "C" {
/* Functions contained in lib_init.c ****************************************/
-EXTERN void weak_function lib_initialize(void);
+void weak_function lib_initialize(void);
#if CONFIG_NFILE_STREAMS > 0
-EXTERN FAR struct streamlist *lib_alloclist(void);
-EXTERN void lib_addreflist(FAR struct streamlist *list);
-EXTERN void lib_releaselist(FAR struct streamlist *list);
+void lib_streaminit(FAR struct streamlist *list);
+void lib_releaselist(FAR struct streamlist *list);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h
index b79dda755..d23fb8796 100644
--- a/nuttx/include/nuttx/net/net.h
+++ b/nuttx/include/nuttx/net/net.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/net/net.h
*
- * Copyright (C) 2007, 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -106,7 +106,6 @@ struct socket
struct socketlist
{
sem_t sl_sem; /* Manage access to the socket list */
- int16_t sl_crefs; /* Reference count */
struct socket sl_sockets[CONFIG_NSOCKET_DESCRIPTORS];
};
#endif
@@ -117,110 +116,114 @@ struct uip_driver_s; /* Forward reference. See nuttx/net/uip/uip-arch.h */
typedef int (*netdev_callback_t)(FAR struct uip_driver_s *dev, void *arg);
/****************************************************************************
- * Public Function Prototypes
+ * Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
/* net_checksd.c *************************************************************/
/* Check if the socket descriptor is valid for the provided TCB and if it
* supports the requested access.
*/
-EXTERN int net_checksd(int fd, int oflags);
+int net_checksd(int fd, int oflags);
/* net_sockets.c *************************************************************/
/* There interfaces are called only from OS scheduling and iniialization logic
* under sched/
*/
-EXTERN void weak_function net_initialize(void);
-EXTERN FAR struct socketlist *net_alloclist(void);
-EXTERN int net_addreflist(FAR struct socketlist *list);
-EXTERN int net_releaselist(FAR struct socketlist *list);
+void weak_function net_initialize(void);
+void net_initlist(FAR struct socketlist *list);
+void net_releaselist(FAR struct socketlist *list);
/* Given a socket descriptor, return the underly NuttX-specific socket
* structure.
*/
-EXTERN FAR struct socket *sockfd_socket(int sockfd);
+FAR struct socket *sockfd_socket(int sockfd);
/* socket.c ******************************************************************/
/* socket using underlying socket structure */
-EXTERN int psock_socket(int domain, int type, int protocol,
- FAR struct socket *psock);
+int psock_socket(int domain, int type, int protocol, FAR struct socket *psock);
/* net_close.c ***************************************************************/
/* The standard close() operation redirects operations on socket descriptors
* to this function.
*/
-EXTERN int net_close(int sockfd);
+int net_close(int sockfd);
/* Performs the close operation on a socket instance */
-EXTERN int psock_close(FAR struct socket *psock);
+int psock_close(FAR struct socket *psock);
/* net_close.c ***************************************************************/
/* Performs the bind() operation on a socket instance */
-EXTERN int psock_bind(FAR struct socket *psock,
- FAR const struct sockaddr *addr, socklen_t addrlen);
+int psock_bind(FAR struct socket *psock, FAR const struct sockaddr *addr,
+ socklen_t addrlen);
/* connect.c *****************************************************************/
/* Performs the connect() operation on a socket instance */
-EXTERN int psock_connect(FAR struct socket *psock,
- FAR const struct sockaddr *addr, socklen_t addrlen);
+int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr,
+ socklen_t addrlen);
/* send.c ********************************************************************/
/* Send using underlying socket structure */
-EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
- size_t len, int flags);
+ssize_t psock_send(FAR struct socket *psock, const void *buf, size_t len,
+ int flags);
/* sendto.c ******************************************************************/
/* Sendto using underlying socket structure */
-EXTERN ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
- size_t len, int flags, FAR const struct sockaddr *to,
- socklen_t tolen);
+ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
+ size_t len, int flags, FAR const struct sockaddr *to,
+ socklen_t tolen);
/* recvfrom.c ****************************************************************/
/* recvfrom using the underlying socket structure */
-EXTERN ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf,
- size_t len, int flags,FAR struct sockaddr *from,
- FAR socklen_t *fromlen);
+ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ int flags,FAR struct sockaddr *from,
+ FAR socklen_t *fromlen);
/* recv using the underlying socket structure */
-#define psock_recv(psock,buf,len,flags) psock_recvfrom(psock,buf,len,flags,NULL,0)
+#define psock_recv(psock,buf,len,flags) \
+ psock_recvfrom(psock,buf,len,flags,NULL,0)
/* getsockopt.c **************************************************************/
/* getsockopt using the underlying socket structure */
-EXTERN int psock_getsockopt(FAR struct socket *psock, int level, int option,
- FAR void *value, FAR socklen_t *value_len);
+int psock_getsockopt(FAR struct socket *psock, int level, int option,
+ FAR void *value, FAR socklen_t *value_len);
/* setsockopt.c **************************************************************/
/* setsockopt using the underlying socket structure */
-EXTERN int psock_setsockopt(FAR struct socket *psock, int level, int option,
- FAR const void *value, socklen_t value_len);
+int psock_setsockopt(FAR struct socket *psock, int level, int option,
+ FAR const void *value, socklen_t value_len);
/* net_ioctl.c ***************************************************************/
/* The standard ioctl() operation redirects operations on socket descriptors
* to this function.
*/
-EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
+int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
/* net_poll.c ****************************************************************/
/* The standard poll() operation redirects operations on socket descriptors
@@ -229,7 +232,9 @@ EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
#ifndef CONFIG_DISABLE_POLL
struct pollfd; /* Forward reference -- see poll.h */
-EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup);
+
+int psock_poll(FAR struct socket *psock, struct pollfd *fds, bool setup);
+int net_poll(int sockfd, struct pollfd *fds, bool setup);
#endif
/* net_dup.c *****************************************************************/
@@ -237,7 +242,7 @@ EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup);
* this function
*/
-EXTERN int net_dup(int sockfd, int minsd);
+int net_dup(int sockfd, int minsd);
/* net_dup2.c ****************************************************************/
/* The standard dup2() operation redirects operations on socket descriptors to
@@ -245,7 +250,7 @@ EXTERN int net_dup(int sockfd, int minsd);
*/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int net_dup2(int sockfd1, int sockfd2);
+int net_dup2(int sockfd1, int sockfd2);
#else
# define net_dup2(sockfd1, sockfd2) dup2(sockfd1, sockfd2)
#endif
@@ -253,12 +258,12 @@ EXTERN int net_dup2(int sockfd1, int sockfd2);
/* net_clone.c ***************************************************************/
/* Performs the low level, common portion of net_dup() and net_dup2() */
-EXTERN int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
+int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
/* net_vfcntl.c **************************************************************/
/* Performs fcntl operations on socket */
-EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap);
+int net_vfcntl(int sockfd, int cmd, va_list ap);
/* netdev-register.c *********************************************************/
/* This function is called by network interface device drivers to inform the
@@ -267,23 +272,23 @@ EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap);
* addresses
*/
-EXTERN int netdev_register(FAR struct uip_driver_s *dev);
+int netdev_register(FAR struct uip_driver_s *dev);
/* netdev-unregister.c *********************************************************/
/* Unregister a network device driver. */
-EXTERN int netdev_unregister(FAR struct uip_driver_s *dev);
+int netdev_unregister(FAR struct uip_driver_s *dev);
/* net_foreach.c ************************************************************/
/* Enumerates all registered network devices */
-EXTERN int netdev_foreach(netdev_callback_t callback, void *arg);
+int netdev_foreach(netdev_callback_t callback, void *arg);
/* drivers/net/slip.c ******************************************************/
/* Instantiate a SLIP network interface. */
#ifdef CONFIG_NET_SLIP
-EXTERN int slip_initialize(int intf, const char *devname);
+int slip_initialize(int intf, const char *devname);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 1e75b5020..f8b4eb0dc 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -52,19 +52,55 @@
#include <time.h>
#include <nuttx/irq.h>
+#include <nuttx/fs/fs.h>
#include <nuttx/net/net.h>
/********************************************************************************
* Pre-processor Definitions
********************************************************************************/
+/* Configuration ****************************************************************/
+/* Task groups currently only supported for retention of child status */
-/* Task Management Definitins ***************************************************/
+#undef HAVE_TASK_GROUP
+#undef HAVE_GROUP_MEMBERS
+
+/* We need a group an group members if we are supportint the parent/child
+ * relationship.
+ */
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+# define HAVE_TASK_GROUP 1
+# define HAVE_GROUP_MEMBERS 1
+
+/* We need a group (but not members) if any other resources are shared within
+ * a task group.
+ */
+
+#else
+# if !defined(CONFIG_DISABLE_ENVIRON)
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NFILE_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NFILE_STREAMS > 0
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NSOCKET_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1
+# endif
+#endif
+
+/* In any event, we don't need group members if support for pthreads is disabled */
+
+#ifdef CONFIG_DISABLE_PTHREAD
+# undef HAVE_GROUP_MEMBERS
+#endif
+
+/* Task Management Definitions **************************************************/
/* This is the maximum number of times that a lock can be set */
#define MAX_LOCK_COUNT 127
-/* Values for the _TCB flags flag bits */
+/* Values for the _TCB flags bits */
#define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */
#define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT)
@@ -74,7 +110,11 @@
#define TCB_FLAG_NONCANCELABLE (1 << 2) /* Bit 2: Pthread is non-cancelable */
#define TCB_FLAG_CANCEL_PENDING (1 << 3) /* Bit 3: Pthread cancel is pending */
#define TCB_FLAG_ROUND_ROBIN (1 << 4) /* Bit 4: Round robin sched enabled */
-#define TCB_FLAG_NOCLDWAIT (1 << 5) /* Bit 5: Do not retain child exit status */
+#define TCB_FLAG_EXIT_PROCESSING (1 << 5) /* Bit 5: Exitting */
+
+/* Values for struct task_group tg_flags */
+
+#define GROUP_FLAG_NOCLDWAIT (1 << 0) /* Bit 0: Do not retain child exit status */
/* Values for struct child_status_s ch_flags */
@@ -143,7 +183,13 @@ union entry_u
};
typedef union entry_u entry_t;
-/* These is the types of the functions that are executed with exit() is called
+/* This is the type of the function called at task startup */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+typedef CODE void (*starthook_t)(FAR void *arg);
+#endif
+
+/* These are the types of the functions that are executed with exit() is called
* (if registered via atexit() on on_exit()).
*/
@@ -159,20 +205,7 @@ typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg);
typedef struct msgq_s msgq_t;
-/* The structure used to maintain environment variables */
-
-#ifndef CONFIG_DISABLE_ENVIRON
-struct environ_s
-{
- unsigned int ev_crefs; /* Reference count used when environment
- * is shared by threads */
- size_t ev_alloc; /* Number of bytes allocated in environment */
- char ev_env[1]; /* Environment strings */
-};
-typedef struct environ_s environ_t;
-# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1)
-#endif
-
+/* struct child_status_s *********************************************************/
/* This structure is used to maintin information about child tasks.
* pthreads work differently, they have join information. This is
* only for child tasks.
@@ -189,6 +222,7 @@ struct child_status_s
};
#endif
+/* struct dspace_s ***************************************************************/
/* This structure describes a reference counted D-Space region. This must be a
* separately allocated "break-away" structure that can be owned by a task and
* any pthreads created by the task.
@@ -214,6 +248,88 @@ struct dspace_s
};
#endif
+/* struct task_group_s ***********************************************************/
+/* All threads created by pthread_create belong in the same task group (along with
+ * the thread of the original task). struct task_group_s is a shared, "breakaway"
+ * structure referenced by each TCB.
+ *
+ * This structure should contain *all* resources shared by tasks and threads that
+ * belong to the same task group:
+ *
+ * Child exit status
+ * Environment varibles
+ * PIC data space and address environments
+ * File descriptors
+ * FILE streams
+ * Sockets
+ *
+ * Currenty, however, this implementation only applies to child exit status.
+ *
+ * Each instance of struct task_group_s is reference counted. Each instance is
+ * created with a reference count of one. The reference incremeneted when each
+ * thread joins the group and decremented when each thread exits, leaving the
+ * group. When the refernce count decrements to zero, the struc task_group_s
+ * is free.
+ */
+
+#ifdef HAVE_TASK_GROUP
+struct task_group_s
+{
+#ifdef HAVE_GROUP_MEMBERS
+ struct task_group_s *flink; /* Supports a singly linked list */
+ gid_t tg_gid; /* The ID of this task group */
+ gid_t tg_pgid; /* The ID of the parent task group */
+#endif
+ uint8_t tg_flags; /* See GROUP_FLAG_* definitions */
+
+ /* Group membership ***********************************************************/
+
+ uint8_t tg_nmembers; /* Number of members in the group */
+#ifdef HAVE_GROUP_MEMBERS
+ uint8_t tg_mxmembers; /* Number of members in allocation */
+ FAR pid_t *tg_members; /* Members of the group */
+#endif
+
+ /* Child exit status **********************************************************/
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+ FAR struct child_status_s *tg_children; /* Head of a list of child status */
+#endif
+
+ /* Environment variables ******************************************************/
+
+#ifndef CONFIG_DISABLE_ENVIRON
+ size_t tg_envsize; /* Size of environment string allocation */
+ FAR char *tg_envp; /* Allocated environment strings */
+#endif
+
+ /* PIC data space and address environments ************************************/
+ /* Logically the PIC data space belongs here (see struct dspace_s). The
+ * current logic needs review: There are differences in the away that the
+ * life of the PIC data is managed.
+ */
+
+ /* File descriptors ***********************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ struct filelist tg_filelist; /* Maps file descriptor to file */
+#endif
+
+ /* FILE streams ***************************************************************/
+
+#if CONFIG_NFILE_STREAMS > 0
+ struct streamlist tg_streamlist; /* Holds C buffered I/O info */
+#endif /* CONFIG_NFILE_STREAMS */
+
+ /* Sockets ********************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ struct socketlist tg_socketlist; /* Maps socket descriptor to socket */
+#endif
+};
+#endif
+
+/* _TCB **************************************************************************/
/* This is the task control block (TCB). Each task or thread is represented by
* a TCB. The TCB is the heart of the NuttX task-control logic.
*/
@@ -225,20 +341,33 @@ struct _TCB
FAR struct _TCB *flink; /* Doubly linked list */
FAR struct _TCB *blink;
+ /* Task Group *****************************************************************/
+
+#ifdef HAVE_TASK_GROUP
+ FAR struct task_group_s *group; /* Pointer to shared task group data */
+#endif
+
/* Task Management Fields *****************************************************/
pid_t pid; /* This is the ID of the thread */
+
#ifdef CONFIG_SCHED_HAVE_PARENT /* Support parent-child relationship */
- pid_t parent; /* This is the ID of the parent thread */
-#ifdef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */
- FAR struct child_status_s *children; /* Head of a list of child status */
-#else
+#ifndef HAVE_GROUP_MEMBERS /* Don't know pids of group members */
+ pid_t ppid; /* This is the ID of the parent thread */
+#ifndef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */
uint16_t nchildren; /* This is the number active children */
#endif
#endif
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
start_t start; /* Thread start function */
entry_t entry; /* Entry Point into the thread */
+#ifdef CONFIG_SCHED_STARTHOOK
+ starthook_t starthook; /* Task startup function */
+ FAR void *starthookarg; /* The argument passed to the function */
+#endif
+
#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT)
# if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1
atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX];
@@ -289,10 +418,6 @@ struct _TCB
uint8_t init_priority; /* Initial priority of the task */
char *argv[CONFIG_MAX_TASK_ARGS+1]; /* Name+start-up parameters */
-#ifndef CONFIG_DISABLE_ENVIRON
- FAR environ_t *envp; /* Environment variables */
-#endif
-
/* Stack-Related Fields *******************************************************/
#ifndef CONFIG_CUSTOM_STACK
@@ -344,22 +469,6 @@ struct _TCB
int pterrno; /* Current per-thread errno */
- /* File system support ********************************************************/
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
- FAR struct filelist *filelist; /* Maps file descriptor to file */
-#endif
-
-#if CONFIG_NFILE_STREAMS > 0
- FAR struct streamlist *streams; /* Holds C buffered I/O info */
-#endif
-
- /* Network socket *************************************************************/
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- FAR struct socketlist *sockets; /* Maps file descriptor to file */
-#endif
-
/* State save areas ***********************************************************/
/* The form and content of these fields are processor-specific. */
@@ -421,6 +530,12 @@ FAR struct streamlist *sched_getstreams(void);
FAR struct socketlist *sched_getsockets(void);
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+/* Setup up a start hook */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg);
+#endif
+
/* Internal vfork support.The overall sequence is:
*
* 1) User code calls vfork(). vfork() is provided in architecture-specific
diff --git a/nuttx/include/nuttx/serial/serial.h b/nuttx/include/nuttx/serial/serial.h
index 49dba3795..4ee2005ef 100644
--- a/nuttx/include/nuttx/serial/serial.h
+++ b/nuttx/include/nuttx/serial/serial.h
@@ -1,7 +1,7 @@
/************************************************************************************
* include/nuttx/serial/serial.h
*
- * Copyright (C) 2007-2008, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#ifdef CONFIG_SERIAL_TERMIOS
# include <termios.h>
#endif
+
#include <nuttx/fs/fs.h>
/************************************************************************************
@@ -193,20 +194,23 @@ struct uart_ops_s
struct uart_dev_s
{
- uint8_t open_count; /* Number of times the device has been opened */
- volatile bool xmitwaiting; /* true: User waiting for space in xmit.buffer */
- volatile bool recvwaiting; /* true: User waiting for data in recv.buffer */
- bool isconsole; /* true: This is the serial console */
- sem_t closesem; /* Locks out new open while close is in progress */
- sem_t xmitsem; /* Wakeup user waiting for space in xmit.buffer */
- sem_t recvsem; /* Wakeup user waiting for data in recv.buffer */
+ uint8_t open_count; /* Number of times the device has been opened */
+ volatile bool xmitwaiting; /* true: User waiting for space in xmit.buffer */
+ volatile bool recvwaiting; /* true: User waiting for data in recv.buffer */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ volatile bool disconnected; /* true: Removable device is not connected */
+#endif
+ bool isconsole; /* true: This is the serial console */
+ sem_t closesem; /* Locks out new open while close is in progress */
+ sem_t xmitsem; /* Wakeup user waiting for space in xmit.buffer */
+ sem_t recvsem; /* Wakeup user waiting for data in recv.buffer */
#ifndef CONFIG_DISABLE_POLL
- sem_t pollsem; /* Manages exclusive access to fds[] */
+ sem_t pollsem; /* Manages exclusive access to fds[] */
#endif
- struct uart_buffer_s xmit; /* Describes transmit buffer */
- struct uart_buffer_s recv; /* Describes receive buffer */
- FAR const struct uart_ops_s *ops; /* Arch-specific operations */
- FAR void *priv; /* Used by the arch-specific logic */
+ struct uart_buffer_s xmit; /* Describes transmit buffer */
+ struct uart_buffer_s recv; /* Describes receive buffer */
+ FAR const struct uart_ops_s *ops; /* Arch-specific operations */
+ FAR void *priv; /* Used by the arch-specific logic */
/* The following is a list if poll structures of threads waiting for
* driver events. The 'struct pollfd' reference for each open is also
@@ -226,25 +230,27 @@ struct uart_dev_s
#endif
};
+
typedef struct uart_dev_s uart_dev_t;
/************************************************************************************
* Public Data
************************************************************************************/
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
* Name: uart_register
*
* Description:
@@ -252,7 +258,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
+int uart_register(FAR const char *path, FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_xmitchars
@@ -265,7 +271,7 @@ EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
+void uart_xmitchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_receivechars
@@ -278,7 +284,7 @@ EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_recvchars(FAR uart_dev_t *dev);
+void uart_recvchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datareceived
@@ -290,7 +296,7 @@ EXTERN void uart_recvchars(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_datareceived(FAR uart_dev_t *dev);
+void uart_datareceived(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datasent
@@ -303,7 +309,31 @@ EXTERN void uart_datareceived(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_datasent(FAR uart_dev_t *dev);
+void uart_datasent(FAR uart_dev_t *dev);
+
+/************************************************************************************
+ * Name: uart_connected
+ *
+ * Description:
+ * Serial devices (like USB serial) can be removed. In that case, the "upper
+ * half" serial driver must be informed that there is no longer a valid serial
+ * channel associated with the driver.
+ *
+ * In this case, the driver will terminate all pending transfers wint ENOTCONN and
+ * will refuse all further transactions while the "lower half" is disconnected.
+ * The driver will continue to be registered, but will be in an unusable state.
+ *
+ * Conversely, the "upper half" serial driver needs to know when the serial
+ * device is reconnected so that it can resume normal operations.
+ *
+ * Assumptions/Limitations:
+ * This function may be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+void uart_connected(FAR uart_dev_t *dev, bool connected);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/syslog.h b/nuttx/include/nuttx/syslog.h
index 3c340d23a..bb3c8f493 100644
--- a/nuttx/include/nuttx/syslog.h
+++ b/nuttx/include/nuttx/syslog.h
@@ -116,10 +116,10 @@ EXTERN int syslog_initialize(void);
*
* Description:
* This is the low-level system logging interface. The debugging/syslogging
- * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is
- * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses
+ * interfaces are syslog() and lowsyslog(). The difference is that
+ * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses
* a lower level interface that works from interrupt handlers. This
- * function is a a low-level interface used to implement lib_lowprintf().
+ * function is a a low-level interface used to implement lowsyslog().
*
****************************************************************************/
diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h
index 1dca050c4..49dc4ee12 100644
--- a/nuttx/include/nuttx/usb/cdcacm.h
+++ b/nuttx/include/nuttx/usb/cdcacm.h
@@ -54,7 +54,7 @@
* Endpoint 0 max packet size. Default 64.
* CONFIG_CDCACM_EPINTIN
* The logical 7-bit address of a hardware endpoint that supports
- * interrupt IN operation. Default 2.
+ * interrupt IN operation. Default 1.
* CONFIG_CDCACM_EPINTIN_FSSIZE
* Max package size for the interrupt IN endpoint if full speed mode.
* Default 64.
@@ -63,7 +63,7 @@
* Default 64.
* CONFIG_CDCACM_EPBULKOUT
* The logical 7-bit address of a hardware endpoint that supports
- * bulk OUT operation
+ * bulk OUT operation. Default: 3
* CONFIG_CDCACM_EPBULKOUT_FSSIZE
* Max package size for the bulk OUT endpoint if full speed mode.
* Default 64.
@@ -72,7 +72,7 @@
* Default 512.
* CONFIG_CDCACM_EPBULKIN
* The logical 7-bit address of a hardware endpoint that supports
- * bulk IN operation
+ * bulk IN operation. Default: 2
* CONFIG_CDCACM_EPBULKIN_FSSIZE
* Max package size for the bulk IN endpoint if full speed mode.
* Default 64.
@@ -107,7 +107,7 @@
*/
#ifndef CONFIG_CDCACM_EPINTIN
-# define CONFIG_CDCACM_EPINTIN 2
+# define CONFIG_CDCACM_EPINTIN 1
#endif
#ifndef CONFIG_CDCACM_EPINTIN_FSSIZE
@@ -124,7 +124,7 @@
*/
#ifndef CONFIG_CDCACM_EPBULKIN
-# define CONFIG_CDCACM_EPBULKIN 3
+# define CONFIG_CDCACM_EPBULKIN 2
#endif
#ifndef CONFIG_CDCACM_EPBULKIN_FSSIZE
@@ -141,7 +141,7 @@
*/
#ifndef CONFIG_CDCACM_EPBULKOUT
-# define CONFIG_CDCACM_EPBULKOUT 4
+# define CONFIG_CDCACM_EPBULKOUT 3
#endif
#ifndef CONFIG_CDCACM_EPBULKOUT_FSSIZE
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index ab3a5f4be..860f48983 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -104,6 +104,7 @@
#define TRACE_DEVUNINIT TRACE_EVENT(TRACE_INIT_ID, 0x0002)
#define TRACE_DEVREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0003)
#define TRACE_DEVUNREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0004)
+#define TRACE_DEVINIT_USER TRACE_EVENT(TRACE_INIT_ID, 0x0005) /* First user-defined */
/* API calls (see usbdev.h) */
@@ -117,6 +118,7 @@
#define TRACE_EPCANCEL TRACE_EVENT(TRACE_EP_ID, 0x0008)
#define TRACE_EPSTALL TRACE_EVENT(TRACE_EP_ID, 0x0009)
#define TRACE_EPRESUME TRACE_EVENT(TRACE_EP_ID, 0x000a)
+#define TRACE_EPAPI_USER TRACE_EVENT(TRACE_EP_ID, 0x000b) /* First user-defined */
#define TRACE_DEVALLOCEP TRACE_EVENT(TRACE_DEV_ID, 0x0001)
#define TRACE_DEVFREEEP TRACE_EVENT(TRACE_DEV_ID, 0x0002)
@@ -124,6 +126,7 @@
#define TRACE_DEVWAKEUP TRACE_EVENT(TRACE_DEV_ID, 0x0004)
#define TRACE_DEVSELFPOWERED TRACE_EVENT(TRACE_DEV_ID, 0x0005)
#define TRACE_DEVPULLUP TRACE_EVENT(TRACE_DEV_ID, 0x0006)
+#define TRACE_DEVAPI_USER TRACE_EVENT(TRACE_DEV_ID, 0x0007) /* First user-defined */
#define TRACE_CLASSBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0001)
#define TRACE_CLASSUNBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0002)
@@ -135,6 +138,8 @@
#define TRACE_CLASSRDCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0007)
#define TRACE_CLASSWRCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0008)
+#define TRACE_CLASSAPI_USER TRACE_EVENT(TRACE_CLASS_ID, 0x0009) /* First user-defined */
+
#define TRACE_CLASSAPI(id) TRACE_EVENT(TRACE_CLASSAPI_ID, id)
#define TRACE_CLASSSTATE(id) TRACE_EVENT(TRACE_CLASSSTATE_ID, id)
diff --git a/nuttx/include/syslog.h b/nuttx/include/syslog.h
new file mode 100644
index 000000000..cfb2db97b
--- /dev/null
+++ b/nuttx/include/syslog.h
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * include/syslog.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_SYSLOG_H
+#define __INCLUDE_SYSLOG_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdarg.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#if defined(__cplusplus)
+extern "C"
+{
+#endif
+
+/* These low-level debug APIs are provided by the NuttX library. These are
+ * normally accessed via the macros in debug.h. If the cross-compiler's
+ * C pre-processor supports a variable number of macro arguments, then those
+ * macros below will map all debug statements to one or the other of the
+ * following.
+ */
+
+int syslog(FAR const char *format, ...);
+int vsyslog(const char *src, va_list ap);
+
+#ifdef CONFIG_ARCH_LOWPUTC
+int lowsyslog(FAR const char *format, ...);
+int lowvsyslog(const char *src, va_list ap);
+#endif
+
+/* Enable or disable syslog output */
+
+#ifdef CONFIG_SYSLOG_ENABLE
+void syslog_enable(bool enable);
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_SYSLOG_H */