summaryrefslogtreecommitdiff
path: root/nuttx/include/sys
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-22 09:29:37 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-22 09:29:37 -0600
commit47b371c98a73442dcf41a4aaaf0242cd565df80e (patch)
treef8e6414216648292a02c54279fe1e17db7bcebe1 /nuttx/include/sys
parenteef91d4aab7324def03a9b7262abb1b8f30218d2 (diff)
downloadpx4-nuttx-47b371c98a73442dcf41a4aaaf0242cd565df80e.tar.gz
px4-nuttx-47b371c98a73442dcf41a4aaaf0242cd565df80e.tar.bz2
px4-nuttx-47b371c98a73442dcf41a4aaaf0242cd565df80e.zip
Add shared memory definitions, types, prototypes
Diffstat (limited to 'nuttx/include/sys')
-rw-r--r--nuttx/include/sys/ipc.h109
-rw-r--r--nuttx/include/sys/mman.h91
-rw-r--r--nuttx/include/sys/shm.h113
-rw-r--r--nuttx/include/sys/types.h7
4 files changed, 313 insertions, 7 deletions
diff --git a/nuttx/include/sys/ipc.h b/nuttx/include/sys/ipc.h
new file mode 100644
index 000000000..e30e59986
--- /dev/null
+++ b/nuttx/include/sys/ipc.h
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * include/sys/ipc.h
+ *
+ * Copyright (C) 2014 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_IPC_H
+#define __INCLUDE_SYS_IPC_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Mode bits: */
+
+#define IPC_CREAT 0x01 /* Create entry if key does not exist */
+#define IPC_EXCL 0x02 /* Fail if key exists */
+#define IPC_NOWAIT 0x04 /* Error if request must wait */
+
+/* Keys: */
+
+#define IPC_PRIVATE 0 /* Private key */
+
+/* Control commands: */
+
+#define IPC_RMID 0 /* Remove identifier */
+#define IPC_SET 1 /* Set options */
+#define IPC_STAT 2 /* Get options */
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/* The ipc_perm structure is used by three mechanisms for XSI interprocess
+ * communication (IPC): messages, semaphores, and shared memory. All use a
+ * common structure type, ipc_perm, to pass information used in determining
+ * permission to perform an IPC operation.
+ */
+
+struct ipc_perm
+{
+ uid_t uid /* Owner's user ID */
+ gid_t gid /* Owner's group ID */
+ uid_t cuid /* Creator's user ID */
+ gid_t cgid /* Creator's group ID */
+ mode_t mode /* Read/write permission */
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+key_t ftok(FAR const char *path, int id);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_SYS_IPC_H */
diff --git a/nuttx/include/sys/mman.h b/nuttx/include/sys/mman.h
index ab847b97a..7acf90a0e 100644
--- a/nuttx/include/sys/mman.h
+++ b/nuttx/include/sys/mman.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/sys/mman.h
*
- * Copyright (C) 2008, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008, 2009, 2011, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,7 +48,7 @@
****************************************************************************/
/* Protections are chosen from these bits, OR'd together. NuttX does not
- * support any of these, but are provided for source level compatibility
+ * yet support any of these, but are provided for source level compatibility
*/
#define PROT_NONE 0x0 /* Page may not be accessed */
@@ -80,31 +80,108 @@
#define MAP_FAILED ((void*)-1)
+/* The following flags are used with msync() */
+
+#define MS_ASYNC 0x01 /* Perform asynchronous writes */
+#define MS_SYNC 0x02 /* Perform synchronous writes */
+#define MS_INVALIDATE 0x04 /* Invalidate mapping */
+
+/* The following flags are used with mlockall() */
+
+#define MCL_CURRENT 0x01 /* Lock currently mapped pages */
+#define MCL_FUTURE 0x02 /* Lock pages that become mapped */
+
+/* If the Advisory Information and either the Memory Mapped Files or Shared
+ * Memory Objects options are supported, values for advice used by
+ * posix_madvise() are defined as follows:
+ *
+ * POSIX_MADV_NORMAL
+ * The application has no advice to give on its behavior with respect to
+ * the specified range. It is the default characteristic if no advice is
+ * given for a range of memory.
+ * POSIX_MADV_SEQUENTIAL
+ * The application expects to access the specified range sequentially from
+ * lower addresses to higher addresses.
+ * POSIX_MADV_RANDOM
+ * The application expects to access the specified range in a random order.
+ * POSIX_MADV_WILLNEED
+ * The application expects to access the specified range in the near
+ * future.
+ * POSIX_MADV_DONTNEED
+ * The application expects that it will not access the specified range in
+ * the near future.
+ */
+
+#define POSIX_MADV_NORMAL (0)
+#define POSIX_MADV_SEQUENTIAL (1)
+#define POSIX_MADV_RANDOM (2)
+#define POSIX_MADV_WILLNEED (3)
+#define POSIX_MADV_DONTNEED (4)
+
+/* The following flags are defined for posix_typed_mem_open():
+ *
+ * POSIX_TYPED_MEM_ALLOCATE
+ * Allocate on mmap().
+ * POSIX_TYPED_MEM_ALLOCATE_CONTIG
+ * Allocate contiguously on mmap().
+ * POSIX_TYPED_MEM_MAP_ALLOCATABLE
+ * Map on mmap(), without affecting allocatability.
+ */
+
+#define POSIX_TYPED_MEM_ALLOCATE (0)
+#define POSIX_TYPED_MEM_ALLOCATE_CONTIG (1)
+#define POSIX_TYPED_MEM_MAP_ALLOCATABLE (2)
+
/****************************************************************************
* Public Type Definitions
****************************************************************************/
+struct posix_typed_mem_info
+{
+ size_t posix_tmi_length; /* Maximum length which may be allocated from a
+ * typed memory object */
+};
+
/****************************************************************************
- * Public Function Prototypes
+ * Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-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);
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+int mlock(FAR const void *addr, size_t len);
+int mlockall(int flags);
+FAR void *mmap(FAR void *start, size_t length, int prot, int flags, int fd,
+ off_t offset);
+int mprotect(FAR void *addr, size_t len, int prot);
+int msync(FAR void *addr, size_t len, int flags);
+int munlock(FAR const void *addr, size_t len);
+int munlockall(void);
#ifdef CONFIG_FS_RAMMAP
-EXTERN int munmap(FAR void *start, size_t length);
+int munmap(FAR void *start, size_t length);
#else
# define munmap(start, length)
#endif
+int posix_madvise(FAR void *addr, size_t len, int advice);
+int posix_mem_offset(FAR const void *addr, size_t len, FAR off_t *off,
+ FAR size_t *contig_len, FAR int *fildes);
+int posix_typed_mem_get_info(int fildes, FAR struct posix_typed_mem_info *info);
+int posix_typed_mem_open(FAR const char *name, int oflag, int tflag);
+int shm_open(FAR const char *name, int oflag, mode_t mode);
+int shm_unlink(FAR const char *name);
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/include/sys/shm.h b/nuttx/include/sys/shm.h
new file mode 100644
index 000000000..99faf2251
--- /dev/null
+++ b/nuttx/include/sys/shm.h
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * include/sys/shm.h
+ *
+ * Copyright (C) 2014 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_SHM_H
+#define __INCLUDE_SYS_SHM_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/ipc.h>
+#include <time.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#define SHM_RDONLY 0x01 /* Attach read-only (else read-write) */
+#defube SHM_RND 0x02 /* Round attach address to SHMLBA */
+
+/* Segment low boundary address multiple */
+
+#ifdef CONFIG_SHM_SHMLBA
+# define SHMLBA CONFIG_SHM_SHMLBA
+#else
+# define SHMLBA 0x0
+#endif
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/* Unsigned integer used for the number of current attaches that must be
+ * able to store values at least as large as a type unsigned short.
+ */
+
+typedef unsigned short shmatt_t;
+
+struct shmid_ds
+{
+ struct ipc_perm shm_perm; /* Operation permission structure */
+ size_t shm_segsz; /* Size of segment in bytes */
+ pid_t shm_lpid; /* Process ID of last shared memory operation */
+ pid_t shm_cpid; /* Process ID of creator */
+ shmatt_t shm_nattch; /* Number of current attaches */
+ time_t shm_atime; /* Time of last shmat() */
+ time_t shm_dtime; /* Time of last shmdt() */
+ time_t shm_ctime; /* Time of last change by shmctl() */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+FAR void *shmat(int shmid, FAR const void *shmaddr, int shmflg);
+int shmctl(int shmid, int cmd, FAR struct shmid_ds *buf);
+int shmdt(FAR const void *shmaddr);
+int shmget(key_t key, size_t size, int shmflg);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_SYS_SHM_H */
diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h
index 9726e3450..530434b22 100644
--- a/nuttx/include/sys/types.h
+++ b/nuttx/include/sys/types.h
@@ -175,6 +175,13 @@ typedef int16_t pid_t;
typedef int16_t id_t;
+/* Unix requires a key of type key_t defined in file sys/types.h for requesting
+ * resources such as shared memory segments, message queues and semaphores. A key
+ * is simply an integer of type key_t
+ */
+
+typedef int16_t key_t;
+
/* Signed integral type of the result of subtracting two pointers */
typedef intptr_t ptrdiff_t;