summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-10 23:42:49 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-10 23:42:49 +0000
commit6157a0e4fd667b835dc74d291019dd61840213cd (patch)
tree029c000a13501c7904b1c5afa38ac99928540dac /nuttx/include
parentf6fffbd5b0a83bd161e8f6417a4d034f72268217 (diff)
downloadpx4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.tar.gz
px4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.tar.bz2
px4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.zip
Remove user_map.h; replace with a header at the beginning of the user-space blob. User work queue no started by os_brinup() on behalf of the application
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5727 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/kmalloc.h62
-rw-r--r--nuttx/include/nuttx/userspace.h155
2 files changed, 193 insertions, 24 deletions
diff --git a/nuttx/include/nuttx/kmalloc.h b/nuttx/include/nuttx/kmalloc.h
index baf84ea2f..40b12f0fb 100644
--- a/nuttx/include/nuttx/kmalloc.h
+++ b/nuttx/include/nuttx/kmalloc.h
@@ -46,6 +46,7 @@
#include <stdlib.h>
#include <nuttx/mm.h>
+#include <nuttx/userspace.h>
#if !defined(CONFIG_NUTTX_KERNEL) || defined(__KERNEL__)
@@ -76,15 +77,21 @@ extern "C"
*/
/* This familiy of allocators is used to manage user-accessible memory
- * from the kernel.
+ * from the kernel. In the flat build, the following are declared in
+ * stdlib.h and are directly callable. In the kernel-phase of the kernel
+ * build, the following are defined in userspace.h as macros that call
+ * into user-space via a header at the begining of the user-space blob.
*/
-#ifndef CONFIG_NUTTX_KERNEL
+#define kumm_initialize(h,s) umm_initialize(h,s)
+#define kumm_addregion(h,s) umm_addregion(h,s)
+#define kumm_trysemaphore() umm_trysemaphore()
+#define kumm_givesemaphore() umm_givesemaphore()
-# define kumm_initialize(h,s) umm_initialize(h,s)
-# define kumm_addregion(h,s) umm_addregion(h,s)
-# define kumm_trysemaphore() umm_trysemaphore()
-# define kumm_givesemaphore() umm_givesemaphore()
+#ifndef CONFIG_NUTTX_KERNEL
+/* In the flat build, the following are declared in stdlib.h and are
+ * directly callable.
+ */
# define kumalloc(s) malloc(s)
# define kuzalloc(s) zalloc(s)
@@ -92,24 +99,24 @@ extern "C"
# define kufree(p) free(p)
#else
+/* In the kernel-phase of the kernel build, the following are defined
+ * in userspace.h as macros that call into user-space via a header at
+ * the begining of the user-space blob.
+ */
-/* This familiy of allocators is used to manage kernel protected memory */
-
-void kumm_initialize(FAR void *heap_start, size_t heap_size);
-void kumm_addregion(FAR void *heapstart, size_t heapsize);
-int kumm_trysemaphore(void);
-void kumm_givesemaphore(void);
-
-FAR void *kumalloc(size_t size);
-FAR void *kuzalloc(size_t size);
-FAR void *kurealloc(FAR void *oldmem, size_t newsize);
-void kufree(FAR void *mem);
+# define kumalloc(s) umm_malloc(s)
+# define kuzalloc(s) umm_zalloc(s)
+# define kurealloc(p,s) umm_realloc(p,s)
+# define kufree(p) umm_free(p)
#endif
/* This familiy of allocators is used to manage kernel protected memory */
#ifndef CONFIG_NUTTX_KERNEL
+/* If this is not a kernel build, then these map to the same interfaces
+ * as were used for the user-mode function.
+ */
# define kmm_initialize(h,s) /* Initialization done by kumm_initialize */
# define kmm_addregion(h,s) umm_addregion(h,s)
@@ -122,18 +129,25 @@ void kufree(FAR void *mem);
# define kfree(p) free(p)
#elif !defined(CONFIG_MM_KERNEL_HEAP)
+/* If this the kernel phase of a kernel build, and there are only user-space
+ * allocators, then the following are defined in userspace.h as macros that
+ * call into user-space via a header at the begining of the user-space blob.
+ */
# define kmm_initialize(h,s) /* Initialization done by kumm_initialize */
-# define kmm_addregion(h,s) kumm_addregion(h,s)
-# define kmm_trysemaphore() kumm_trysemaphore()
-# define kmm_givesemaphore() kumm_givesemaphore()
+# define kmm_addregion(h,s) umm_addregion(h,s)
+# define kmm_trysemaphore() umm_trysemaphore()
+# define kmm_givesemaphore() umm_givesemaphore()
-# define kmalloc(s) kumalloc(s)
-# define kzalloc(s) kuzalloc(s)
-# define krealloc(p,s) kurealloc(p,s)
-# define kfree(p) kufree(p)
+# define kmalloc(s) umm_malloc(s)
+# define kzalloc(s) umm_zalloc(s)
+# define krealloc(p,s) umm_realloc(p,s)
+# define kfree(p) umm_free(p)
#else
+/* Otherwise, the kernel-space allocators are declared here and we can call
+ * them directly.
+ */
void kmm_initialize(FAR void *heap_start, size_t heap_size);
void kmm_addregion(FAR void *heapstart, size_t heapsize);
diff --git a/nuttx/include/nuttx/userspace.h b/nuttx/include/nuttx/userspace.h
new file mode 100644
index 000000000..d2192fe5f
--- /dev/null
+++ b/nuttx/include/nuttx/userspace.h
@@ -0,0 +1,155 @@
+/****************************************************************************
+ * include/nuttx/userspace.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_USERSPACE_H
+#define __INCLUDE_NUTTX_USERSPACE_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* If CONFIG_NUTTX_KERNEL, then CONFIG_NUTTX_USERSPACE must be defined to
+ * provide the address where the user-space header can be found in memory.
+ */
+
+#ifndef CONFIG_NUTTX_USERSPACE
+# error "CONFIG_NUTTX_USERSPACE is not defined"
+#endif
+
+/* Let's insist on 4-byte alignment. This alignment may not be required
+ * technically for all platforms. However, neither is it an unreasonable
+ * requirement for any platform.
+ */
+
+#if (CONFIG_NUTTX_USERSPACE & 3) != 0
+# warning "CONFIG_NUTTX_USERSPACE is not aligned to a 4-byte boundary"
+#endif
+
+/* Helper Macros ************************************************************/
+/* This macro is used to access the struct userpace_s header that can be
+ * found at the beginning of the user-space blob.
+ */
+
+#define USERSPACE ((FAR struct userspace_s *)CONFIG_NUTTX_USERSPACE)
+
+/* In user space, these functions are directly callable. In kernel space,
+ * they can be called through the userspace structure.
+ */
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
+# define umm_initialize(b,s) USERSPACE->mm_initialize(b,s)
+# define umm_addregion(b,s) USERSPACE->mm_addregion(b,s)
+# define umm_trysemaphore() USERSPACE->mm_trysemaphore()
+# define umm_givesemaphore() USERSPACE->mm_givesemaphore()
+# define umm_malloc(s) USERSPACE->mm_malloc(s)
+# define umm_zalloc(s) USERSPACE->mm_zalloc(s)
+# define umm_realloc(p,s) USERSPACE->mm_realloc(p,s)
+# define umm_free(p) USERSPACE->mm_free(p)
+#endif
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+/* Every user-space blob starts with a header that provides information about
+ * the blob. The form of that header is provided by struct userspace_s. An
+ * instance of this structure is expected to reside at CONFIG_NUTTX_USERSPACE.
+ */
+
+struct userspace_s
+{
+ /* General memory map */
+
+ main_t us_entrypoint;
+ uintptr_t us_textstart;
+ uintptr_t us_textend;
+ uintptr_t us_datasource;
+ uintptr_t us_datastart;
+ uintptr_t us_dataend;
+ uintptr_t us_bssstart;
+ uintptr_t us_bssend;
+
+ /* Memory manager entry points */
+
+ void (*mm_initialize)(FAR void *heap_start, size_t heap_size);
+ void (*mm_addregion)(FAR void *heap_start, size_t heap_size);
+ int (*mm_trysemaphore)(void);
+ void (*mm_givesemaphore)(void);
+
+ FAR void *(*mm_malloc)(size_t size);
+ FAR void *(*mm_realloc)(FAR void *oldmem, size_t newsize);
+ FAR void *(*mm_zalloc)(size_t size);
+ void (*mm_free)(FAR void *mem);
+
+ /* User-space work queue support */
+
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK)
+ int (*work_usrstart)(void);
+#endif
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_NUTTX_KERNEL */
+#endif /* __INCLUDE_NUTTX_USERSPACE_H */