aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include/sys
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include/sys')
-rw-r--r--nuttx/include/sys/ioctl.h83
-rw-r--r--nuttx/include/sys/mman.h113
-rw-r--r--nuttx/include/sys/mount.h77
-rw-r--r--nuttx/include/sys/prctl.h114
-rw-r--r--nuttx/include/sys/select.h121
-rw-r--r--nuttx/include/sys/sendfile.h123
-rw-r--r--nuttx/include/sys/socket.h234
-rw-r--r--nuttx/include/sys/sockio.h120
-rw-r--r--nuttx/include/sys/stat.h134
-rw-r--r--nuttx/include/sys/statfs.h145
-rw-r--r--nuttx/include/sys/syscall.h398
-rw-r--r--nuttx/include/sys/time.h74
-rw-r--r--nuttx/include/sys/types.h234
-rw-r--r--nuttx/include/sys/vfs.h61
-rw-r--r--nuttx/include/sys/wait.h118
15 files changed, 0 insertions, 2149 deletions
diff --git a/nuttx/include/sys/ioctl.h b/nuttx/include/sys/ioctl.h
deleted file mode 100644
index 3d1874869..000000000
--- a/nuttx/include/sys/ioctl.h
+++ /dev/null
@@ -1,83 +0,0 @@
-/****************************************************************************
- * include/sys/ioctl.h
- *
- * Copyright (C) 2007, 2008, 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_SYS_IOCTL_H
-#define __INCLUDE_SYS_IOCTL_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/* Get NuttX configuration and NuttX-specific IOCTL definitions */
-
-#include <nuttx/config.h>
-#include <nuttx/fs/ioctl.h>
-
-/* Include network ioctls info */
-
-#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
-# include <nuttx/net/ioctl.h>
-#endif
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* ioctl() is a non-standard UNIX-like API */
-
-EXTERN int ioctl(int fd, int req, unsigned long arg);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_IOCTL_H */
diff --git a/nuttx/include/sys/mman.h b/nuttx/include/sys/mman.h
deleted file mode 100644
index ab847b97a..000000000
--- a/nuttx/include/sys/mman.h
+++ /dev/null
@@ -1,113 +0,0 @@
-/****************************************************************************
- * include/sys/mman.h
- *
- * Copyright (C) 2008, 2009, 2011 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_SYS_MMAN_H
-#define __INCLUDE_SYS_MMAN_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <sys/types.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Protections are chosen from these bits, OR'd together. NuttX does not
- * support any of these, but are provided for source level compatibility
- */
-
-#define PROT_NONE 0x0 /* Page may not be accessed */
-#define PROT_READ 0x1 /* Page may be read */
-#define PROT_WRITE 0x2 /* Page may be written */
-#define PROT_EXEC 0x4 /* Page may be executed */
-
-/* Sharing types -- ignored by NuttX. */
-
-#define MAP_SHARED 0x00001 /* Share this mapping */
-#define MAP_PRIVATE 0x00002 /* Create a private copy-on-write mapping */
-#define MAP_TYPE 0x0000f /* Mask for type of mapping */
-#define MAP_FIXED 0x00010 /* Map to specified address exactly */
-#define MAP_FILE 0x00000 /* The mapping is backed by a file */
-#define MAP_ANONYMOUS 0x00020 /* The mapping is not backed by any file */
-#define MAP_ANON MAP_ANONYMOUS
-
-/* These are Linux-specific. */
-
-#define MAP_GROWSDOWN 0x00100 /* Used to stack allocations */
-#define MAP_DENYWRITE 0x00800 /* Do not permit writes to file */
-#define MAP_EXECUTABLE 0x01000 /* Mark it as an executable */
-#define MAP_LOCKED 0x02000 /* Lock pages mapped into memory */
-#define MAP_NORESERVE 0x04000 /* Do not reserve swap space for this mapping */
-#define MAP_POPULATE 0x08000 /* Populate (prefault) pagetables */
-#define MAP_NONBLOCK 0x10000 /* Do not block on IO */
-
-/* Failure return */
-
-#define MAP_FAILED ((void*)-1)
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN FAR void *mmap(FAR void *start, size_t length, int prot, int flags,
- int fd, off_t offset);
-
-#ifdef CONFIG_FS_RAMMAP
-EXTERN int munmap(FAR void *start, size_t length);
-#else
-# define munmap(start, length)
-#endif
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_MMAN_H */
diff --git a/nuttx/include/sys/mount.h b/nuttx/include/sys/mount.h
deleted file mode 100644
index 194dec8cc..000000000
--- a/nuttx/include/sys/mount.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/****************************************************************************
- * include/sys/mount.h
- *
- * Copyright (C) 2007-2009 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_SYS_MOUNT_H
-#define __INCLUDE_SYS_MOUNT_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Mount flags */
-
-#define MS_RDONLY 1 /* Mount file system read-only */
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN int mount(const char *source, const char *target,
- const char *filesystemtype, unsigned long mountflags,
- const void *data);
-EXTERN int umount(const char *target);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_MOUNT_H */
diff --git a/nuttx/include/sys/prctl.h b/nuttx/include/sys/prctl.h
deleted file mode 100644
index f1441a77a..000000000
--- a/nuttx/include/sys/prctl.h
+++ /dev/null
@@ -1,114 +0,0 @@
-/****************************************************************************
- * include/sys/prctl.h
- *
- * 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_SYS_PRCTL_H
-#define __INCLUDE_SYS_PRCTL_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Supported prctl() commands.
- *
- * PR_SET_NAME
- * Set the task (or thread) name for the thread whose ID is in required
- * arg2 (int), using the value in the location pointed to by required arg1
- * (char*). The name can be up to CONFIG_TASK_NAME_SIZE long (including
- * any null termination). The thread ID of 0 will set the name of the
- * calling thread. As an example:
- *
- * prctl(PR_SET_NAME, "MyName", 0);
- *
- * PR_GET_NAME
- * Return the task (or thread) name for the for the thread whose ID is
- * optional arg2 (int), in the buffer pointed to by optional arg1 (char *).
- * The buffer must be CONFIG_TASK_NAME_SIZE long (including any null
- * termination). As an example:
- *
- * char myname[CONFIG_TASK_NAME_SIZE];
- * prctl(PR_GET_NAME, myname, 0);
- */
-
- #define PR_SET_NAME 1
- #define PR_GET_NAME 2
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/****************************************************************************
- * Name: prctl
- *
- * Description:
- * prctl() is called with a first argument describing what to do (with
- * values PR_* defined above) and with additional arguments depending on
- * the specific command.
- *
- * Returned Value:
- * The returned value may depend on the specific commnand. For PR_SET_NAME
- * and PR_GET_NAME, the returned value of 0 indicates successful operation.
- * On any failure, -1 is retruend and the errno value is set appropriately.
- *
- * EINVAL The value of 'option' is not recognized.
- * EFAULT optional arg1 is not a valid address.
- * ESRCH No task/thread can be found corresponding to that specified
- * by optional arg1.
- *
- ****************************************************************************/
-
-EXTERN int prctl(int option, ...);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_PRCTL_H */
diff --git a/nuttx/include/sys/select.h b/nuttx/include/sys/select.h
deleted file mode 100644
index 1ff074b6c..000000000
--- a/nuttx/include/sys/select.h
+++ /dev/null
@@ -1,121 +0,0 @@
-/****************************************************************************
- * include/sys/select.h
- *
- * Copyright (C) 2008-2009, 2011 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_SYS_SELECT_H
-#define __INCLUDE_SYS_SELECT_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <time.h>
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Get the total number of descriptors that we will have to support */
-
-#define __SELECT_NDESCRIPTORS (CONFIG_NFILE_DESCRIPTORS + CONFIG_NSOCKET_DESCRIPTORS)
-
-/* We will use a 32-bit bitsets to represent the set of descriptors. How
- * many uint32_t's do we need to span all descriptors?
- */
-
-#if __SELECT_NDESCRIPTORS <= 32
-# define __SELECT_NUINT32 1
-#elif __SELECT_NDESCRIPTORS <= 64
-# define __SELECT_NUINT32 2
-#elif __SELECT_NDESCRIPTORS <= 96
-# define __SELECT_NUINT32 3
-#elif __SELECT_NDESCRIPTORS <= 128
-# define __SELECT_NUINT32 4
-#elif __SELECT_NDESCRIPTORS <= 160
-# define __SELECT_NUINT32 5
-#elif __SELECT_NDESCRIPTORS <= 192
-# define __SELECT_NUINT32 6
-#elif __SELECT_NDESCRIPTORS <= 224
-# define __SELECT_NUINT32 7
-#elif __SELECT_NDESCRIPTORS <= 256
-# define __SELECT_NUINT32 8
-#else
-# warning "Large fd_set needed"
-#endif
-
-/* These macros map a file descripto to an index and bit number */
-
-#define _FD_NDX(fd) ((fd) >> 5)
-#define _FD_BIT(fd) ((fd) & 0x1f)
-
-/* Standard helper macros */
-
-#define FD_CLR(fd,set) (((uint32_t*)(set))[_FD_NDX(fd)] &= ~(1 << _FD_BIT(fd)))
-#define FD_SET(fd,set) (((uint32_t*)(set))[_FD_NDX(fd)] |= (1 << _FD_BIT(fd)))
-#define FD_ISSET(fd,set) ((((uint32_t*)(set))[_FD_NDX(fd)] & (1 << _FD_BIT(fd))) != 0)
-#define FD_ZERO(set) memset(set, 0, sizeof(fd_set))
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
-typedef uint32_t fd_set[__SELECT_NUINT32];
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
- FAR fd_set *exceptfds, FAR struct timeval *timeout);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
-#endif /* __INCLUDE_SYS_SELECT_H */
diff --git a/nuttx/include/sys/sendfile.h b/nuttx/include/sys/sendfile.h
deleted file mode 100644
index 0f3c05444..000000000
--- a/nuttx/include/sys/sendfile.h
+++ /dev/null
@@ -1,123 +0,0 @@
-/****************************************************************************
- * include/sys/sendfile.h
- *
- * 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_SYS_SENDFILE_H
-#define __INCLUDE_SYS_SENDFILE_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-/* Configuration ************************************************************/
-
-#ifndef CONFIG_LIB_SENDFILE_BUFSIZE
-# define CONFIG_LIB_SENDFILE_BUFSIZE 512
-#endif
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/************************************************************************
- * Name: sendfile
- *
- * Description:
- * sendfile() copies data between one file descriptor and another.
- * sendfile() basically just wraps a sequence of reads() and writes()
- * to perform a copy. It serves a purpose in systems where there is
- * a penalty for copies to between user and kernal space, but really
- * nothing in NuttX but provide some Linux compatible (and adding
- * another 'almost standard' interface).
- *
- * NOTE: This interface is *not* specified in POSIX.1-2001, or other
- * standards. The implementation here is very similar to the Linux
- * sendfile interface. Other UNIX systems implement sendfile() with
- * different semantics and prototypes. sendfile() should not be used
- * in portable programs.
- *
- * Input Parmeters:
- * infd - A file (or socket) descriptor opened for reading
- * outfd - A descriptor opened for writing.
- * offset - If 'offset' is not NULL, then it points to a variable
- * holding the file offset from which sendfile() will start
- * reading data from 'infd'. When sendfile() returns, this
- * variable will be set to the offset of the byte following
- * the last byte that was read. If 'offset' is not NULL,
- * then sendfile() does not modify the current file offset of
- * 'infd'; otherwise the current file offset is adjusted to
- * reflect the number of bytes read from 'infd.'
- *
- * If 'offset' is NULL, then data will be read from 'infd'
- * starting at the current file offset, and the file offset
- * will be updated by the call.
- * count - The number of bytes to copy between the file descriptors.
- *
- * Returned Value:
- * If the transfer was successful, the number of bytes written to outfd is
- * returned. On error, -1 is returned, and errno is set appropriately.
- * There error values are those returned by read() or write() plus:
- *
- * EINVAL - Bad input parameters.
- * ENOMEM - Could not allocated an I/O buffer
- *
- ************************************************************************/
-
-EXTERN ssize_t sendfile (int outfd, int infd, FAR off_t *offset, size_t count);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_SENDFILE_H */
diff --git a/nuttx/include/sys/socket.h b/nuttx/include/sys/socket.h
deleted file mode 100644
index 89ade941f..000000000
--- a/nuttx/include/sys/socket.h
+++ /dev/null
@@ -1,234 +0,0 @@
-/****************************************************************************
- * include/sys/socket.h
- *
- * Copyright (C) 2007, 2009, 2011 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_SYS_SOCKET_H
-#define __INCLUDE_SYS_SOCKET_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <sys/types.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* The socket()domain parameter specifies a communication domain; this selects
- * the protocol family which will be used for communication.
- */
-
-/* Protocol families */
-
-#define PF_UNSPEC 0 /* Protocol family unspecified */
-#define PF_UNIX 1 /* Local communication */
-#define PF_LOCAL 1 /* Local communication */
-#define PF_INET 2 /* IPv4 Internet protocols */
-#define PF_INET6 3 /* IPv6 Internet protocols */
-#define PF_IPX 4 /* IPX - Novell protocols */
-#define PF_NETLINK 5 /* Kernel user interface device */
-#define PF_X25 6 /* ITU-T X.25 / ISO-8208 protocol */
-#define PF_AX25 7 /* Amateur radio AX.25 protocol */
-#define PF_ATMPVC 8 /* Access to raw ATM PVCs */
-#define PF_APPLETALK 9 /* Appletalk */
-#define PF_PACKET 10 /* Low level packet interface */
-
-/* Address families */
-
-#define AF_UNSPEC PF_UNSPEC
-#define AF_UNIX PF_UNIX
-#define AF_LOCAL PF_LOCAL
-#define AF_INET PF_INET
-#define AF_INET6 PF_INET6
-#define AF_IPX PF_IPX
-#define AF_NETLINK PF_NETLINK
-#define AF_X25 PF_X25
-#define AF_AX25 PF_AX25
-#define AF_ATMPVC PF_ATMPVC
-#define AF_APPLETALK PF_APPLETALK
-#define AF_PACKET PF_PACKET
-
-/* The socket created by socket() has the indicated type, which specifies
- * the communication semantics.
- */
-
-#define SOCK_STREAM 0 /* Provides sequenced, reliable, two-way, connection-based byte streams.
- * An out-of-band data transmission mechanism may be supported. */
-#define SOCK_DGRAM 1 /* Supports datagrams (connectionless, unreliable messages of a fixed
- * maximum length). */
-#define SOCK_SEQPACKET 2 /* Provides a sequenced, reliable, two-way connection-based data
- * transmission path for datagrams of fixed maximum length; a consumer
- * is required to read an entire packet with each read system call. */
-#define SOCK_RAW 3 /* Provides raw network protocol access. */
-#define SOCK_RDM 4 /* Provides a reliable datagram layer that does not guarantee ordering. */
-#define SOCK_PACKET 5 /* Obsolete and should not be used in new programs */
-
-/* Bits in the FLAGS argument to `send', `recv', et al. These are the bits
- * recognized by Linus, not all are supported by NuttX.
- */
-
-#define MSG_OOB 0x0001 /* Process out-of-band data. */
-#define MSG_PEEK 0x0002 /* Peek at incoming messages. */
-#define MSG_DONTROUTE 0x0004 /* Don't use local routing. */
-#define MSG_CTRUNC 0x0008 /* Control data lost before delivery. */
-#define MSG_PROXY 0x0010 /* Supply or ask second address. */
-#define MSG_TRUNC 0x0020
-#define MSG_DONTWAIT 0x0040 /* Enable nonblocking IO. */
-#define MSG_EOR 0x0080 /* End of record. */
-#define MSG_WAITALL 0x0100 /* Wait for a full request. */
-#define MSG_FIN 0x0200
-#define MSG_SYN 0x0400
-#define MSG_CONFIRM 0x0800 /* Confirm path validity. */
-#define MSG_RST 0x1000
-#define MSG_ERRQUEUE 0x2000 /* Fetch message from error queue. */
-#define MSG_NOSIGNAL 0x4000 /* Do not generate SIGPIPE. */
-#define MSG_MORE 0x8000 /* Sender will send more. */
-
-/* Socket options */
-
-#define SO_DEBUG 0 /* Enables recording of debugging information (get/set).
- * arg: pointer to integer containing a boolean value */
-#define SO_ACCEPTCONN 1 /* Reports whether socket listening is enabled (get only).
- * arg: pointer to integer containing a boolean value */
-#define SO_BROADCAST 2 /* Permits sending of broadcast messages (get/set).
- * arg: pointer to integer containing a boolean value */
-#define SO_REUSEADDR 3 /* Allow reuse of local addresses (get/set)
- * arg: pointer to integer containing a boolean value */
-#define SO_KEEPALIVE 4 /* Keeps connections active by enabling the periodic transmission
- * of messages (get/set).
- * arg: pointer to integer containing a boolean value */
-#define SO_LINGER 5 /* Lingers on a close() if data is present (get/set)
- * arg: struct linger */
-#define SO_OOBINLINE 6 /* Leaves received out-of-band data (data marked urgent) inline
- * (get/set) arg: pointer to integer containing a boolean value */
-#define SO_SNDBUF 7 /* Sets send buffer size. arg: integer value (get/set). */
-#define SO_RCVBUF 8 /* Sets receive buffer size. arg: integer value (get/set). */
-#define SO_ERROR 9 /* Reports and clears error status (get only). arg: returns
- * an integer value */
-#define SO_TYPE 10 /* Reports the socket type (get only). return: int */
-#define SO_DONTROUTE 11 /* Requests that outgoing messages bypass standard routing (get/set)
- * arg: pointer to integer containing a boolean value */
-#define SO_RCVLOWAT 12 /* Sets the minimum number of bytes to process for socket input
- * (get/set). arg: integer value */
-#define SO_RCVTIMEO 13 /* Sets the timeout value that specifies the maximum amount of time
- * an input function waits until it completes (get/set).
- * arg: struct timeval */
-#define SO_SNDLOWAT 14 /* Sets the minimum number of bytes to process for socket output
- * (get/set). arg: integer value */
-#define SO_SNDTIMEO 15 /* Sets the timeout value specifying the amount of time that an
- * output function blocks because flow control prevents data from
- * being sent(get/set). arg: struct timeval */
-
-/* Protocol levels supported by get/setsockopt(): */
-
-#define SOL_SOCKET 0 /* Only socket-level options supported */
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
- /* sockaddr_storage structure. This structure must be (1) large enough to
- * accommodate all supported protocol-specific address structures, and (2)
- * aligned at an appropriate boundary so that pointers to it can be cast
- * as pointers to protocol-specific address structures and used to access
- * the fields of those structures without alignment problems
- */
-
-#ifdef CONFIG_NET_IPv6
-struct sockaddr_storage
-{
- sa_family_t ss_family; /* Address family */
- char ss_data[18]; /* 18-bytes of address data */
-};
-#else
-struct sockaddr_storage
-{
- sa_family_t ss_family; /* Address family */
- char ss_data[14]; /* 14-bytes of address data */
-};
-#endif
-
-/* The sockaddr structure is used to define a socket address which is used
- * in the bind(), connect(), getpeername(), getsockname(), recvfrom(), and
- * sendto() functions.
- */
-
-struct sockaddr
-{
- sa_family_t sa_family; /* Address family: See AF_* definitions */
- char sa_data[14]; /* 14-bytes of address data */
-};
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN int socket(int domain, int type, int protocol);
-EXTERN int bind(int sockfd, FAR const struct sockaddr *addr, socklen_t addrlen);
-EXTERN int connect(int sockfd, FAR const struct sockaddr *addr, socklen_t addrlen);
-
-EXTERN int listen(int sockfd, int backlog);
-EXTERN int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen);
-
-EXTERN ssize_t send(int sockfd, FAR const void *buf, size_t len, int flags);
-EXTERN ssize_t sendto(int sockfd, FAR const void *buf, size_t len, int flags,
- FAR const struct sockaddr *to, socklen_t tolen);
-
-EXTERN ssize_t recv(int sockfd, FAR void *buf, size_t len, int flags);
-EXTERN ssize_t recvfrom(int sockfd, FAR void *buf, size_t len, int flags,
- FAR struct sockaddr *from, FAR socklen_t *fromlen);
-
-EXTERN int setsockopt(int sockfd, int level, int option,
- FAR const void *value, socklen_t value_len);
-EXTERN int getsockopt(int sockfd, int level, int option,
- FAR void *value, FAR socklen_t *value_len);
-
-EXTERN int getsockname(int sockfd, FAR struct sockaddr *addr,
- FAR socklen_t *addrlen);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_SOCKET_H */
diff --git a/nuttx/include/sys/sockio.h b/nuttx/include/sys/sockio.h
deleted file mode 100644
index abfc2f562..000000000
--- a/nuttx/include/sys/sockio.h
+++ /dev/null
@@ -1,120 +0,0 @@
-/****************************************************************************
- * include/sys/sockio.h
- *
- * Copyright (C) 2010, 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_SYS_SOCKIO_H
-#define __INCLUDE_SYS_SOCKIO_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/* Get NuttX configuration and NuttX-specific network IOCTL definitions */
-
-#include <nuttx/config.h>
-#include <nuttx/fs/ioctl.h>
-#include <nuttx/net/ioctl.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-#define IMSFNAMSIZ 8
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
- /* RFC3678: IPv4 Options
- *
- * o ioctl() SIOCGIPMSFILTER: to retrieve the list of source addresses
- * that comprise the source filter along with the current filter mode.
- *
- * o ioctl() SIOCSIPMSFILTER: to set or modify the source filter content
- * (e.g., unicast source address list) or mode (exclude or include).
- *
- * Ioctl option Argument type
- * ----------------------------- ----------------------
- * SIOCGIPMSFILTER struct ip_msfilter
- * SIOCSIPMSFILTER struct ip_msfilter
- *
- * The imsf_fmode mode is a 32-bit integer that identifies the filter
- * mode. The value of this field must be either MCAST_INCLUDE or
- * MCAST_EXCLUDE, which are likewise defined in <netinet/in.h>.
- */
-
-#if 0 /* REVISIT: Current NuttX implementation is non-standard.
- * Lookup is by device name, not IP address.
- */
-
-struct ip_msfilter
-{
- struct in_addr imsf_multiaddr; /* IP multicast address of group */
- struct in_addr imsf_interface; /* Local IP address of interface */
- uint32_t imsf_fmode; /* Filter mode */
-#ifdef CONFIG_NET_IGMPv3
- uint32_t imsf_numsrc; /* number of sources in src_list */
- struct in_addr imsf_slist[1]; /* start of source list */
-#endif
-};
-
-#else
-
-struct ip_msfilter
-{
- char imsf_name[IMSFNAMSIZ]; /* Network device name, e.g., "eth0" */
- struct in_addr imsf_multiaddr; /* IP multicast address of group */
- uint32_t imsf_fmode; /* Filter mode */
-};
-
-#endif
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_SOCKIO_H */
diff --git a/nuttx/include/sys/stat.h b/nuttx/include/sys/stat.h
deleted file mode 100644
index 1204b15aa..000000000
--- a/nuttx/include/sys/stat.h
+++ /dev/null
@@ -1,134 +0,0 @@
-/****************************************************************************
- * include/sys/stat.h
- *
- * Copyright (C) 2007-2009, 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_SYS_STAT_H
-#define __INCLUDE_SYS_STAT_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <sys/types.h>
-#include <time.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* mode_t bit settings (most of these do not apply to Nuttx). This assumes
- * that the full size of a mode_t is 16-bits. (However, mode_t must be size
- * 'int' because it is promoted to size int when passed in varargs).
- */
-
-#define S_IXOTH 0000001 /* Permissions for others: RWX */
-#define S_IWOTH 0000002
-#define S_IROTH 0000004
-#define S_IRWXO 0000007
-
-#define S_IXGRP 0000010 /* Group permissions: RWX */
-#define S_IWGRP 0000020
-#define S_IRGRP 0000040
-#define S_IRWXG 0000070
-
-#define S_IXUSR 0000100 /* Owner permissions: RWX */
-#define S_IWUSR 0000200
-#define S_IRUSR 0000400
-#define S_IRWXU 0000700
-
-#define S_ISVTX 0001000 /* "sticky" bit */
-#define S_ISGID 0002000 /* Set group ID bit */
-#define S_ISUID 0004000 /* Set UID bit */
-
-#define S_IFIFO 0010000 /* File type bites */
-#define S_IFCHR 0020000
-#define S_IFDIR 0040000
-#define S_IFBLK 0060000
-#define S_IFREG 0100000
-#define S_IFLNK 0120000
-#define S_IFSOCK 0140000
-#define S_IFMT 0170000
-
-/* File type macros that operate on an instance of mode_t */
-
-#define S_ISLNK(m) (((m) & S_IFMT) == S_IFLNK)
-#define S_ISREG(m) (((m) & S_IFMT) == S_IFREG)
-#define S_ISDIR(m) (((m) & S_IFMT) == S_IFDIR)
-#define S_ISCHR(m) (((m) & S_IFMT) == S_IFCHR)
-#define S_ISBLK(m) (((m) & S_IFMT) == S_IFBLK)
-#define S_ISFIFO(m) (((m) & S_IFMT) == S_IFIFO)
-#define S_ISSOCK(m) (((m) & S_IFMT) == S_IFSOCK)
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
-/* This is the simplified struct stat as returned by fstat(). This structure
- * provides information about a specific file or directory in the file system.
- */
-
-struct stat
-{
- mode_t st_mode; /* File type, atributes, and access mode bits */
- off_t st_size; /* Size of file/directory, in bytes */
- blksize_t st_blksize; /* Blocksize used for filesystem I/O */
- blkcnt_t st_blocks; /* Number of blocks allocated */
- time_t st_atime; /* Time of last access */
- time_t st_mtime; /* Time of last modification */
- time_t st_ctime; /* Time of last status change */
-};
-
-/****************************************************************************
- * Global Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN int mkdir(FAR const char *pathname, mode_t mode);
-EXTERN int mkfifo(FAR const char *pathname, mode_t mode);
-EXTERN int stat(const char *path, FAR struct stat *buf);
-EXTERN int fstat(int fd, FAR struct stat *buf);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_STAT_H */
diff --git a/nuttx/include/sys/statfs.h b/nuttx/include/sys/statfs.h
deleted file mode 100644
index 70e963dd9..000000000
--- a/nuttx/include/sys/statfs.h
+++ /dev/null
@@ -1,145 +0,0 @@
-/****************************************************************************
- * include/sys/statfs.h
- *
- * Copyright (C) 2007-2009, 2011 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_SYS_STATFS_H
-#define __INCLUDE_SYS_STATFS_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* struct statfs file system types. */
-
-#define ADFS_SUPER_MAGIC 0xadf5
-#define AFFS_SUPER_MAGIC 0xadff
-#define BEFS_SUPER_MAGIC 0x42465331
-#define BFS_MAGIC 0x1badface
-#define CIFS_MAGIC_NUMBER 0xff534d42
-#define CODA_SUPER_MAGIC 0x73757245
-#define COH_SUPER_MAGIC 0x012ff7b7
-#define CRAMFS_MAGIC 0x28cd3d45
-#define DEVFS_SUPER_MAGIC 0x1373
-#define EFS_SUPER_MAGIC 0x00414a53
-#define EXT_SUPER_MAGIC 0x137d
-#define EXT2_OLD_SUPER_MAGIC 0xef51
-#define EXT2_SUPER_MAGIC 0xef53
-#define EXT3_SUPER_MAGIC 0xef53
-#define HFS_SUPER_MAGIC 0x4244
-#define HPFS_SUPER_MAGIC 0xf995e849
-#define HUGETLBFS_MAGIC 0x958458f6
-#define ISOFS_SUPER_MAGIC 0x9660
-#define JFFS2_SUPER_MAGIC 0x72b6
-#define JFS_SUPER_MAGIC 0x3153464a
-#define MINIX_SUPER_MAGIC 0x137f /* orig. minix */
-#define MINIX_SUPER_MAGIC2 0x138f /* 30 char minix */
-#define MINIX2_SUPER_MAGIC 0x2468 /* minix V2 */
-#define MINIX2_SUPER_MAGIC2 0x2478 /* minix V2, 30 char names */
-#define MSDOS_SUPER_MAGIC 0x4d44
-#define NCP_SUPER_MAGIC 0x564c
-#define NFS_SUPER_MAGIC 0x6969
-#define NTFS_SB_MAGIC 0x5346544e
-#define OPENPROM_SUPER_MAGIC 0x9fa1
-#define PROC_SUPER_MAGIC 0x9fa0
-#define QNX4_SUPER_MAGIC 0x002f
-#define REISERFS_SUPER_MAGIC 0x52654973
-#define ROMFS_MAGIC 0x7275
-#define SMB_SUPER_MAGIC 0x517B
-#define SYSV2_SUPER_MAGIC 0x012ff7b6
-#define SYSV4_SUPER_MAGIC 0x012FF7B5
-#define TMPFS_MAGIC 0x01021994
-#define UDF_SUPER_MAGIC 0x15013346
-#define UFS_MAGIC 0x00011954
-#define USBDEVICE_SUPER_MAGIC 0x9fa2
-#define VXFS_SUPER_MAGIC 0xa501fcf5
-#define XENIX_SUPER_MAGIC 0x012ff7b4
-#define XFS_SUPER_MAGIC 0x58465342
-#define _XIAFS_SUPER_MAGIC 0x012fd16d
-
-/* NuttX specific file-systems */
-
-#define BINFS_MAGIC 0x4242
-#define NXFFS_MAGIC 0x4747
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
-struct statfs
-{
- uint32_t f_type; /* Type of filesystem (see definitions above) */
- size_t f_namelen; /* Maximum length of filenames */
- size_t f_bsize; /* Optimal block size for transfers */
- off_t f_blocks; /* Total data blocks in the file system of this size */
- off_t f_bfree; /* Free blocks in the file system */
- off_t f_bavail; /* Free blocks avail to non-superuser */
- off_t f_files; /* Total file nodes in the file system */
- off_t f_ffree; /* Free file nodes in the file system */
-};
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* Inspired by Linux statfs() which was, in turn, inspired by
- * the BSD statfs(). None of these implementations agree in the
- * form of the struct statfs.
- */
-
-EXTERN int statfs(const char *path, struct statfs *buf);
-EXTERN int fstatfs(int fd, struct statfs *buf);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_STATFS_H */
diff --git a/nuttx/include/sys/syscall.h b/nuttx/include/sys/syscall.h
deleted file mode 100644
index 57545beb7..000000000
--- a/nuttx/include/sys/syscall.h
+++ /dev/null
@@ -1,398 +0,0 @@
-/****************************************************************************
- * include/sys/syscall.h
- * This file contains the system call numbers.
- *
- * Copyright (C) 2011-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_SYS_SYSCALL_H
-#define __INCLUDE_SYS_SYSCALL_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#ifndef __ASSEMBLY__
-# include <stdint.h>
-#endif
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Reserve the first system calls for platform-specific usage if so
- * configured.
- */
-
-#ifndef CONFIG_SYS_RESERVED
-# define CONFIG_SYS_RESERVED (0)
-#endif
-
-/* System call numbers
- *
- * These first system calls are supported regardless of the NuttX
- * configuration
- */
-
-#define SYS__exit (CONFIG_SYS_RESERVED+0)
-#define SYS_exit (CONFIG_SYS_RESERVED+1)
-#define SYS_get_errno (CONFIG_SYS_RESERVED+2)
-#define SYS_getpid (CONFIG_SYS_RESERVED+3)
-#define SYS_sched_getparam (CONFIG_SYS_RESERVED+4)
-#define SYS_sched_getscheduler (CONFIG_SYS_RESERVED+5)
-#define SYS_sched_lock (CONFIG_SYS_RESERVED+6)
-#define SYS_sched_lockcount (CONFIG_SYS_RESERVED+7)
-#define SYS_sched_rr_get_interval (CONFIG_SYS_RESERVED+8)
-#define SYS_sched_setparam (CONFIG_SYS_RESERVED+9)
-#define SYS_sched_setscheduler (CONFIG_SYS_RESERVED+10)
-#define SYS_sched_unlock (CONFIG_SYS_RESERVED+11)
-#define SYS_sched_yield (CONFIG_SYS_RESERVED+12)
-#define SYS_sem_close (CONFIG_SYS_RESERVED+13)
-#define SYS_sem_destroy (CONFIG_SYS_RESERVED+14)
-#define SYS_sem_open (CONFIG_SYS_RESERVED+15)
-#define SYS_sem_post (CONFIG_SYS_RESERVED+16)
-#define SYS_sem_trywait (CONFIG_SYS_RESERVED+17)
-#define SYS_sem_unlink (CONFIG_SYS_RESERVED+18)
-#define SYS_sem_wait (CONFIG_SYS_RESERVED+19)
-#define SYS_set_errno (CONFIG_SYS_RESERVED+20)
-#define SYS_task_create (CONFIG_SYS_RESERVED+21)
-#define SYS_task_delete (CONFIG_SYS_RESERVED+22)
-#define SYS_task_restart (CONFIG_SYS_RESERVED+23)
-#define SYS_up_assert (CONFIG_SYS_RESERVED+24)
-#define SYS_up_assert_code (CONFIG_SYS_RESERVED+25)
-#define __SYS_atexit (CONFIG_SYS_RESERVED+26)
-
-/* The following can be individually enabled */
-
-#ifdef CONFIG_SCHED_ATEXIT
-# define SYS_atexit __SYS_atexit
-# define __SYS_onexit (__SYS_atexit+1)
-#else
-# define __SYS_onexit __SYS_atexit
-#endif
-
-#ifdef CONFIG_SCHED_ONEXIT
-# define SYS_onexit __SYS_onexit
-# define __SYS_waitpaid (__SYS_onexit+1)
-#else
-# define __SYS_waitpaid __SYS_onexit
-#endif
-
-#ifdef CONFIG_SCHED_WAITPID
-# define SYS_waitpid __SYS_waitpaid
-# define __SYS_signals (__SYS_waitpaid+1)
-#else
-# define __SYS_signals __SYS_waitpaid
-#endif
-
-/* The following are only defined is signals are supported in the NuttX
- * configuration.
- */
-
-#ifndef CONFIG_DISABLE_SIGNALS
-# define SYS_kill (__SYS_signals+0)
-# define SYS_sigaction (__SYS_signals+1)
-# define SYS_sigpending (__SYS_signals+2)
-# define SYS_sigprocmask (__SYS_signals+3)
-# define SYS_sigqueue (__SYS_signals+4)
-# define SYS_sigsuspend (__SYS_signals+5)
-# define SYS_sigtimedwait (__SYS_signals+6)
-# define SYS_sigwaitinfo (__SYS_signals+7)
-# define SYS_sleep (__SYS_signals+8)
-# define SYS_usleep (__SYS_signals+9)
-# define __SYS_clock (__SYS_signals+10)
-#else
-# define __SYS_clock __SYS_signals
-#endif
-
-/* The following are only defined if the system clock is enabled in the
- * NuttX configuration.
- */
-
-#ifndef CONFIG_DISABLE_CLOCK
-# define SYS_clock_systimer (__SYS_clock+0)
-# define SYS_clock_getres (__SYS_clock+1)
-# define SYS_clock_gettime (__SYS_clock+2)
-# define SYS_clock_settime (__SYS_clock+3)
-# define SYS_gettimeofday (__SYS_clock+4)
-# define __SYS_timers (__SYS_clock+5)
-#else
-# define __SYS_timers __SYS_clock
-#endif
-
-/* The following are defined only if POSIX timers are supported */
-
-#ifndef CONFIG_DISABLE_POSIX_TIMERS
-# define SYS_timer_create (__SYS_timers+0)
-# define SYS_timer_delete (__SYS_timers+1)
-# define SYS_timer_getoverrun (__SYS_timers+2)
-# define SYS_timer_gettime (__SYS_timers+3)
-# define SYS_timer_settime (__SYS_timers+4)
-# define __SYS_descriptors (__SYS_timers+5)
-#else
-# define __SYS_descriptors __SYS_timers
-#endif
-
-/* The following are defined if either file or socket descriptor are
- * enabled.
- */
-
-#ifndef CONFIG_NET
-# undef CONFIG_NSOCKET_DESCRIPTORS
-# define CONFIG_NSOCKET_DESCRIPTORS 0
-#endif
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
-# define SYS_close (__SYS_descriptors+0)
-# define SYS_ioctl (__SYS_descriptors+1)
-# define SYS_read (__SYS_descriptors+2)
-# define SYS_write (__SYS_descriptors+3)
-# ifndef CONFIG_DISABLE_POLL
-# define SYS_poll (__SYS_descriptors+4)
-# define SYS_select (__SYS_descriptors+5)
-# define __SYS_filedesc (__SYS_descriptors+6)
-# else
-# define __SYS_filedesc (__SYS_descriptors+4)
-# endif
-#else
-# define __SYS_filedesc __SYS_descriptors
-#endif
-
-/* The following are defined if file descriptors are enabled */
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
-# define SYS_closedir (__SYS_filedesc+0)
-# define SYS_dup (__SYS_filedesc+1)
-# define SYS_dup2 (__SYS_filedesc+2)
-# define SYS_fcntl (__SYS_filedesc+3)
-# define SYS_lseek (__SYS_filedesc+4)
-# define SYS_mkfifo (__SYS_filedesc+5)
-# define SYS_mmap (__SYS_filedesc+6)
-# define SYS_open (__SYS_filedesc+7)
-# define SYS_opendir (__SYS_filedesc+8)
-# define SYS_pipe (__SYS_filedesc+9)
-# define SYS_readdir (__SYS_filedesc+10)
-# define SYS_rewinddir (__SYS_filedesc+11)
-# define SYS_seekdir (__SYS_filedesc+12)
-# define SYS_stat (__SYS_filedesc+13)
-# define SYS_statfs (__SYS_filedesc+14)
-# define SYS_telldir (__SYS_filedesc+15)
-
-# if CONFIG_NFILE_STREAMS > 0
-# define SYS_fs_fdopen (__SYS_filedesc+16)
-# define SYS_sched_getstreams (__SYS_filedesc+17)
-# define __SYS_mountpoint (__SYS_filedesc+18)
-# else
-# define __SYS_mountpoint (__SYS_filedesc+16)
-# endif
-
-# if !defined(CONFIG_DISABLE_MOUNTPOINT)
-# define SYS_fsync (__SYS_mountpoint+0)
-# define SYS_mkdir (__SYS_mountpoint+1)
-# define SYS_mount (__SYS_mountpoint+2)
-# define SYS_rename (__SYS_mountpoint+3)
-# define SYS_rmdir (__SYS_mountpoint+4)
-# define SYS_umount (__SYS_mountpoint+5)
-# define SYS_unlink (__SYS_mountpoint+6)
-# define __SYS_pthread (__SYS_mountpoint+7)
-# else
-# define __SYS_pthread __SYS_mountpoint
-# endif
-
-#else
-# define __SYS_pthread __SYS_filedesc
-#endif
-
-/* The following are defined if pthreads are enabled */
-
-#ifndef CONFIG_DISABLE_PTHREAD
-# define SYS_pthread_barrier_destroy (__SYS_pthread+0)
-# define SYS_pthread_barrier_init (__SYS_pthread+1)
-# define SYS_pthread_barrier_wait (__SYS_pthread+2)
-# define SYS_pthread_cancel (__SYS_pthread+3)
-# define SYS_pthread_cond_broadcast (__SYS_pthread+4)
-# define SYS_pthread_cond_destroy (__SYS_pthread+5)
-# define SYS_pthread_cond_init (__SYS_pthread+6)
-# define SYS_pthread_cond_signal (__SYS_pthread+7)
-# define SYS_pthread_cond_wait (__SYS_pthread+8)
-# define SYS_pthread_create (__SYS_pthread+9)
-# define SYS_pthread_detach (__SYS_pthread+10)
-# define SYS_pthread_exit (__SYS_pthread+11)
-# define SYS_pthread_getschedparam (__SYS_pthread+12)
-# define SYS_pthread_getspecific (__SYS_pthread+13)
-# define SYS_pthread_join (__SYS_pthread+14)
-# define SYS_pthread_key_create (__SYS_pthread+15)
-# define SYS_pthread_key_delete (__SYS_pthread+16)
-# define SYS_pthread_mutex_destroy (__SYS_pthread+17)
-# define SYS_pthread_mutex_init (__SYS_pthread+18)
-# define SYS_pthread_mutex_lock (__SYS_pthread+19)
-# define SYS_pthread_mutex_trylock (__SYS_pthread+20)
-# define SYS_pthread_mutex_unlock (__SYS_pthread+21)
-# define SYS_pthread_once (__SYS_pthread+22)
-# define SYS_pthread_setcancelstate (__SYS_pthread+23)
-# define SYS_pthread_setschedparam (__SYS_pthread+24)
-# define SYS_pthread_setschedprio (__SYS_pthread+25)
-# define SYS_pthread_setspecific (__SYS_pthread+26)
-# define SYS_pthread_yield (__SYS_pthread+27)
-
-# ifndef CONFIG_DISABLE_SIGNAL
-# define SYS_pthread_cond_timedwait (__SYS_pthread+28)
-# define SYS_pthread_kill (__SYS_pthread+29)
-# define SYS_pthread_sigmask (__SYS_pthread+30)
-# define __SYS_mqueue (__SYS_pthread+31)
-# else
-# define __SYS_mqueue (__SYS_pthread+28)
-# endif
-
-#else
-# define __SYS_mqueue __SYS_pthread
-#endif
-
-/* The following are defined only if message queues are enabled */
-
-#ifndef CONFIG_DISABLE_MQUEUE
-# define SYS_mq_close (__SYS_mqueue+0)
-# define SYS_mq_notify (__SYS_mqueue+1)
-# define SYS_mq_open (__SYS_mqueue+2)
-# define SYS_mq_receive (__SYS_mqueue+3)
-# define SYS_mq_send (__SYS_mqueue+4)
-# define SYS_mq_timedreceive (__SYS_mqueue+5)
-# define SYS_mq_timedsend (__SYS_mqueue+6)
-# define SYS_mq_unlink (__SYS_mqueue+7)
-# define __SYS_environ (__SYS_mqueue+8)
-#else
-# define __SYS_environ __SYS_mqueue
-#endif
-
-/* The following are defined only if environment variables are supported */
-
-#ifndef CONFIG_DISABLE_ENVIRON
-# define SYS_clearenv (__SYS_environ+0)
-# define SYS_getenv (__SYS_environ+1)
-# define SYS_putenv (__SYS_environ+2)
-# define SYS_setenv (__SYS_environ+3)
-# define SYS_unsetenv (__SYS_environ+4)
-# define __SYS_network (__SYS_environ+5)
-#else
-# define __SYS_network __SYS_environ
-#endif
-
-/* The following are defined only if networking AND sockets are supported */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)
-# define SYS_accept (__SYS_network+0)
-# define SYS_bind (__SYS_network+1)
-# define SYS_connect (__SYS_network+2)
-# define SYS_getsockopt (__SYS_network+3)
-# define SYS_listen (__SYS_network+4)
-# define SYS_recv (__SYS_network+5)
-# define SYS_recvfrom (__SYS_network+6)
-# define SYS_send (__SYS_network+7)
-# define SYS_sendto (__SYS_network+8)
-# define SYS_setsockopt (__SYS_network+9)
-# define SYS_socket (__SYS_network+10)
-# define SYS_nnetsocket (__SYS_network+11)
-#else
-# define SYS_nnetsocket __SYS_network
-#endif
-
-/* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */
-
-#if CONFIG_TASK_NAME_SIZE > 0
-# define SYS_prctl (SYS_nnetsocket+0)
-# define SYS_maxsyscall (SYS_nnetsocket+1)
-#else
-# define SYS_maxsyscall SYS_nnetsocket
-#endif
-
-/* Note that the reported number of system calls does *NOT* include the
- * architecture-specific system calls. If the "real" total is required,
- * use SYS_maxsyscall.
- */
-
-#define SYS_nsyscalls (SYS_maxsyscall-CONFIG_SYS_RESERVED)
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/* This is the union of all possible stub function types */
-
-union syscall_stubfunc_u
-{
- uintptr_t (*stub0)(void);
- uintptr_t (*stub1)(uintptr_t parm1);
- uintptr_t (*stub2)(uintptr_t parm1, uintptr_t parm2);
- uintptr_t (*stub3)(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
- uintptr_t (*stub4)(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3,
- uintptr_t parm4);
- uintptr_t (*stub5)(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3,
- uintptr_t parm4, uintptr_t parm5);
- uintptr_t (*stub6)(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3,
- uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-};
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* Stub lookup tables. Each table is indexed by the system call numbers
- * defined above. Given the system call number, the corresponding entry in
- * these tables describes how to call the stub dispatch function.
- */
-
-EXTERN const union syscall_stubfunc_u g_stublookup[SYS_nsyscalls];
-EXTERN const uint8_t g_stubnparms[SYS_nsyscalls];
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-#undef EXTERN
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif /* __INCLUDE_SYS_SYSCALL_H */
-
diff --git a/nuttx/include/sys/time.h b/nuttx/include/sys/time.h
deleted file mode 100644
index 75dfd7280..000000000
--- a/nuttx/include/sys/time.h
+++ /dev/null
@@ -1,74 +0,0 @@
-/****************************************************************************
- * include/sys/time.h
- *
- * Copyright (C) 2009 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_SYS_TIME_H
-#define __INCLUDE_SYS_TIME_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <time.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN int gettimeofday(struct timeval *tp, FAR void *tzp);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_TIME_H */
diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h
deleted file mode 100644
index 38f091e8a..000000000
--- a/nuttx/include/sys/types.h
+++ /dev/null
@@ -1,234 +0,0 @@
-/****************************************************************************
- * include/sys/types.h
- *
- * Copyright (C) 2007-2009, 2011-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_SYS_TYPES_H
-#define __INCLUDE_SYS_TYPES_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-
-#ifndef __ASSEMBLY__
-# include <stdint.h>
-#endif
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Alternative values for type bool (for historic reasons) */
-
-#ifndef TRUE
-# define TRUE 1
-#endif
-#ifndef FALSE
-# define FALSE 0
-#endif
-
-/* NULL is usually defined in stddef.h (which includes this file) */
-
-#ifndef NULL
- /* SDCC is sensitive to NULL pointer type conversions, and C++ defines
- * NULL as zero
- */
-
-# if defined(SDCC) || defined(__cplusplus)
-# define NULL (0)
-# else
-# define NULL ((void*)0)
-# endif
-#endif
-
-/* POSIX-like OS return values: */
-
-#if !defined(__cplusplus)
-# undef ERROR
-# define ERROR -1
-#endif
-
-#undef OK
-#define OK 0
-
-/* HPUX-like MIN/MAX value */
-
-#define PRIOR_RR_MIN 0
-#define PRIOR_RR_MAX 255
-#define PRIOR_FIFO_MIN 0
-#define PRIOR_FIFO_MAX 255
-#define PRIOR_OTHER_MIN 0
-#define PRIOR_OTHER_MAX 255
-
-/* Scheduling Priorities. NOTE: Only the idle task can take
- * the true minimum priority. */
-
-#define SCHED_PRIORITY_MAX 255
-#define SCHED_PRIORITY_DEFAULT 100
-#define SCHED_PRIORITY_MIN 1
-#define SCHED_PRIORITY_IDLE 0
-
-/****************************************************************************
- * Type Declarations
- ****************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/* Floating point types */
-
-typedef float float32;
-#ifndef CONFIG_HAVE_DOUBLE
-typedef float double_t;
-typedef float float64;
-#else
-typedef double double_t;
-typedef double float64;
-#endif
-
-/* Misc. scalar types */
-
-/* mode_t is an integer type used for file attributes. mode_t needs
- * to be at least 16-bits but, in fact must be sizeof(int) because it is
- * pased via varargs.
- */
-
-typedef unsigned int mode_t;
-
-/* size_t is used for sizes of memory objects.
- * ssize_t is used for a count of bytes or an error indication.
- */
-
-#ifdef CONFIG_SMALL_MEMORY
-typedef uint16_t size_t;
-typedef int16_t ssize_t;
-#else
-typedef uint32_t size_t;
-typedef int32_t ssize_t;
-#endif
-
-/* uid_t is used for user IDs
- * gid_t is used for group IDs.
- */
-
-typedef int16_t uid_t;
-typedef int16_t gid_t;
-
-/* dev_t is used for device IDs */
-
-typedef uint16_t dev_t;
-
-/* ino_t is used for file serial numbers */
-
-typedef uint16_t ino_t;
-
-/* 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 int16_t pid_t;
-
-/* id_t is a general identifier that can be used to contain at least a pid_t,
- * uid_t, or gid_t.
- */
-
-typedef int16_t id_t;
-
-/* Signed integral type of the result of subtracting two pointers */
-
-typedef intptr_t ptrdiff_t;
-
-/* Wide, 16-bit character types. wchar_t is a built-in type in C++ and
- * its declaration here may cause compilation errors on some compilers
- * if -DCONFIG_WCHAR_BUILTIN is not included in the CXXFLAGS.
- */
-
-#ifndef CONFIG_WCHAR_BUILTIN
-typedef uint16_t wchar_t;
-#endif
-
-/* blkcnt_t and off_t are signed integer types.
- *
- * blkcnt_t is used for file block counts.
- * off_t is used for file offsets and sizes.
- * fpos_t is used for file positions.
- *
- * Hence, all should be independent of processor architecture.
- */
-
-typedef uint32_t blkcnt_t;
-typedef int32_t off_t;
-typedef off_t fpos_t;
-
-/* Large file versions */
-
-#ifdef CONFIG_HAVE_LONG_LONG
-typedef int64_t off64_t;
-typedef int64_t fpos64_t;
-#endif
-
-/* blksize_t is a signed integer value used for file block sizes */
-
-typedef int16_t blksize_t;
-
-/* Network related */
-
-typedef unsigned int socklen_t;
-typedef uint16_t sa_family_t;
-
-/* Used for system times in clock ticks */
-
-typedef uint32_t clock_t;
-
-/* The type useconds_t shall be an unsigned integer type capable of storing
- * values at least in the range [0, 1000000]. The type suseconds_t shall be
- * a signed integer type capable of storing values at least in the range
- * [-1, 1000000].
- */
-
-typedef uint32_t useconds_t;
-typedef int32_t suseconds_t;
-
-/* Task entry point */
-
-typedef int (*main_t)(int argc, char *argv[]);
-
-#endif
-
-/****************************************************************************
- * Global Function Prototypes
- ****************************************************************************/
-
-#endif /* __INCLUDE_SYS_TYPES_H */
diff --git a/nuttx/include/sys/vfs.h b/nuttx/include/sys/vfs.h
deleted file mode 100644
index 8433893c3..000000000
--- a/nuttx/include/sys/vfs.h
+++ /dev/null
@@ -1,61 +0,0 @@
-/****************************************************************************
- * include/sys/vfs.h
- *
- * Copyright (C) 2007, 2008 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_SYS_VFS_H
-#define __INCLUDE_SYS_VFS_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/* sys/vfs.h is just an alternative location for the information in
- * sys/statfs.h.
- */
-
-#include <sys/statfs.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#endif /* __INCLUDE_SYS_VFS_H */
diff --git a/nuttx/include/sys/wait.h b/nuttx/include/sys/wait.h
deleted file mode 100644
index 2476adef9..000000000
--- a/nuttx/include/sys/wait.h
+++ /dev/null
@@ -1,118 +0,0 @@
-/****************************************************************************
- * include/sys/wait.h
- *
- * 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
- * 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_SYS_WAIT_H
-#define __INCLUDE_SYS_WAIT_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <sys/types.h>
-#include <signal.h>
-
-#ifdef CONFIG_SCHED_WAITPID
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* The following are provided for analysis of returned status values.
- * Encoded is as follows as 2 bytes of info(MS) then two bytes of code (LS).
- * Code:
- * 0 - Child has exited, info is the exit code.
- * Other values - Not implemented
- */
-
-#define WEXITSTATUS(s) (((s) >> 8) & 0xff)/* Return exit status */
-
-#define WIFEXITED(s) (((s) & 0xff) == 0) /* True: Child exited normally */
-#define WIFCONTINUED(s) (false) /* True: Child has been continued */
-#define WIFSIGNALED(s) (false) /* True: Child exited due to uncaught signal */
-#define WIFSTOPPED(s) (false) /* True: Child is currently stopped */
-#define WSTOPSIG(s) (false) /* Return signal number that caused process to stop */
-#define WTERMSIG(s) (false) /* Return signal number that caused process to terminate */
-
-/* The following symbolic constants are possible values for the options
- * argument to waitpid() (1) and/or waitid() (2),
- */
-
-#define WCONTINUED (1 << 0) /* Status for child that has been continued (1)(2) */
-#define WNOHANG (1 << 1) /* Do not wait if status not available (1) */
-#define WUNTRACED (1 << 2) /* Report status of stopped child process (1) */
-
-#define WEXITED (1 << 3) /* Wait for processes that have exited (2) */
-#define WSTOPPED (1 << 4) /* Status for child stopped on signal (2) */
-#define WNOHANG (1 << 5) /* Return immediately if there are no children (2) */
-#define WNOWAIT (1 << 6) /* Keep the process in a waitable state (2) */
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-enum idtype_e
-{
- P_PID = 1,
- P_GID = 2,
- P_ALL = 3
-};
-typedef enum idtype_e idtype_t;
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-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)
-}
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif /* CONFIG_SCHED_WAITPID */
-#endif /* __INCLUDE_SYS_WAIT_H */