aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/arch.h2
-rw-r--r--nuttx/include/nuttx/binfmt/binfmt.h8
-rw-r--r--nuttx/include/nuttx/binfmt/builtin.h156
-rw-r--r--nuttx/include/nuttx/clock.h2
-rw-r--r--nuttx/include/nuttx/fs/binfs.h83
-rw-r--r--nuttx/include/nuttx/fs/dirent.h6
-rw-r--r--nuttx/include/nuttx/fs/fs.h3
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h5
-rw-r--r--nuttx/include/nuttx/input/kbd_codec.h347
-rw-r--r--nuttx/include/nuttx/lcd/ug-2864hsweg01.h245
-rw-r--r--nuttx/include/nuttx/net/mii.h168
-rw-r--r--nuttx/include/nuttx/nx/nxfonts.h11
-rw-r--r--nuttx/include/nuttx/progmem.h4
-rw-r--r--nuttx/include/nuttx/sched.h34
-rw-r--r--nuttx/include/nuttx/usb/hid.h2
-rw-r--r--nuttx/include/nuttx/wqueue.h2
-rw-r--r--nuttx/include/pthread.h152
-rw-r--r--nuttx/include/semaphore.h10
-rw-r--r--nuttx/include/signal.h68
-rw-r--r--nuttx/include/spawn.h198
-rw-r--r--nuttx/include/stdbool.h4
-rw-r--r--nuttx/include/sys/types.h4
-rw-r--r--nuttx/include/sys/wait.h10
-rw-r--r--nuttx/include/unistd.h16
24 files changed, 1334 insertions, 206 deletions
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index 8b4b10ade..958986472 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/arch.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-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/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h
index 6df5190d2..c6c7c874a 100644
--- a/nuttx/include/nuttx/binfmt/binfmt.h
+++ b/nuttx/include/nuttx/binfmt/binfmt.h
@@ -117,6 +117,12 @@ struct binary_s
#endif
size_t mapsize; /* Size of the mapped address region (needed for munmap) */
+
+ /* Start-up information that is provided by the loader, but may be modified
+ * by the caller between load_module() and exec_module() calls.
+ */
+
+ uint8_t priority; /* Task execution priority */
size_t stacksize; /* Size of the stack in bytes (unallocated) */
};
@@ -221,7 +227,7 @@ int unload_module(FAR const struct binary_s *bin);
*
****************************************************************************/
-int exec_module(FAR const struct binary_s *bin, int priority);
+int exec_module(FAR const struct binary_s *bin);
/****************************************************************************
* Name: exec
diff --git a/nuttx/include/nuttx/binfmt/builtin.h b/nuttx/include/nuttx/binfmt/builtin.h
new file mode 100644
index 000000000..632f8944d
--- /dev/null
+++ b/nuttx/include/nuttx/binfmt/builtin.h
@@ -0,0 +1,156 @@
+/****************************************************************************
+ * include/nuttx/binfmt/builtin.h
+ *
+ * Originally by:
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * With subsequent updates, modifications, and general maintenance by:
+ *
+ * Copyright (C) 2012-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_NUTTX_BINFMT_BUILTIN_H
+#define __INCLUDE_NUTTX_BINFMT_BUILTIN_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+struct builtin_s
+{
+ const char *name; /* Invocation name and as seen under /sbin/ */
+ int priority; /* Use: SCHED_PRIORITY_DEFAULT */
+ int stacksize; /* Desired stack size */
+ main_t main; /* Entry point: main(int argc, char *argv[]) */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* The g_builtins[] array holds information about each builtin function. If
+ * support for builtin functions is enabled in the NuttX configuration, then
+ * this arrary (along with the number_builtins() function) must be provided
+ * by the application code.
+ */
+
+EXTERN const struct builtin_s g_builtins[];
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Utility Functions Provided to Applications by binfmt/libbuiltin
+ ****************************************************************************/
+/****************************************************************************
+ * Name: builtin_isavail
+ *
+ * Description:
+ * Checks for availabiliy of application registerred during compile time.
+ *
+ * Input Parameter:
+ * filename - Name of the linked-in binary to be started.
+ *
+ * Returned Value:
+ * This is an end-user function, so it follows the normal convention:
+ * Returns index of builtin application. If it is not found then it
+ * returns -1 (ERROR) and sets errno appropriately.
+ *
+ ****************************************************************************/
+
+int builtin_isavail(FAR const char *appname);
+
+/****************************************************************************
+ * Name: builtin_getname
+ *
+ * Description:
+ * Returns pointer to a name of built-in application pointed by the
+ * index.
+ *
+ * Input Parameter:
+ * index, from 0 and on ...
+ *
+ * Returned Value:
+ * Returns valid pointer pointing to the app name if index is valid.
+ * Otherwise NULL is returned.
+ *
+ ****************************************************************************/
+
+FAR const char *builtin_getname(int index);
+
+/****************************************************************************
+ * Data Set Access Functions Provided to Applications by binfmt/libbuiltin
+ ****************************************************************************/
+/****************************************************************************
+ * Name: number_builtins
+ *
+ * Description:
+ * Returns the number of builtin functions in the g_builtins[] array. If
+ * support for builtin functions is enabled in the NuttX configuration,
+ * then this function (along with g_builtins[]) must be provided by the
+ * application code.
+ *
+ * Input Parameter:
+ * None
+ *
+ * Returned Value:
+ * The number of entries in the g_builtins[] array. This function does
+ * not return failures.
+ *
+ ****************************************************************************/
+
+int number_builtins(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_BINFMT_BUILTIN_H */
+
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index 952e0e5ef..e640ecd2e 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -113,7 +113,7 @@
#define USEC2TICK(usec) (((usec)+(USEC_PER_TICK/2))/USEC_PER_TICK) /* Rounds */
#define MSEC2TICK(msec) (((msec)+(MSEC_PER_TICK/2))/MSEC_PER_TICK) /* Rounds */
#define DSEC2TICK(dsec) MSEC2TICK((dsec)*MSEC_PER_DSEC)
-#define SEC2TICK(sec) MSEC2TICK((sec)*MSEC_PER_SEC)
+#define SEC2TICK(sec) MSEC2TICK((sec)*MSEC_PER_SEC) /* Exact */
#define TICK2NSEC(tick) ((tick)*NSEC_PER_TICK) /* Exact */
#define TICK2USEC(tick) ((tick)*USEC_PER_TICK) /* Exact */
diff --git a/nuttx/include/nuttx/fs/binfs.h b/nuttx/include/nuttx/fs/binfs.h
new file mode 100644
index 000000000..d967506d8
--- /dev/null
+++ b/nuttx/include/nuttx/fs/binfs.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * include/nuttx/fs/binfs.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_NUTTX_FS_BINFS_H
+#define __INCLUDE_NUTTX_FS_BINFS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifdef CONFIG_FS_BINFS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* The "bindir" is file system that supports access to the builtin applications.
+ * It is typically mounted under /bin.
+ */
+
+EXTERN mountpt_operations;
+EXTERN const struct mountpt_operations binfs_operations;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_FS_BINFS */
+#endif /* __INCLUDE_NUTTX_FS_BINFS_H */
diff --git a/nuttx/include/nuttx/fs/dirent.h b/nuttx/include/nuttx/fs/dirent.h
index 75867c87a..f8d356850 100644
--- a/nuttx/include/nuttx/fs/dirent.h
+++ b/nuttx/include/nuttx/fs/dirent.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/fs/dirent.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
@@ -102,7 +102,7 @@ struct fs_romfsdir_s
};
#endif /* CONFIG_FS_ROMFS */
-#ifdef CONFIG_APPS_BINDIR
+#ifdef CONFIG_FS_BINFS
/* The apps/ pseudo bin/ directory. The state value is simply an index */
struct fs_binfsdir_s
@@ -179,7 +179,7 @@ struct fs_dirent_s
#ifdef CONFIG_FS_ROMFS
struct fs_romfsdir_s romfs;
#endif
-#ifdef CONFIG_APPS_BINDIR
+#ifdef CONFIG_FS_BINFS
struct fs_binfsdir_s binfs;
#endif
#ifdef CONFIG_FS_NXFFS
diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h
index 1759310bc..327bf37ca 100644
--- a/nuttx/include/nuttx/fs/fs.h
+++ b/nuttx/include/nuttx/fs/fs.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/fs/fs.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
@@ -161,6 +161,7 @@ struct mountpt_operations
*/
int (*sync)(FAR struct file *filp);
+ int (*dup)(FAR const struct file *oldp, FAR struct file *newp);
/* Directory operations */
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index 6d60c2ee9..a15de03b9 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -105,6 +105,11 @@
#define FIOC_OPTIMIZE _FIOC(0x0003) /* IN: None
* OUT: None
*/
+#define FIOC_FILENAME _FIOC(0x0004) /* IN: FAR const char ** pointer
+ * OUT: Pointer to a persistent file name
+ * (Guaranteed to persist while the file
+ * is open).
+ */
#define FIONREAD _FIOC(0x0004) /* IN: Location to return value (int *)
* OUT: Bytes readable from this fd
diff --git a/nuttx/include/nuttx/input/kbd_codec.h b/nuttx/include/nuttx/input/kbd_codec.h
new file mode 100644
index 000000000..9a7c7c8e6
--- /dev/null
+++ b/nuttx/include/nuttx/input/kbd_codec.h
@@ -0,0 +1,347 @@
+/************************************************************************************
+ * include/nuttx/input/kbd_codec.h
+ * Serialize and marshaling keyboard data and events
+ *
+ * Copyright (C) 2012 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_NUTTX_INPUT_KBD_CODEC_H
+#define __INCLUDE_NUTTX_INPUT_KBD_CODEC_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/streams.h>
+
+#ifdef CONFIG_LIB_KBDCODEC
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* These are the special keyboard commands recognized by the CODEC. */
+
+enum kbd_keycode_e
+{
+ KEYCODE_NORMAL = 0, /* Not a special keycode */
+
+ /* Delete and Backspace keycodes (in case they may be different than the
+ * ASCII BKSP and DEL values.
+ */
+
+ KEYCODE_FWDDEL, /* DELete (forward delete) */
+ KEYCODE_BACKDEL, /* Backspace (backward delete) */
+
+ /* Cursor movement */
+
+ KEYCODE_HOME, /* Home */
+ KEYCODE_END, /* End */
+ KEYCODE_LEFT, /* Left arrow */
+ KEYCODE_RIGHT, /* Right arrow */
+ KEYCODE_UP, /* Up arrow */
+ KEYCODE_DOWN, /* Down arrow */
+ KEYCODE_PAGEUP, /* Page up */
+ KEYCODE_PAGEDOWN, /* Page down */
+
+ /* Edit commands */
+
+ KEYCODE_INSERT, /* Insert */
+ KEYCODE_AGAIN, /* Again */
+ KEYCODE_UNDO, /* Undo */
+ KEYCODE_REDO, /* Redo */
+ KEYCODE_CUT, /* Cut */
+ KEYCODE_COPY, /* Copy */
+ KEYCODE_PASTE, /* Paste */
+ KEYCODE_FIND, /* Find */
+
+ /* Selection codes */
+
+ KEYCODE_ENTER, /* Enter */
+ KEYCODE_SELECT, /* Select */
+ KEYCODE_EXECUTE, /* Execute */
+
+ /* Keyboard modes */
+
+ KEYCODE_CAPSLOCK, /* Caps Lock */
+ KEYCODE_SCROLLLOCK, /* Scroll Lock */
+ KEYCODE_NUMLOCK, /* Keypad Num Lock and Clear */
+ KEYCODE_LCAPSLOCK, /* Locking Caps Lock */
+ KEYCODE_LNUMLOCK, /* Locking Num Lock */
+ KEYCODE_LSCROLLLOCK, /* Locking Scroll Lock */
+
+ /* Misc control codes */
+
+ KEYCODE_POWER, /* Power */
+ KEYCODE_HELP, /* Help */
+ KEYCODE_MENU, /* Menu */
+ KEYCODE_STOP, /* Stop */
+ KEYCODE_PAUSE, /* Pause */
+ KEYCODE_BREAK, /* Break */
+ KEYCODE_CANCEL, /* Cancel */
+ KEYCODE_PRTSCRN, /* PrintScreen */
+ KEYCODE_SYSREQ, /* SysReq/Attention */
+
+ /* Audio */
+
+ KEYCODE_MUTE, /* Mute */
+ KEYCODE_VOLUP, /* Volume Up */
+ KEYCODE_VOLDOWN, /* Volume Down */
+
+ /* Telephone */
+
+ KEYCODE_ANSWER, /* Answer (phone) */
+ KEYCODE_HANGUP, /* Hang-up (phone) */
+
+ /* Calculator */
+
+ KEYCODE_CLEAR, /* Clear */
+ KEYCODE_CLEARENTRY, /* Clear entry */
+ KEYCODE_NEGATE, /* +/- */
+
+ KEYCODE_MEMSTORE, /* Memory store */
+ KEYCODE_MEMCLEAR, /* Memory clear */
+ KEYCODE_MEMRECALL, /* Memory recall */
+ KEYCODE_MEMADD, /* Memory add */
+ KEYCODE_MEMSUB, /* Memory substract */
+ KEYCODE_MEMMUL, /* Memory multiply */
+ KEYCODE_MEMDIV, /* Memory divide */
+
+ KEYCODE_BINARY, /* Binary mode */
+ KEYCODE_OCTAL, /* Octal mode */
+ KEYCODE_DECIMAL, /* Decimal mode */
+ KEYCODE_HEXADECIMAL, /* Hexadecimal mode */
+
+ /* Languages */
+
+ KEYCODE_LANG1, /* LANG1 */
+ KEYCODE_LANG2, /* LANG2 */
+ KEYCODE_LANG3, /* LANG3 */
+ KEYCODE_LANG4, /* LANG4 */
+ KEYCODE_LANG5, /* LANG5 */
+ KEYCODE_LANG6, /* LANG6 */
+ KEYCODE_LANG7, /* LANG7 */
+ KEYCODE_LANG8, /* LANG8 */
+
+ /* Context-specific function keys */
+
+ KEYCODE_F1, /* Function key 1 */
+ KEYCODE_F2, /* Function key 2 */
+ KEYCODE_F3, /* Function key 3 */
+ KEYCODE_F4, /* Function key 4 */
+ KEYCODE_F5, /* Function key 5 */
+ KEYCODE_F6, /* Function key 6 */
+ KEYCODE_F7, /* Function key 7 */
+ KEYCODE_F8, /* Function key 8 */
+ KEYCODE_F9, /* Function key 9 */
+ KEYCODE_F10, /* Function key 10 */
+ KEYCODE_F11, /* Function key 11 */
+ KEYCODE_F12, /* Function key 12 */
+ KEYCODE_F13, /* Function key 13 */
+ KEYCODE_F14, /* Function key 14 */
+ KEYCODE_F15, /* Function key 15 */
+ KEYCODE_F16, /* Function key 16 */
+ KEYCODE_F17, /* Function key 17 */
+ KEYCODE_F18, /* Function key 18 */
+ KEYCODE_F19, /* Function key 19 */
+ KEYCODE_F20, /* Function key 20 */
+ KEYCODE_F21, /* Function key 21 */
+ KEYCODE_F22, /* Function key 22 */
+ KEYCODE_F23, /* Function key 23 */
+ KEYCODE_F24 /* Function key 24 */
+};
+
+#define FIRST_KEYCODE KEYCODE_FWDDEL
+#define LAST_KEYCODE KEYCODE_F24
+
+/* kbd_decode() return values */
+
+#define KBD_PRESS 0 /* Key press event */
+#define KBD_RELEASE 1 /* Key release event */
+#define KBD_SPECPRESS 2 /* Special key press event */
+#define KBD_SPECREL 3 /* Special key release event */
+#define KBD_ERROR EOF /* Error or end-of-file */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+struct kbd_getstate_s
+{
+ uint8_t nch; /* Number of characters in the buffer */
+ uint8_t ndx; /* Index to next character in the buffer */
+ uint8_t buf[4]; /* Buffer of ungotten data */
+};
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/****************************************************************************
+ * The following functions are intended for use by "producer", keyboard
+ * or keypad drivers to encode information into driver buffers.
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kbd_press
+ *
+ * Description:
+ * Indicates a normal key press event. Put one byte of normal keyboard
+ * data into the output stream.
+ *
+ * Input Parameters:
+ * ch - The character to be added to the output stream.
+ * stream - An instance of lib_outstream_s to do the low-level put
+ * operation.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#define kbd_press(ch, stream) (stream)->put((stream), (int)(ch))
+
+/****************************************************************************
+ * Name: kbd_release
+ *
+ * Description:
+ * Encode the release of a normal key.
+ *
+ * Input Parameters:
+ * ch - The character associated with the key that was releared.
+ * stream - An instance of lib_outstream_s to do the low-level put
+ * operation.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void kbd_release(uint8_t ch, FAR struct lib_outstream_s *stream);
+
+/****************************************************************************
+ * Name: kbd_specpress
+ *
+ * Description:
+ * Denotes a special key press event. Put one special keyboard command
+ * into the output stream.
+ *
+ * Input Parameters:
+ * keycode - The command to be added to the output stream.
+ * stream - An instance of lib_outstream_s to do the low-level put
+ * operation.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void kbd_specpress(enum kbd_keycode_e keycode,
+ FAR struct lib_outstream_s *stream);
+
+/****************************************************************************
+ * Name: kbd_specrel
+ *
+ * Description:
+ * Denotes a special key release event. Put one special keyboard
+ * command into the output stream.
+ *
+ * Input Parameters:
+ * keycode - The command to be added to the output stream.
+ * stream - An instance of lib_outstream_s to do the low-level put
+ * operation.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void kbd_specrel(enum kbd_keycode_e keycode,
+ FAR struct lib_outstream_s *stream);
+
+/****************************************************************************
+ * The following functions are intended for use by "consumer" applications
+ * to remove and decode information from the driver provided buffer.
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kbd_decode
+ *
+ * Description:
+ * Get one byte of data or special command from the driver provided input
+ * buffer.
+ *
+ * Input Parameters:
+ * stream - An instance of lib_instream_s to do the low-level get
+ * operation.
+ * pch - The location to save the returned value. This may be
+ * either a normal, character code or a special command from enum
+ * kbd_keycode_e
+ * state - A user provided buffer to support parsing. This structure
+ * should be cleared the first time that kbd_decode is called.
+ *
+ * Returned Value:
+ *
+ * KBD_PRESS - Indicates the successful receipt of normal, keyboard data.
+ * This corresponds to a keypress event. The returned value in pch is a
+ * simple byte of text or control data corresponding to the pressed key.
+ * KBD_RELEASE - Indicates a key release event. The returned value in pch
+ * is the byte of text or control data corresponding to the released key.
+ * KBD_SPECPRESS - Indicates the successful receipt of a special keyboard
+ * command. The returned value in pch is a value from enum kbd_getstate_s.
+ * KBD_SPECREL - Indicates a special key release event. The returned value
+ * in pch is a value from enum kbd_getstate_s.
+ * EOF - An error has getting the next character (reported by the stream).
+ * Normally indicates the end of file.
+ *
+ ****************************************************************************/
+
+int kbd_decode(FAR struct lib_instream_s *stream,
+ FAR struct kbd_getstate_s *state, FAR uint8_t *pch);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_LIB_KBDCODEC */
+#endif /* __INCLUDE_NUTTX_INPUT_KBD_CODEC_H */
+
diff --git a/nuttx/include/nuttx/lcd/ug-2864hsweg01.h b/nuttx/include/nuttx/lcd/ug-2864hsweg01.h
new file mode 100644
index 000000000..bbefd39be
--- /dev/null
+++ b/nuttx/include/nuttx/lcd/ug-2864hsweg01.h
@@ -0,0 +1,245 @@
+/**************************************************************************************
+ * include/nuttx/lcd/ug-2864hsweg01.h
+ * Driver for Univision UG-2864HSWEG01 OLED display (wih SSD1306 controller) in SPI
+ * mode
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References:
+ * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID:
+ * UG-2864HSWEG01, Doc No: SAS1-9046-B, Univision Technology Inc.
+ * 2. SSD1306, 128 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with
+ * Controller, Solomon Systech
+ *
+ * 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_NUTTX_UG_8264HSWEG01_H
+#define __INCLUDE_NUTTX_UG_8264HSWEG01_H
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_LCD_UG2864HSWEG01
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* Configuration **********************************************************************/
+/* UG-2864HSWEG01 Configuration Settings:
+ *
+ * CONFIG_UG2864HSWEG01_SPIMODE - Controls the SPI mode
+ * CONFIG_UG2864HSWEG01_FREQUENCY - Define to use a different bus frequency
+ * CONFIG_UG2864HSWEG01_NINTERFACES - Specifies the number of physical UG-2864HSWEG01
+ * devices that will be supported.
+ *
+ * Required LCD driver settings:
+ *
+ * CONFIG_LCD_UG28HSWEG01 - Enable UG-2864HSWEG01 support
+ * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
+ * CONFIG_LCD_MAXPOWER must be 1
+ *
+ * Option LCD driver settings:
+ * CONFIG_LCD_LANDSCAPE, CONFIG_LCD_PORTRAIT, CONFIG_LCD_RLANDSCAPE, and
+ * CONFIG_LCD_RPORTRAIT - Display orientation.
+ *
+ * Required SPI driver settings:
+ * CONFIG_SPI_CMDDATA - Include support for cmd/data selection.
+ */
+
+/* SPI Interface
+ *
+ * "The serial interface consists of serial clock SCL, serial data SI, A0 and
+ * CS . SI is shifted into an 8-bit shift register on every rising edge of
+ * SCL in the order of D7, D6, … and D0. A0 is sampled on every eighth clock
+ * and the data byte in the shift register is written to the display data RAM
+ * or command register in the same clock."
+ *
+ * MODE 3:
+ * Clock polarity: High (CPOL=1)
+ * Clock phase: Sample on trailing (rising edge) (CPHA 1)
+ */
+
+#ifndef CONFIG_UG2864HSWEG01_SPIMODE
+# define CONFIG_UG2864HSWEG01_SPIMODE SPIDEV_MODE3
+#endif
+
+/* "This module determines whether the input data is interpreted as data or
+ * command. When A0 = “H”, the inputs at D7 - D0 are interpreted as data and be
+ * written to display RAM. When A0 = “L”, the inputs at D7 - D0 are interpreted
+ * as command, they will be decoded and be written to the corresponding command
+ * registers.
+ */
+
+#ifndef CONFIG_SPI_CMDDATA
+# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration"
+#endif
+
+/* CONFIG_UG2864HSWEG01_NINTERFACES determines the number of physical interfaces
+ * that will be supported.
+ */
+
+#ifndef CONFIG_UG2864HSWEG01_NINTERFACES
+# define CONFIG_UG2864HSWEG01_NINTERFACES 1
+#endif
+
+/* Check contrast selection */
+
+#if !defined(CONFIG_LCD_MAXCONTRAST)
+# define CONFIG_LCD_MAXCONTRAST 255
+#endif
+
+#if CONFIG_LCD_MAXCONTRAST <= 0|| CONFIG_LCD_MAXCONTRAST > 255
+# error "CONFIG_LCD_MAXCONTRAST exceeds supported maximum"
+#endif
+
+#if CONFIG_LCD_MAXCONTRAST < 255
+# warning "Optimal setting of CONFIG_LCD_MAXCONTRAST is 255"
+#endif
+
+/* Check power setting */
+
+#if !defined(CONFIG_LCD_MAXPOWER)
+# define CONFIG_LCD_MAXPOWER 1
+#endif
+
+#if CONFIG_LCD_MAXPOWER != 1
+# warning "CONFIG_LCD_MAXPOWER exceeds supported maximum"
+# undef CONFIG_LCD_MAXPOWER
+# define CONFIG_LCD_MAXPOWER 1
+#endif
+
+/* Color is 1bpp monochrome with leftmost column contained in bits 0 */
+
+#ifdef CONFIG_NX_DISABLE_1BPP
+# warning "1 bit-per-pixel support needed"
+#endif
+
+/* Orientation */
+
+#if defined(CONFIG_LCD_LANDSCAPE)
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RLANDSCAPE
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_PORTRAIT)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_RLANDSCAPE
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_RLANDSCAPE)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_RPORTRAIT)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RLANDSCAPE
+#else
+# define CONFIG_LCD_LANDSCAPE 1
+# warning "Assuming landscape orientation"
+#endif
+
+/* Some important "colors" */
+
+#define UG_Y1_BLACK 0
+#define UG_Y1_WHITE 1
+
+/**************************************************************************************
+ * Public Types
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Public Data
+ **************************************************************************************/
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**************************************************************************************
+ * Public Function Prototypes
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: ug2864hsweg01_initialize
+ *
+ * Description:
+ * Initialize the UG-2864HSWEG01 video hardware. The initial state of the
+ * OLED is fully initialized, display memory cleared, and the OLED ready
+ * to use, but with the power setting at 0 (full off == sleep mode).
+ *
+ * Input Parameters:
+ *
+ * spi - A reference to the SPI driver instance.
+ * devno - A value in the range of 0 through CONFIG_UG2864HSWEG01_NINTERFACES-1.
+ * This allows support for multiple OLED devices.
+ *
+ * Returned Value:
+ *
+ * On success, this function returns a reference to the LCD object for
+ * the specified OLED. NULL is returned on any failure.
+ *
+ **************************************************************************************/
+
+struct lcd_dev_s; /* See include/nuttx/lcd/lcd.h */
+struct spi_dev_s; /* See include/nuttx/spi.h */
+FAR struct lcd_dev_s *ug2864hsweg01_initialize(FAR struct spi_dev_s *spi,
+ unsigned int devno);
+
+/************************************************************************************************
+ * Name: ug2864hsweg01_fill
+ *
+ * Description:
+ * This non-standard method can be used to clear the entire display by writing one
+ * color to the display. This is much faster than writing a series of runs.
+ *
+ * Input Parameters:
+ * priv - Reference to private driver structure
+ *
+ * Assumptions:
+ * Caller has selected the OLED section.
+ *
+ **************************************************************************************/
+
+void ug2864hsweg01_fill(FAR struct lcd_dev_s *dev, uint8_t color);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_LCD_UG2864HSWEG01 */
+#endif /* __INCLUDE_NUTTX_UG_8264HSWEG01_H */
diff --git a/nuttx/include/nuttx/net/mii.h b/nuttx/include/nuttx/net/mii.h
index 6a5fc6e89..de4dcdfd7 100644
--- a/nuttx/include/nuttx/net/mii.h
+++ b/nuttx/include/nuttx/net/mii.h
@@ -112,12 +112,12 @@
/* Luminary LM3S6918 built-in PHY: 0x07-0x0f, 0x14-0x16, 0x19-0x1f reserved */
-#define MII_LM3S_VSPECIFIC 0x10 /* Vendor-Specific */
-#define MII_LM3S_INTCS 0x11 /* Interrupt control/status */
-#define MII_LM3S_DIAGNOSTIC 0x12 /* Diagnostic */
-#define MII_LM3S_XCVRCONTROL 0x13 /* Transceiver Control */
-#define MII_LM3S_LEDCONFIG 0x17 /* LED Configuration */
-#define MII_LM3S_MDICONTROL 0x18 /* Ethernet PHY Management MDI/MDIX Control */
+#define MII_LM_VSPECIFIC 0x10 /* Vendor-Specific */
+#define MII_LM_INTCS 0x11 /* Interrupt control/status */
+#define MII_LM_DIAGNOSTIC 0x12 /* Diagnostic */
+#define MII_LM_XCVRCONTROL 0x13 /* Transceiver Control */
+#define MII_LM_LEDCONFIG 0x17 /* LED Configuration */
+#define MII_LM_MDICONTROL 0x18 /* Ethernet PHY Management MDI/MDIX Control */
/* Micrel KS8721: 0x15, 0x1b, and 0x1f */
@@ -323,79 +323,79 @@
/* LM3S6918-specific register bit settings **********************************/
/* LM3S6918 Vendor-Specific, address 0x10 */
-#define LM3S_VSPECIFIC_RXCC (1 << 0) /* Bit 0: Receive Clock Control*/
-#define LM3S_VSPECIFIC_PCSBP (1 << 1) /* Bit 1: PCS Bypass */
-#define LM3S_VSPECIFIC_RVSPOL (1 << 4) /* Bit 4: Receive Data Polarity */
-#define LM3S_VSPECIFIC_APOL (1 << 5) /* Bit 5: Auto-Polarity Disable */
-#define LM3S_VSPECIFIC_NL10 (1 << 10) /* Bit 10: Natural Loopback Mode */
-#define LM3S_VSPECIFIC_SQEI (1 << 11) /* Bit 11: SQE Inhibit Testing */
-#define LM3S_VSPECIFIC_TXHIM (1 << 12) /* Bit 12: Transmit High Impedance Mode */
-#define LM3S_VSPECIFIC_INPOL (1 << 14) /* Bit 14: Interrupt Polarity Value*/
-#define LM3S_VSPECIFIC_RPTR (1 << 15) /* Bit 15: Repeater mode*/
+#define LM_VSPECIFIC_RXCC (1 << 0) /* Bit 0: Receive Clock Control*/
+#define LM_VSPECIFIC_PCSBP (1 << 1) /* Bit 1: PCS Bypass */
+#define LM_VSPECIFIC_RVSPOL (1 << 4) /* Bit 4: Receive Data Polarity */
+#define LM_VSPECIFIC_APOL (1 << 5) /* Bit 5: Auto-Polarity Disable */
+#define LM_VSPECIFIC_NL10 (1 << 10) /* Bit 10: Natural Loopback Mode */
+#define LM_VSPECIFIC_SQEI (1 << 11) /* Bit 11: SQE Inhibit Testing */
+#define LM_VSPECIFIC_TXHIM (1 << 12) /* Bit 12: Transmit High Impedance Mode */
+#define LM_VSPECIFIC_INPOL (1 << 14) /* Bit 14: Interrupt Polarity Value*/
+#define LM_VSPECIFIC_RPTR (1 << 15) /* Bit 15: Repeater mode*/
/* LM3S6918 Interrupt Control/Status, address 0x11 */
-#define LM3S_INTCS_ANEGCOMPINT (1 << 0) /* Bit 0: Auto-Negotiation Complete Interrupt */
-#define LM3S_INTCS_RFAULTINT (1 << 1) /* Bit 1: Remote Fault Interrupt */
-#define LM3S_INTCS_LSCHGINT (1 << 2) /* Bit 2: Link Status Change Interrupt */
-#define LM3S_INTCS_LPACKINT (1 << 3) /* Bit 3: LP Acknowledge Interrupt */
-#define LM3S_INTCS_PDFINT (1 << 4) /* Bit 4: Parallel Detection Fault Interrupt */
-#define LM3S_INTCS_PRXINT (1 << 5) /* Bit 5: Page Receive Interrupt */
-#define LM3S_INTCS_RXERINT (1 << 6) /* Bit 6: Receive Error Interrupt */
-#define LM3S_INTCS_JABBERINT (1 << 7) /* Bit 7: Jabber Event Interrupt */
-#define LM3S_INTCS_ANEGCOMPIE (1 << 8) /* Bit 8: Auto-Negotiation Complete Interrupt Enable */
-#define LM3S_INTCS_RFAULTIE (1 << 9) /* Bit 9: Remote Fault Interrupt Enable */
-#define LM3S_INTCS_LSCHGIE (1 << 10) /* Bit 10: Link Status Change Interrupt Enable */
-#define LM3S_INTCS_LPACKIE (1 << 11) /* Bit 11: LP Acknowledge Interrupt Enable */
-#define LM3S_INTCS_PDFIE (1 << 12) /* Bit 12: Parallel Detection Fault Interrupt Enable */
-#define LM3S_INTCS_PRXIE (1 << 13) /* Bit 13: Page Received Interrupt Enable */
-#define LM3S_INTCS_RXERIE (1 << 14) /* Bit 14: Receive Error Interrupt Enable */
-#define LM3S_INTCS_JABBERIE (1 << 15) /* Bit 15: Jabber Interrupt Enable */
+#define LM_INTCS_ANEGCOMPINT (1 << 0) /* Bit 0: Auto-Negotiation Complete Interrupt */
+#define LM_INTCS_RFAULTINT (1 << 1) /* Bit 1: Remote Fault Interrupt */
+#define LM_INTCS_LSCHGINT (1 << 2) /* Bit 2: Link Status Change Interrupt */
+#define LM_INTCS_LPACKINT (1 << 3) /* Bit 3: LP Acknowledge Interrupt */
+#define LM_INTCS_PDFINT (1 << 4) /* Bit 4: Parallel Detection Fault Interrupt */
+#define LM_INTCS_PRXINT (1 << 5) /* Bit 5: Page Receive Interrupt */
+#define LM_INTCS_RXERINT (1 << 6) /* Bit 6: Receive Error Interrupt */
+#define LM_INTCS_JABBERINT (1 << 7) /* Bit 7: Jabber Event Interrupt */
+#define LM_INTCS_ANEGCOMPIE (1 << 8) /* Bit 8: Auto-Negotiation Complete Interrupt Enable */
+#define LM_INTCS_RFAULTIE (1 << 9) /* Bit 9: Remote Fault Interrupt Enable */
+#define LM_INTCS_LSCHGIE (1 << 10) /* Bit 10: Link Status Change Interrupt Enable */
+#define LM_INTCS_LPACKIE (1 << 11) /* Bit 11: LP Acknowledge Interrupt Enable */
+#define LM_INTCS_PDFIE (1 << 12) /* Bit 12: Parallel Detection Fault Interrupt Enable */
+#define LM_INTCS_PRXIE (1 << 13) /* Bit 13: Page Received Interrupt Enable */
+#define LM_INTCS_RXERIE (1 << 14) /* Bit 14: Receive Error Interrupt Enable */
+#define LM_INTCS_JABBERIE (1 << 15) /* Bit 15: Jabber Interrupt Enable */
/* LM3S6918 Diagnostic, address 0x12 */
-#define LM3S_DIAGNOSTIC_RX_LOCK (1 << 8) /* Bit 8: Receive PLL Lock */
-#define LM3S_DIAGNOSTIC_RXSD (1 << 9) /* Bit 9: Receive Detection */
-#define LM3S_DIAGNOSTIC_RATE (1 << 10) /* Bit 10: Rate */
-#define LM3S_DIAGNOSTIC_DPLX (1 << 11) /* Bit 11: Duplex Mode */
-#define LM3S_DIAGNOSTIC_ANEGF (1 << 12) /* Bit 12: Auto-Negotiation Failure */
+#define LM_DIAGNOSTIC_RX_LOCK (1 << 8) /* Bit 8: Receive PLL Lock */
+#define LM_DIAGNOSTIC_RXSD (1 << 9) /* Bit 9: Receive Detection */
+#define LM_DIAGNOSTIC_RATE (1 << 10) /* Bit 10: Rate */
+#define LM_DIAGNOSTIC_DPLX (1 << 11) /* Bit 11: Duplex Mode */
+#define LM_DIAGNOSTIC_ANEGF (1 << 12) /* Bit 12: Auto-Negotiation Failure */
/* LM3S6918 Transceiver Control, address 0x13 */
-#define LM3S_XCVRCONTROL_TXO_SHIFT 14 /* Bits 15-14: Transmit Amplitude Selection */
-#define LM3S_XCVRCONTROL_TXO_MASK (3 << LM3S_XCVRCONTROL_TXO_SHIFT)
-#define LM3S_XCVRCONTROL_TXO_00DB (0 << LM3S_XCVRCONTROL_TXO_SHIFT) /* Gain 0.0dB of insertion loss */
-#define LM3S_XCVRCONTROL_TXO_04DB (1 << LM3S_XCVRCONTROL_TXO_SHIFT) /* Gain 0.4dB of insertion loss */
-#define LM3S_XCVRCONTROL_TXO_08DB (2 << LM3S_XCVRCONTROL_TXO_SHIFT) /* Gain 0.8dB of insertion loss */
-#define LM3S_XCVRCONTROL_TXO_12DB (3 << LM3S_XCVRCONTROL_TXO_SHIFT) /* Gain 1.2dB of insertion loss */
+#define LM_XCVRCONTROL_TXO_SHIFT 14 /* Bits 15-14: Transmit Amplitude Selection */
+#define LM_XCVRCONTROL_TXO_MASK (3 << LM_XCVRCONTROL_TXO_SHIFT)
+#define LM_XCVRCONTROL_TXO_00DB (0 << LM_XCVRCONTROL_TXO_SHIFT) /* Gain 0.0dB of insertion loss */
+#define LM_XCVRCONTROL_TXO_04DB (1 << LM_XCVRCONTROL_TXO_SHIFT) /* Gain 0.4dB of insertion loss */
+#define LM_XCVRCONTROL_TXO_08DB (2 << LM_XCVRCONTROL_TXO_SHIFT) /* Gain 0.8dB of insertion loss */
+#define LM_XCVRCONTROL_TXO_12DB (3 << LM_XCVRCONTROL_TXO_SHIFT) /* Gain 1.2dB of insertion loss */
/* LM3S6918 LED Configuration, address 0x17 */
-#define LM3S_LEDCONFIG_LED0_SHIFT (0) /* Bits 3-0: LED0 Source */
-#define LM3S_LEDCONFIG_LED0_MASK (0x0f << LM3S_LEDCONFIG_LED0_SHIFT)
-#define LM3S_LEDCONFIG_LED0_LINKOK (0 << LM3S_LEDCONFIG_LED0_SHIFT) /* Link OK */
-#define LM3S_LEDCONFIG_LED0_RXTX (1 << LM3S_LEDCONFIG_LED0_SHIFT) /* RX or TX activity */
-#define LM3S_LEDCONFIG_LED0_100BASET (5 << LM3S_LEDCONFIG_LED0_SHIFT) /* 100BASE-TX mode */
-#define LM3S_LEDCONFIG_LED0_10BASET (6 << LM3S_LEDCONFIG_LED0_SHIFT) /* 10BASE-T mode */
-#define LM3S_LEDCONFIG_LED0_FDUPLEX (7 << LM3S_LEDCONFIG_LED0_SHIFT) /* Full duplex */
-#define LM3S_LEDCONFIG_LED0_OKRXTX (8 << LM3S_LEDCONFIG_LED0_SHIFT) /* Full duplex */
-#define LM3S_LEDCONFIG_LED1_SHIFT (4) /* Bits 7-4: LED1 Source */
-#define LM3S_LEDCONFIG_LED1_MASK (0x0f << LM3S_LEDCONFIG_LED1_SHIFT)
-#define LM3S_LEDCONFIG_LED1_LINKOK (0 << LM3S_LEDCONFIG_LED1_SHIFT) /* Link OK */
-#define LM3S_LEDCONFIG_LED1_RXTX (1 << LM3S_LEDCONFIG_LED1_SHIFT) /* RX or TX activity */
-#define LM3S_LEDCONFIG_LED1_100BASET (5 << LM3S_LEDCONFIG_LED1_SHIFT) /* 100BASE-TX mode */
-#define LM3S_LEDCONFIG_LED1_10BASET (6 << LM3S_LEDCONFIG_LED1_SHIFT) /* 10BASE-T mode */
-#define LM3S_LEDCONFIG_LED1_FDUPLEX (7 << LM3S_LEDCONFIG_LED1_SHIFT) /* Full duplex */
-#define LM3S_LEDCONFIG_LED1_OKRXTX (8 << LM3S_LEDCONFIG_LED1_SHIFT) /* Full duplex */
+#define LM_LEDCONFIG_LED0_SHIFT (0) /* Bits 3-0: LED0 Source */
+#define LM_LEDCONFIG_LED0_MASK (0x0f << LM_LEDCONFIG_LED0_SHIFT)
+#define LM_LEDCONFIG_LED0_LINKOK (0 << LM_LEDCONFIG_LED0_SHIFT) /* Link OK */
+#define LM_LEDCONFIG_LED0_RXTX (1 << LM_LEDCONFIG_LED0_SHIFT) /* RX or TX activity */
+#define LM_LEDCONFIG_LED0_100BASET (5 << LM_LEDCONFIG_LED0_SHIFT) /* 100BASE-TX mode */
+#define LM_LEDCONFIG_LED0_10BASET (6 << LM_LEDCONFIG_LED0_SHIFT) /* 10BASE-T mode */
+#define LM_LEDCONFIG_LED0_FDUPLEX (7 << LM_LEDCONFIG_LED0_SHIFT) /* Full duplex */
+#define LM_LEDCONFIG_LED0_OKRXTX (8 << LM_LEDCONFIG_LED0_SHIFT) /* Full duplex */
+#define LM_LEDCONFIG_LED1_SHIFT (4) /* Bits 7-4: LED1 Source */
+#define LM_LEDCONFIG_LED1_MASK (0x0f << LM_LEDCONFIG_LED1_SHIFT)
+#define LM_LEDCONFIG_LED1_LINKOK (0 << LM_LEDCONFIG_LED1_SHIFT) /* Link OK */
+#define LM_LEDCONFIG_LED1_RXTX (1 << LM_LEDCONFIG_LED1_SHIFT) /* RX or TX activity */
+#define LM_LEDCONFIG_LED1_100BASET (5 << LM_LEDCONFIG_LED1_SHIFT) /* 100BASE-TX mode */
+#define LM_LEDCONFIG_LED1_10BASET (6 << LM_LEDCONFIG_LED1_SHIFT) /* 10BASE-T mode */
+#define LM_LEDCONFIG_LED1_FDUPLEX (7 << LM_LEDCONFIG_LED1_SHIFT) /* Full duplex */
+#define LM_LEDCONFIG_LED1_OKRXTX (8 << LM_LEDCONFIG_LED1_SHIFT) /* Full duplex */
/* LM3S6918 MDI/MDIX Control, address 0x18 */
-#define LM3S_MDICONTROL_MDIXSD_SHIFT (0) /* Bits 3-0: Auto-Switching Seed */
-#define LM3S_MDICONTROL_MDIXSD_MASK (0x0f << LM3S_MDICONTROL_MDIXSD_SHIFT)
-#define LM3S_MDICONTROL_MDIXCM (1 << 4) /* Bit 4: Auto-Switching Complete */
-#define LM3S_MDICONTROL_MDIX (1 << 5) /* Bit 5: Auto-Switching Configuration */
-#define LM3S_MDICONTROL_AUTOSW (1 << 6) /* Bit 6: Auto-Switching Enable */
-#define LM3S_MDICONTROL_PDMODE (1 << 7) /* Bit 7: Parallel Detection Mode */
+#define LM_MDICONTROL_MDIXSD_SHIFT (0) /* Bits 3-0: Auto-Switching Seed */
+#define LM_MDICONTROL_MDIXSD_MASK (0x0f << LM_MDICONTROL_MDIXSD_SHIFT)
+#define LM_MDICONTROL_MDIXCM (1 << 4) /* Bit 4: Auto-Switching Complete */
+#define LM_MDICONTROL_MDIX (1 << 5) /* Bit 5: Auto-Switching Configuration */
+#define LM_MDICONTROL_AUTOSW (1 << 6) /* Bit 6: Auto-Switching Enable */
+#define LM_MDICONTROL_PDMODE (1 << 7) /* Bit 7: Parallel Detection Mode */
/* KS8921-specific register bit settings ************************************/
/* KS8921 MII Control register bit definitions (not in 802.3) */
@@ -430,26 +430,26 @@
/* KS8921 10BASE-TX PHY control register */
-#define KS8721_10BTCR_BIT0 (1 << 0) /* Bit 0: xxx */
-#define KS8721_10BTCR_BIT1 (1 << 1) /* Bit 1: xxx */
-#define KS8721_10BTCR_MODE_SHIFT (2) /* Bits 2-4: Operation Mode Indication */
-#define KS8721_10BTCR_MODE_MASK (7 << KS8721_10BTCR_MODE_SHIFT)
-# define KS8721_10BTCR_MODE_ANEG (0 << KS8721_10BTCR_MODE_SHIFT) /* Still in auto-negotiation */
-# define KS8721_10BTCR_MODE_10BTHD (1 << KS8721_10BTCR_MODE_SHIFT) /* 10BASE-T half-duplex */
-# define KS8721_10BTCR_MODE_100BTHD (2 << KS8721_10BTCR_MODE_SHIFT) /* 100BASE_t half-duplex */
-# define KS8721_10BTCR_MODE_DEFAULT (3 << KS8721_10BTCR_MODE_SHIFT) /* Default */
-# define KS8721_10BTCR_MODE_10BTFD (5 << KS8721_10BTCR_MODE_SHIFT) /* 10BASE-T full duplex */
-# define KS8721_10BTCR_MODE_100BTFD (6 << KS8721_10BTCR_MODE_SHIFT) /* 100BASE-T full duplex */
-# define KS8721_10BTCR_MODE_ISOLATE (7 << KS8721_10BTCR_MODE_SHIFT) /* PHY/MII isolate */
-#define KS8721_10BTCR_ISOLATE (1 << 5) /* Bit 5: PHY isolate */
-#define KS8721_10BTCR_PAUSE (1 << 6) /* Bit 6: Enable pause */
-#define KS8721_10BTCR_ANEGCOMP (1 << 7) /* Bit 7: Auto-negotiation complete */
-#define KS8721_10BTCR_JABBERE (1 << 8) /* Bit 8: Enable Jabber */
-#define KS8721_10BTCR_INTLVL (1 << 9) /* Bit 9: Interrupt level */
-#define KS8721_10BTCR_POWER (1 << 10) /* Bit 10: Power saving */
-#define KS8721_10BTCR_FORCE (1 << 11) /* Bit 11: Force link */
-#define KS8721_10BTCR_ENERGY (1 << 12) /* Bit 12: Energy detect */
-#define KS8721_10BTCR_PAIRSWAPD (1 << 13) /* Bit 13: Pairswap disable */
+#define KS8721_10BTCR_BIT0 (1 << 0) /* Bit 0: xxx */
+#define KS8721_10BTCR_BIT1 (1 << 1) /* Bit 1: xxx */
+#define KS8721_10BTCR_MODE_SHIFT (2) /* Bits 2-4: Operation Mode Indication */
+#define KS8721_10BTCR_MODE_MASK (7 << KS8721_10BTCR_MODE_SHIFT)
+# define KS8721_10BTCR_MODE_ANEG (0 << KS8721_10BTCR_MODE_SHIFT) /* Still in auto-negotiation */
+# define KS8721_10BTCR_MODE_10BTHD (1 << KS8721_10BTCR_MODE_SHIFT) /* 10BASE-T half-duplex */
+# define KS8721_10BTCR_MODE_100BTHD (2 << KS8721_10BTCR_MODE_SHIFT) /* 100BASE_t half-duplex */
+# define KS8721_10BTCR_MODE_DEFAULT (3 << KS8721_10BTCR_MODE_SHIFT) /* Default */
+# define KS8721_10BTCR_MODE_10BTFD (5 << KS8721_10BTCR_MODE_SHIFT) /* 10BASE-T full duplex */
+# define KS8721_10BTCR_MODE_100BTFD (6 << KS8721_10BTCR_MODE_SHIFT) /* 100BASE-T full duplex */
+# define KS8721_10BTCR_MODE_ISOLATE (7 << KS8721_10BTCR_MODE_SHIFT) /* PHY/MII isolate */
+#define KS8721_10BTCR_ISOLATE (1 << 5) /* Bit 5: PHY isolate */
+#define KS8721_10BTCR_PAUSE (1 << 6) /* Bit 6: Enable pause */
+#define KS8721_10BTCR_ANEGCOMP (1 << 7) /* Bit 7: Auto-negotiation complete */
+#define KS8721_10BTCR_JABBERE (1 << 8) /* Bit 8: Enable Jabber */
+#define KS8721_10BTCR_INTLVL (1 << 9) /* Bit 9: Interrupt level */
+#define KS8721_10BTCR_POWER (1 << 10) /* Bit 10: Power saving */
+#define KS8721_10BTCR_FORCE (1 << 11) /* Bit 11: Force link */
+#define KS8721_10BTCR_ENERGY (1 << 12) /* Bit 12: Energy detect */
+#define KS8721_10BTCR_PAIRSWAPD (1 << 13) /* Bit 13: Pairswap disable */
/****************************************************************************
* Type Definitions
diff --git a/nuttx/include/nuttx/nx/nxfonts.h b/nuttx/include/nuttx/nx/nxfonts.h
index f1aecb9e5..91bce0036 100644
--- a/nuttx/include/nuttx/nx/nxfonts.h
+++ b/nuttx/include/nuttx/nx/nxfonts.h
@@ -113,6 +113,11 @@
#elif defined(CONFIG_NXFONT_SERIF38X49B)
# define NXFONT_DEFAULT FONTID_SERIF38X49B
+/* Mono-space fonts */
+
+#elif defined(CONFIG_NXFONT_MONO5X8)
+# define NXFONT_DEFAULT FONTID_MONO5X8
+
#endif
/****************************************************************************
@@ -125,6 +130,12 @@ enum nx_fontid_e
{
FONTID_DEFAULT = 0 /* The default font */
+/* Monospace fonts */
+
+#ifdef CONFIG_NXFONT_MONO5X8
+ , FONTID_MONO5X8 = 18 /* The 5x8 monospace font */
+#endif
+
/* Sans Serif fonts */
#ifdef CONFIG_NXFONT_SANS17X22
diff --git a/nuttx/include/nuttx/progmem.h b/nuttx/include/nuttx/progmem.h
index ac5a65940..2da59eab1 100644
--- a/nuttx/include/nuttx/progmem.h
+++ b/nuttx/include/nuttx/progmem.h
@@ -99,7 +99,7 @@ uint16_t up_progmem_pagesize(uint16_t page);
* Address to page conversion
*
* Input Parameters:
- * addr - Address without flash offet (aligned to page0)
+ * addr - Address with of without flash offset (absolute or aligned to page0)
*
* Returned Value:
* Page or negative value on error. The following errors are reported
@@ -165,7 +165,7 @@ int up_progmem_ispageerased(uint16_t page);
* the address be aligned inside the page boundaries.
*
* Input Parameters:
- * addr - Address without flash offet (aligned to page0)
+ * addr - Address with or without flash offset (absolute or aligned to page0)
* buf - Pointer to buffer
* count - Number of bytes to write *
*
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 6eaba6e9c..b2ec1cee4 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -1,7 +1,7 @@
/********************************************************************************
* include/nuttx/sched.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -202,6 +202,10 @@ struct _TCB
/* Task Management Fields *****************************************************/
pid_t pid; /* This is the ID of the thread */
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ pid_t parent; /* This is the ID of the parent thread */
+ uint16_t nchildren; /* This is the number active children */
+#endif
start_t start; /* Thread start function */
entry_t entry; /* Entry Point into the thread */
@@ -223,7 +227,7 @@ struct _TCB
# endif
#endif
-#ifdef CONFIG_SCHED_WAITPID
+#if defined(CONFIG_SCHED_WAITPID) && !defined(CONFIG_SCHED_HAVE_PARENT)
sem_t exitsem; /* Support for waitpid */
int *stat_loc; /* Location to return exit status */
#endif
@@ -382,6 +386,32 @@ EXTERN FAR struct streamlist *sched_getstreams(void);
EXTERN FAR struct socketlist *sched_getsockets(void);
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+/* Internal vfork support.The overall sequence is:
+ *
+ * 1) User code calls vfork(). vfork() is provided in architecture-specific
+ * code.
+ * 2) vfork()and calls task_vforksetup().
+ * 3) task_vforksetup() allocates and configures the child task's TCB. This
+ * consists of:
+ * - Allocation of the child task's TCB.
+ * - Initialization of file descriptors and streams
+ * - Configuration of environment variables
+ * - Setup the intput parameters for the task.
+ * - Initialization of the TCB (including call to up_initial_state()
+ * 4) vfork() provides any additional operating context. vfork must:
+ * - Allocate and initialize the stack
+ * - Initialize special values in any CPU registers that were not
+ * already configured by up_initial_state()
+ * 5) vfork() then calls task_vforkstart()
+ * 6) task_vforkstart() then executes the child thread.
+ *
+ * task_vforkabort() may be called if an error occurs between steps 3 and 6.
+ */
+
+FAR _TCB *task_vforksetup(start_t retaddr);
+pid_t task_vforkstart(FAR _TCB *child);
+void task_vforkabort(FAR _TCB *child, int errcode);
+
/* sched_foreach will enumerate over each task and provide the
* TCB of each task to a user callback functions. Interrupts
* will be disabled throughout this enumeration!
diff --git a/nuttx/include/nuttx/usb/hid.h b/nuttx/include/nuttx/usb/hid.h
index 5b83f08fc..877203a9c 100644
--- a/nuttx/include/nuttx/usb/hid.h
+++ b/nuttx/include/nuttx/usb/hid.h
@@ -619,7 +619,7 @@
#define USBHID_KBDUSE_RCTRL 0xe4 /* Keyboard RightControl */
#define USBHID_KBDUSE_RSHIFT 0xe5 /* Keyboard RightShift */
#define USBHID_KBDUSE_RALT 0xe6 /* Keyboard RightAlt */
-#define USBHID_KBDUSE_RGUI 0xe7 /* Keyboard Right GUI*/
+#define USBHID_KBDUSE_RGUI 0xe7 /* Keyboard Right GUI */
#define USBHID_KBDUSE_MAX 0xe7
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index c509bf197..d56901d89 100644
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -68,7 +68,7 @@
* CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
* thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
* CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
- * the worker thread. Default: 4
+ * the worker thread. Default: 17
*
* CONFIG_SCHED_LPWORK. If CONFIG_SCHED_WORKQUEUE is defined, then a single
* work queue is created by default. If CONFIG_SCHED_LPWORK is also defined
diff --git a/nuttx/include/pthread.h b/nuttx/include/pthread.h
index 5a08f13b6..a98b9aaaa 100644
--- a/nuttx/include/pthread.h
+++ b/nuttx/include/pthread.h
@@ -41,15 +41,17 @@
********************************************************************************/
#include <nuttx/config.h> /* Default settings */
-#include <nuttx/compiler.h> /* Compiler settings */
+#include <nuttx/compiler.h> /* Compiler settings, noreturn_function */
#include <sys/types.h> /* Needed for general types */
+#include <sys/prctl.h> /* Needed by pthread_[set|get]name_np */
+
#include <stdint.h> /* C99 fixed width integer types */
#include <stdbool.h> /* C99 boolean types */
+#include <unistd.h> /* For getpid */
#include <semaphore.h> /* Needed for sem_t */
#include <signal.h> /* Needed for sigset_t */
#include <time.h> /* Needed for struct timespec */
-#include <nuttx/compiler.h> /* For noreturn_function */
/********************************************************************************
* Compilation Switches
@@ -58,10 +60,11 @@
/* Standard POSIX switches */
#ifndef _POSIX_THREADS
-#define _POSIX_THREADS
+# define _POSIX_THREADS
#endif
+
#ifndef _POSIX_THREAD_ATTR_STACKSIZE
-#define _POSIX_THREAD_ATTR_STACKSIZE
+# define _POSIX_THREAD_ATTR_STACKSIZE
#endif
/********************************************************************************
@@ -153,10 +156,8 @@
********************************************************************************/
#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/* pthread-specific types */
@@ -245,28 +246,29 @@ struct sched_param; /* Defined in sched.h */
* the individual attributes used by a given implementation.
*/
-EXTERN int pthread_attr_init(FAR pthread_attr_t *attr);
+int pthread_attr_init(FAR pthread_attr_t *attr);
/* An attributes object can be deleted when it is no longer needed. */
-EXTERN int pthread_attr_destroy(pthread_attr_t *attr);
+int pthread_attr_destroy(pthread_attr_t *attr);
/* Set or obtain the default scheduling algorithm */
-EXTERN int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy);
-EXTERN int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy);
-EXTERN int pthread_attr_setschedparam(FAR pthread_attr_t *attr,
- FAR const struct sched_param *param);
-EXTERN int pthread_attr_getschedparam(FAR pthread_attr_t *attr,
- FAR struct sched_param *param);
-EXTERN int pthread_attr_setinheritsched(FAR pthread_attr_t *attr, int inheritsched);
-EXTERN int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr,
- FAR int *inheritsched);
+int pthread_attr_setschedpolicy(FAR pthread_attr_t *attr, int policy);
+int pthread_attr_getschedpolicy(FAR pthread_attr_t *attr, int *policy);
+int pthread_attr_setschedparam(FAR pthread_attr_t *attr,
+ FAR const struct sched_param *param);
+int pthread_attr_getschedparam(FAR pthread_attr_t *attr,
+ FAR struct sched_param *param);
+int pthread_attr_setinheritsched(FAR pthread_attr_t *attr,
+ int inheritsched);
+int pthread_attr_getinheritsched(FAR const pthread_attr_t *attr,
+ FAR int *inheritsched);
/* Set or obtain the default stack size */
-EXTERN int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize);
-EXTERN int pthread_attr_getstacksize(FAR pthread_attr_t *attr, long *stackaddr);
+int pthread_attr_setstacksize(FAR pthread_attr_t *attr, long stacksize);
+int pthread_attr_getstacksize(FAR pthread_attr_t *attr, long *stackaddr);
/* To create a thread object and runnable thread, a routine must be specified
* as the new thread's start routine. An argument may be passed to this
@@ -275,34 +277,33 @@ EXTERN int pthread_attr_getstacksize(FAR pthread_attr_t *attr, long *stackaddr);
* about the kind of thread being created.
*/
-EXTERN int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
- pthread_startroutine_t startroutine,
- pthread_addr_t arg);
+int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
+ pthread_startroutine_t startroutine, pthread_addr_t arg);
/* A thread object may be "detached" to specify that the return value and
* completion status will not be requested.
*/
-EXTERN int pthread_detach(pthread_t thread);
+int pthread_detach(pthread_t thread);
/* A thread may terminate it's own execution or the execution of another
* thread.
*/
-EXTERN void pthread_exit(pthread_addr_t value) noreturn_function;
-EXTERN int pthread_cancel(pthread_t thread);
-EXTERN int pthread_setcancelstate(int state, FAR int *oldstate);
-EXTERN void pthread_testcancel(void);
+void pthread_exit(pthread_addr_t value) noreturn_function;
+int pthread_cancel(pthread_t thread);
+int pthread_setcancelstate(int state, FAR int *oldstate);
+void pthread_testcancel(void);
/* A thread can await termination of another thread and retrieve the return
* value of the thread.
*/
-EXTERN int pthread_join(pthread_t thread, FAR pthread_addr_t *value);
+int pthread_join(pthread_t thread, FAR pthread_addr_t *value);
/* A thread may tell the scheduler that its processor can be made available. */
-EXTERN void pthread_yield(void);
+void pthread_yield(void);
/* A thread may obtain a copy of its own thread handle. */
@@ -314,91 +315,94 @@ EXTERN void pthread_yield(void);
/* Thread scheduling parameters */
-EXTERN int pthread_getschedparam(pthread_t thread, FAR int *policy,
- FAR struct sched_param *param);
-EXTERN int pthread_setschedparam(pthread_t thread, int policy,
- FAR const struct sched_param *param);
-EXTERN int pthread_setschedprio(pthread_t thread, int prio);
+int pthread_getschedparam(pthread_t thread, FAR int *policy,
+ FAR struct sched_param *param);
+int pthread_setschedparam(pthread_t thread, int policy,
+ FAR const struct sched_param *param);
+int pthread_setschedprio(pthread_t thread, int prio);
/* Thread-specific Data Interfaces */
-EXTERN int pthread_key_create(FAR pthread_key_t *key,
- CODE void (*destructor)(FAR void*));
-EXTERN int pthread_setspecific(pthread_key_t key, FAR void *value);
-EXTERN FAR void *pthread_getspecific(pthread_key_t key);
-EXTERN int pthread_key_delete(pthread_key_t key);
+int pthread_key_create(FAR pthread_key_t *key,
+ CODE void (*destructor)(FAR void*));
+int pthread_setspecific(pthread_key_t key, FAR void *value);
+FAR void *pthread_getspecific(pthread_key_t key);
+int pthread_key_delete(pthread_key_t key);
/* Create, operate on, and destroy mutex attributes. */
-EXTERN int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr);
-EXTERN int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr);
-EXTERN int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr, FAR int *pshared);
-EXTERN int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr, int pshared);
+int pthread_mutexattr_init(FAR pthread_mutexattr_t *attr);
+int pthread_mutexattr_destroy(FAR pthread_mutexattr_t *attr);
+int pthread_mutexattr_getpshared(FAR pthread_mutexattr_t *attr,
+ FAR int *pshared);
+int pthread_mutexattr_setpshared(FAR pthread_mutexattr_t *attr,
+ int pshared);
#ifdef CONFIG_MUTEX_TYPES
-EXTERN int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type);
-EXTERN int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type);
+int pthread_mutexattr_gettype(const pthread_mutexattr_t *attr, int *type);
+int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type);
#endif
/* The following routines create, delete, lock and unlock mutexes. */
-EXTERN int pthread_mutex_init(FAR pthread_mutex_t *mutex, FAR pthread_mutexattr_t *attr);
-EXTERN int pthread_mutex_destroy(FAR pthread_mutex_t *mutex);
-EXTERN int pthread_mutex_lock(FAR pthread_mutex_t *mutex);
-EXTERN int pthread_mutex_trylock(FAR pthread_mutex_t *mutex);
-EXTERN int pthread_mutex_unlock(FAR pthread_mutex_t *mutex);
+int pthread_mutex_init(FAR pthread_mutex_t *mutex,
+ FAR pthread_mutexattr_t *attr);
+int pthread_mutex_destroy(FAR pthread_mutex_t *mutex);
+int pthread_mutex_lock(FAR pthread_mutex_t *mutex);
+int pthread_mutex_trylock(FAR pthread_mutex_t *mutex);
+int pthread_mutex_unlock(FAR pthread_mutex_t *mutex);
/* Operations on condition variables */
-EXTERN int pthread_condattr_init(FAR pthread_condattr_t *attr);
-EXTERN int pthread_condattr_destroy(FAR pthread_condattr_t *attr);
+int pthread_condattr_init(FAR pthread_condattr_t *attr);
+int pthread_condattr_destroy(FAR pthread_condattr_t *attr);
/* A thread can create and delete condition variables. */
-EXTERN int pthread_cond_init(FAR pthread_cond_t *cond, FAR pthread_condattr_t *attr);
-EXTERN int pthread_cond_destroy(FAR pthread_cond_t *cond);
+int pthread_cond_init(FAR pthread_cond_t *cond, FAR pthread_condattr_t *attr);
+int pthread_cond_destroy(FAR pthread_cond_t *cond);
/* A thread can signal to and broadcast on a condition variable. */
-EXTERN int pthread_cond_broadcast(FAR pthread_cond_t *cond);
-EXTERN int pthread_cond_signal(FAR pthread_cond_t *cond);
+int pthread_cond_broadcast(FAR pthread_cond_t *cond);
+int pthread_cond_signal(FAR pthread_cond_t *cond);
/* A thread can wait for a condition variable to be signalled or broadcast. */
-EXTERN int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex);
+int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex);
/* A thread can perform a timed wait on a condition variable. */
-EXTERN int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex,
- FAR const struct timespec *abstime);
+int pthread_cond_timedwait(FAR pthread_cond_t *cond,
+ FAR pthread_mutex_t *mutex,
+ FAR const struct timespec *abstime);
/* Barrier attributes */
-EXTERN int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr);
-EXTERN int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr);
-EXTERN int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr,
- FAR int *pshared);
-EXTERN int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr,
- int pshared);
+int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr);
+int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr);
+int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr,
+ FAR int *pshared);
+int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr,
+ int pshared);
/* Barriers */
-EXTERN int pthread_barrier_destroy(FAR pthread_barrier_t *barrier);
-EXTERN int pthread_barrier_init(FAR pthread_barrier_t *barrier,
+int pthread_barrier_destroy(FAR pthread_barrier_t *barrier);
+int pthread_barrier_init(FAR pthread_barrier_t *barrier,
FAR const pthread_barrierattr_t *attr,
unsigned int count);
-EXTERN int pthread_barrier_wait(FAR pthread_barrier_t *barrier);
+int pthread_barrier_wait(FAR pthread_barrier_t *barrier);
/* Pthread initialization */
-EXTERN int pthread_once(FAR pthread_once_t *once_control,
+int pthread_once(FAR pthread_once_t *once_control,
CODE void (*init_routine)(void));
/* Pthread signal management APIs */
-EXTERN int pthread_kill(pthread_t thread, int sig);
-EXTERN int pthread_sigmask(int how, FAR const sigset_t *set, FAR sigset_t *oset);
+int pthread_kill(pthread_t thread, int sig);
+int pthread_sigmask(int how, FAR const sigset_t *set, FAR sigset_t *oset);
-#undef EXTERN
#ifdef __cplusplus
}
#endif
diff --git a/nuttx/include/semaphore.h b/nuttx/include/semaphore.h
index 257a5826f..203118bd6 100644
--- a/nuttx/include/semaphore.h
+++ b/nuttx/include/semaphore.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/semaphore.h
*
- * 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
@@ -103,9 +103,13 @@ typedef struct sem_s sem_t;
/* Initializers */
#ifdef CONFIG_PRIORITY_INHERITANCE
-# define SEM_INITIALIZER(c) {(c), SEMHOLDER_INITIALIZER}
+# if CONFIG_SEM_PREALLOCHOLDERS > 0
+# define SEM_INITIALIZER(c) {(c), NULL} /* semcount, hhead */
+# else
+# define SEM_INITIALIZER(c) {(c), SEMHOLDER_INITIALIZER} /* semcount, holder */
+# endif
#else
-# define SEM_INITIALIZER(c) {(c)}
+# define SEM_INITIALIZER(c) {(c)} /* semcount */
#endif
/****************************************************************************
diff --git a/nuttx/include/signal.h b/nuttx/include/signal.h
index 02b222343..30726105b 100644
--- a/nuttx/include/signal.h
+++ b/nuttx/include/signal.h
@@ -66,44 +66,56 @@
/* A few of the real time signals are used within the OS. They have
* default values that can be overridden from the configuration file. The
- * rest are all user signals:
+ * rest are all user signals.
+ *
+ * These are semi-standard signal definitions:
*/
#ifndef CONFIG_SIG_SIGUSR1
-#define SIGUSR1 0 /* User signal 1 */
+# define SIGUSR1 1 /* User signal 1 */
#else
-#define SIGUSR1 CONFIG_SIG_SIGUSR1
+# define SIGUSR1 CONFIG_SIG_SIGUSR1
#endif
#ifndef CONFIG_SIG_SIGUSR2
-#define SIGUSR2 1 /* User signal 2 */
+# define SIGUSR2 2 /* User signal 2 */
#else
-#define SIGUSR2 CONFIG_SIG_SIGUSR2
+# define SIGUSR2 CONFIG_SIG_SIGUSR2
#endif
#ifndef CONFIG_SIG_SIGALARM
-#define SIGALRM 2 /* Default signal used with POSIX timers (used only */
+# define SIGALRM 3 /* Default signal used with POSIX timers (used only */
/* no other signal is provided) */
#else
-#define SIGALRM CONFIG_SIG_SIGALARM
+# define SIGALRM CONFIG_SIG_SIGALARM
#endif
-#ifndef CONFIG_DISABLE_PTHREAD
-#ifndef CONFIG_SIG_SIGCONDTIMEDOUT
-#define SIGCONDTIMEDOUT 3 /* Used in the implementation of pthread_cond_timedwait */
-#else
-#define SIGCONDTIMEDOUT CONFIG_SIG_SIGCONDTIMEDOUT
+#ifdef CONFIG_SCHED_HAVE_PARENT
+# ifndef CONFIG_SIG_SIGCHLD
+# define SIGCHLD 4 /* Used by child threads to signal parent thread */
+# else
+# define SIGCHLD CONFIG_SIG_SIGCHLD
+# endif
#endif
+
+/* The following are non-standard signal definitions */
+
+#ifndef CONFIG_DISABLE_PTHREAD
+# ifndef CONFIG_SIG_SIGCONDTIMEDOUT
+# define SIGCONDTIMEDOUT 16 /* Used in the implementation of pthread_cond_timedwait */
+# else
+# define SIGCONDTIMEDOUT CONFIG_SIG_SIGCONDTIMEDOUT
+# endif
#endif
/* SIGWORK is used to wake up various internal, NuttX worker thread */
#if defined(CONFIG_SCHED_WORKQUEUE) || defined(CONFIG_PAGING)
-#ifndef CONFIG_SIG_SIGWORK
-#define SIGWORK 4 /* Used to wake up the work queue */
-#else
-#define SIGWORK CONFIG_SIG_SIGWORK
-#endif
+# ifndef CONFIG_SIG_SIGWORK
+# define SIGWORK 17 /* Used to wake up the work queue */
+# else
+# define SIGWORK CONFIG_SIG_SIGWORK
+# endif
#endif
/* sigprocmask() "how" definitions. Only one of the following can be specified: */
@@ -122,12 +134,18 @@
/* These are the possible values of the signfo si_code field */
-#define SI_USER 0 /* Signal sent from kill, raise, or abort */
-#define SI_QUEUE 1 /* Signal sent from sigqueue */
-#define SI_TIMER 2 /* Signal is result of timer expiration */
-#define SI_ASYNCIO 3 /* Signal is the result of asynch IO completion */
-#define SI_MESGQ 4 /* Signal generated by arrival of a message on an */
- /* empty message queue */
+#define SI_USER 0 /* Signal sent from kill, raise, or abort */
+#define SI_QUEUE 1 /* Signal sent from sigqueue */
+#define SI_TIMER 2 /* Signal is result of timer expiration */
+#define SI_ASYNCIO 3 /* Signal is the result of asynch IO completion */
+#define SI_MESGQ 4 /* Signal generated by arrival of a message on an */
+ /* empty message queue */
+#define CLD_EXITED 5 /* Child has exited (SIGCHLD only) */
+#define CLD_KILLED 6 /* Child was killed (SIGCHLD only) */
+#define CLD_DUMPED 7 /* Child terminated abnormally (SIGCHLD only) */
+#define CLD_TRAPPED 8 /* Traced child has trapped (SIGCHLD only) */
+#define CLD_STOPPED 9 /* Child has stopped (SIGCHLD only) */
+#define CLD_CONTINUED 10 /* Stopped child had continued (SIGCHLD only) */
/* Values for the sigev_notify field of struct sigevent */
@@ -175,6 +193,10 @@ struct siginfo
uint8_t si_signo; /* Identifies signal */
uint8_t si_code; /* Source: SI_USER, SI_QUEUE, SI_TIMER, SI_ASYNCIO, or SI_MESGQ */
union sigval si_value; /* Data passed with signal */
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ pid_t si_pid; /* Sending task ID */
+ int si_status; /* Exit value or signal (SIGCHLD only). */
+#endif
};
typedef struct siginfo siginfo_t;
diff --git a/nuttx/include/spawn.h b/nuttx/include/spawn.h
new file mode 100644
index 000000000..5e0ce3416
--- /dev/null
+++ b/nuttx/include/spawn.h
@@ -0,0 +1,198 @@
+/****************************************************************************
+ * include/spawn.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_SPAWN_H
+#define __INCLUDE_SPAWN_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <sched.h>
+#include <signal.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* "The spawn.h header shall define the flags that may be set in a
+ * posix_spawnattr_t object using the posix_spawnattr_setflags() function:"
+ */
+
+#define POSIX_SPAWN_RESETIDS (1 << 0) /* 1: Reset effective user ID */
+#define POSIX_SPAWN_SETPGROUP (1 << 1) /* 1: Set process group */
+#define POSIX_SPAWN_SETSCHEDPARAM (1 << 2) /* 1: Set task's priority */
+#define POSIX_SPAWN_SETSCHEDULER (1 << 3) /* 1: Set task's scheduler policy */
+#define POSIX_SPAWN_SETSIGDEF (1 << 4) /* 1: Set default signal actions */
+#define POSIX_SPAWN_SETSIGMASK (1 << 5) /* 1: Set sigmask */
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+/* "The spawn.h header shall define the posix_spawnattr_t and
+ * posix_spawn_file_actions_t types used in performing spawn operations.
+ *
+ * The internal structure underlying the posix_spawnattr_t is exposed here
+ * because the user will be required to allocate this memory.
+ */
+
+struct posix_spawnattr_s
+{
+ uint8_t flags;
+ uint8_t priority;
+ uint8_t policy;
+#ifndef CONFIG_DISABLE_SIGNALS
+ sigset_t sigmask;
+#endif
+};
+
+typedef struct posix_spawnattr_s posix_spawnattr_t;
+
+/* posix_spawn_file_actions_addclose(), posix_spawn_file_actions_adddup2(),
+ * and posix_spawn_file_actions_addopen() will allocate memory and append
+ * a new file action to an instance of posix_spawn_file_actions_t. The
+ * internal representation of these structures is not exposed to the user.
+ * The user need only know that the size sizeof(posix_spawn_file_actions_t)
+ * will hold a pointer to data.
+ */
+
+typedef FAR void *posix_spawn_file_actions_t;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/* "The following shall be declared as functions and may also be defined as
+ * macros. Function prototypes shall be provided."
+ */
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/* posix_spawn[p] interfaces ************************************************/
+
+#ifdef CONFIG_BINFMT_EXEPATH
+int posix_spawnp(FAR pid_t *pid, FAR const char *path,
+ FAR const posix_spawn_file_actions_t *file_actions,
+ FAR const posix_spawnattr_t *attr,
+ FAR char *const argv[], FAR char *const envp[]);
+#define posix_spawn(pid,path,file_actions,attr,argv,envp) \
+ posix_spawnp(pid,path,file_actions,attr,argv,envp)
+#else
+int posix_spawn(FAR pid_t *pid, FAR const char *path,
+ FAR const posix_spawn_file_actions_t *file_actions,
+ FAR const posix_spawnattr_t *attr,
+ FAR char *const argv[], FAR char *const envp[]);
+#endif
+
+/* File action interfaces ***************************************************/
+/* File action initialization and destruction */
+
+int posix_spawn_file_actions_init(FAR posix_spawn_file_actions_t *file_actions);
+int posix_spawn_file_actions_destroy(FAR posix_spawn_file_actions_t *file_actions);
+
+/* Add file action interfaces */
+
+int posix_spawn_file_actions_addclose(FAR posix_spawn_file_actions_t *file_actions,
+ int fd);
+int posix_spawn_file_actions_adddup2(FAR posix_spawn_file_actions_t *file_actions,
+ int fd1, int fd2);
+int posix_spawn_file_actions_addopen(FAR posix_spawn_file_actions_t *file_actions,
+ int fd, FAR const char *path, int oflags, mode_t mode);
+
+/* Spawn attributes interfaces **********************************************/
+/* Spawn attributes initialization and destruction */
+
+int posix_spawnattr_init(FAR posix_spawnattr_t *attr);
+
+/* int posix_spawnattr_destroy(FAR posix_spawnattr_t *); */
+#ifdef CONFIG_DEBUG
+# define posix_spawnattr_destroy(attr) (attr ? 0 : EINVAL)
+#else
+# define posix_spawnattr_destroy(attr) (0)
+#endif
+
+/* Get spawn attributes interfaces */
+
+int posix_spawnattr_getflags(FAR const posix_spawnattr_t *attr, FAR short *flags);
+#define posix_spawnattr_getpgroup(attr,group) (ENOSYS)
+int posix_spawnattr_getschedparam(FAR const posix_spawnattr_t *attr,
+ FAR struct sched_param *param);
+int posix_spawnattr_getschedpolicy(FAR const posix_spawnattr_t *attr,
+ FAR int *policy);
+#define posix_spawnattr_getsigdefault(attr,sigdefault) (ENOSYS)
+#ifndef CONFIG_DISABLE_SIGNALS
+int posix_spawnattr_getsigmask(FAR const posix_spawnattr_t *attr,
+ FAR sigset_t *sigmask);
+#else
+# define posix_spawnattr_getsigmask(attr,sigmask) (ENOSYS)
+#endif
+
+/* Set spawn attributes interfaces */
+
+int posix_spawnattr_setflags(FAR posix_spawnattr_t *attr, short flags);
+#define posix_spawnattr_setpgroup(attr,group) (ENOSYS)
+int posix_spawnattr_setschedparam(FAR posix_spawnattr_t *attr,
+ FAR const struct sched_param *param);
+int posix_spawnattr_setschedpolicy(FAR posix_spawnattr_t *attr, int policy);
+#define posix_spawnattr_setsigdefault(attr,sigdefault) (ENOSYS)
+#ifndef CONFIG_DISABLE_SIGNALS
+int posix_spawnattr_setsigmask(FAR posix_spawnattr_t *attr,
+ FAR const sigset_t *sigmask);
+#else
+# define posix_spawnattr_setsigmask(attr,sigmask) (ENOSYS)
+#endif
+
+/* Non standard debug functions */
+
+#ifdef CONFIG_DEBUG
+void posix_spawn_file_actions_dump(FAR posix_spawn_file_actions_t *file_actions);
+void posix_spawnattr_dump(FAR posix_spawnattr_t *attr);
+#else
+# define posix_spawn_file_actions_dump(fa)
+# define posix_spawnattr_dump(a)
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_SPAWN_H */
diff --git a/nuttx/include/stdbool.h b/nuttx/include/stdbool.h
index 9c16aee29..6c3302549 100644
--- a/nuttx/include/stdbool.h
+++ b/nuttx/include/stdbool.h
@@ -90,8 +90,8 @@
# define bool _Bool8
#endif
-#define true 1
-#define false 0
+#define true (bool)1
+#define false (bool)0
#define __bool_true_false_are_defined 1
diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h
index 2ae69d4a7..95feee72e 100644
--- a/nuttx/include/sys/types.h
+++ b/nuttx/include/sys/types.h
@@ -154,7 +154,9 @@ typedef uint16_t dev_t;
typedef uint16_t ino_t;
-/* pid_t is used for process IDs and process group IDs */
+/* pid_t is used for process IDs and process group IDs. It must be signed because
+ * negative PID values are used to represent invalid PIDs.
+ */
typedef int pid_t;
diff --git a/nuttx/include/sys/wait.h b/nuttx/include/sys/wait.h
index 6af1e971e..2476adef9 100644
--- a/nuttx/include/sys/wait.h
+++ b/nuttx/include/sys/wait.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/sys/wait.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -66,7 +66,7 @@
#define WTERMSIG(s) (false) /* Return signal number that caused process to terminate */
/* The following symbolic constants are possible values for the options
- * argument to waitpi(1) (1) and/or waitid() (2),
+ * argument to waitpid() (1) and/or waitid() (2),
*/
#define WCONTINUED (1 << 0) /* Status for child that has been continued (1)(2) */
@@ -104,9 +104,9 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN pid_t wait(int *stat_loc);
-EXTERN int waitid(idtype_t idtype, id_t id, siginfo_t *siginfo, int options);
-EXTERN pid_t waitpid(pid_t pid, int *stat_loc, int options);
+EXTERN pid_t wait(FAR int *stat_loc);
+EXTERN int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options);
+EXTERN pid_t waitpid(pid_t pid, FAR int *stat_loc, int options);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h
index 681ce9e63..46eb14cdd 100644
--- a/nuttx/include/unistd.h
+++ b/nuttx/include/unistd.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/unistd.h
*
- * Copyright (C) 2007-2009 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
@@ -129,6 +129,7 @@ EXTERN int optopt; /* unrecognized option character */
/* Task Control Interfaces */
+EXTERN pid_t vfork(void);
EXTERN pid_t getpid(void);
EXTERN void _exit(int status) noreturn_function;
EXTERN unsigned int sleep(unsigned int seconds);
@@ -159,6 +160,19 @@ EXTERN FAR char *getcwd(FAR char *buf, size_t size);
EXTERN int unlink(FAR const char *pathname);
EXTERN int rmdir(FAR const char *pathname);
+/* Execution of programs from files */
+
+#ifdef CONFIG_LIBC_EXECFUNCS
+EXTERN int execl(FAR const char *path, ...);
+EXTERN int execv(FAR const char *path, FAR char *const argv[]);
+
+/* Non-standard functions to manage symbol tables */
+
+struct symtab_s; /* See include/nuttx/binfmt/symtab.h */
+EXTERN void exec_getsymtab(FAR const struct symtab_s **symtab, FAR int *nsymbols);
+EXTERN void exec_setsymtab(FAR const struct symtab_s *symtab, int nsymbols);
+#endif
+
/* Other */
EXTERN int getopt(int argc, FAR char *const argv[], FAR const char *optstring);