summaryrefslogtreecommitdiff
path: root/nuttx/mm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-09 21:12:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-09 21:12:20 +0000
commitdda5be5c1fc672b5d9cb3a910b5e0cb0a41046c5 (patch)
tree0af32db840a032a50312791977b7d129def1d5b3 /nuttx/mm
parent2ac33dcffabd9422659c3b013ed8624c09ae90e4 (diff)
downloadpx4-nuttx-dda5be5c1fc672b5d9cb3a910b5e0cb0a41046c5.tar.gz
px4-nuttx-dda5be5c1fc672b5d9cb3a910b5e0cb0a41046c5.tar.bz2
px4-nuttx-dda5be5c1fc672b5d9cb3a910b5e0cb0a41046c5.zip
More changes for a kernel-mode allocator (more to be done)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5724 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/mm')
-rw-r--r--nuttx/mm/Kconfig6
-rw-r--r--nuttx/mm/Makefile13
-rw-r--r--nuttx/mm/kmm_addregion.c113
-rw-r--r--nuttx/mm/kmm_initialize.c113
-rw-r--r--nuttx/mm/kmm_kfree.c110
-rw-r--r--nuttx/mm/kmm_kmalloc.c110
-rw-r--r--nuttx/mm/kmm_krealloc.c111
-rw-r--r--nuttx/mm/kmm_kzalloc.c110
-rw-r--r--nuttx/mm/kmm_semaphore.c140
-rw-r--r--nuttx/mm/mm_initialize.c7
-rw-r--r--nuttx/mm/mm_kernel.c282
-rw-r--r--nuttx/mm/mm_kerneluser.c306
-rw-r--r--nuttx/mm/mm_user.c (renamed from nuttx/mm/umm_semaphore.c)66
-rw-r--r--nuttx/mm/umm_addregion.c81
-rw-r--r--nuttx/mm/umm_initialize.c81
15 files changed, 665 insertions, 984 deletions
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index 991972f32..57b039fa9 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -27,6 +27,12 @@ config MM_KERNEL_HEAP
necessary. If you wish to secure the kernel data as well, then
this option should be selected.
+ The kernel heap size that is used is provided a a platform-specific
+ up_allocate_kheap() interface. This configuration setting is made
+ available to that platform specific code. However, the
+ up_allocate_kheap() interface may chose to ignore this setting if it
+ has a more appropriate heap allocation strategy.
+
config MM_KERNEL_HEAPSIZE
int "Kernal heap size"
default 8192
diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
index 12a237bb7..baae6b4df 100644
--- a/nuttx/mm/Makefile
+++ b/nuttx/mm/Makefile
@@ -35,17 +35,24 @@
-include $(TOPDIR)/Make.defs
+# Core allocator logic
+
ASRCS =
CSRCS = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c
CSRCS += mm_shrinkchunk.c mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c
CSRCS += mm_memalign.c mm_free.c mm_mallinfo.c
-CSRCS += umm_initialize.c umm_addregion.c umm_semaphore.c
+# Allocator instances
+CSRCS += mm_user.c
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CSRCS += mm_kerneluser.c
ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CSRCS += kmm_initialize.c kmm_addregion.c kmm_semaphore.c
-CSRCS += kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
+CSRCS += mm_kernel.c
endif
+endif
+
+# An optional granule allocator
ifeq ($(CONFIG_GRAN),y)
CSRCS += mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c
diff --git a/nuttx/mm/kmm_addregion.c b/nuttx/mm/kmm_addregion.c
deleted file mode 100644
index 979b285ed..000000000
--- a/nuttx/mm/kmm_addregion.c
+++ /dev/null
@@ -1,113 +0,0 @@
-/************************************************************************
- * mm/kmm_addregion.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KADDREGION(h,s) ((kmaddregion_t)CONFIG_USER_MMADDREGION)(h,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kmaddregion_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_addregion
- *
- * Description:
- * This is a simple redirection to the user-space mm_addregion()
- * function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the memory region
- * heap_size - The size (in bytes) if the memory region.
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. mm_addregion() resides in user-space
- * 2. The address of the user space mm_addregion() is provided in
- * user_map.h
- * 3. The user-space mm_addregion() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_addregion(FAR void *heap_start, size_t heap_size)
-{
- return KADDREGION(heap_start, heap_size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_initialize.c b/nuttx/mm/kmm_initialize.c
deleted file mode 100644
index c5f5df05d..000000000
--- a/nuttx/mm/kmm_initialize.c
+++ /dev/null
@@ -1,113 +0,0 @@
-/************************************************************************
- * mm/kmm_initialize.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KINITIALIZE(h,s) ((kminitialize_t)CONFIG_USER_MMINIT)(h,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kminitialize_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_initialize
- *
- * Description:
- * This is a simple redirection to the user-space mm_initialize()
- * function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the (initial) memory region
- * heap_size - The size (in bytes) if the (initial) memory region.
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. mm_initialize() resides in user-space
- * 2. The address of the user space mm_initialize() is provided in
- * user_map.h
- * 3. The user-space mm_initialize() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_initialize(FAR void *heap_start, size_t heap_size)
-{
- return KINITIALIZE(heap_start, heap_size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_kfree.c b/nuttx/mm/kmm_kfree.c
deleted file mode 100644
index c4e31ebfa..000000000
--- a/nuttx/mm/kmm_kfree.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * mm/kmm_kfree.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KFREE(p) ((kfree_t)CONFIG_USER_FREE)(p)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kfree_t)(FAR void *);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kfree
- *
- * Description:
- * This is a simple redirection to the user-space free() function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. free() resides in user-space
- * 2. The address of the user space free() is provided in user_map.h
- * 3. The user-space free() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kfree(FAR void *mem)
-{
- return KFREE(mem);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_kmalloc.c b/nuttx/mm/kmm_kmalloc.c
deleted file mode 100644
index e2c347342..000000000
--- a/nuttx/mm/kmm_kmalloc.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * mm/kmm_kmalloc.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KMALLOC(s) ((kmalloc_t)CONFIG_USER_MALLOC)(s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*kmalloc_t)(size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmalloc
- *
- * Description:
- * This is a simple redirection to the user-space malloc() function.
- *
- * Parameters:
- * size - Size (in bytes) of the memory region to be allocated.
- *
- * Return Value:
- * The address of the allocated memory (NULL on failure to allocate)
- *
- * Assumptions:
- * 1. malloc() resides in user-space
- * 2. The address of the user space malloc() is provided in user_map.h
- * 3. The user-space malloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *kmalloc(size_t size)
-{
- return KMALLOC(size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_krealloc.c b/nuttx/mm/kmm_krealloc.c
deleted file mode 100644
index d5bebff38..000000000
--- a/nuttx/mm/kmm_krealloc.c
+++ /dev/null
@@ -1,111 +0,0 @@
-/************************************************************************
- * mm/kmm_krealloc.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KREALLOC(p,s) ((krealloc_t)CONFIG_USER_REALLOC)(p,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*krealloc_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: krealloc
- *
- * Description:
- * This is a simple redirection to the user-space realloc() function.
- *
- * Parameters:
- * oldmem - The old memory allocated
- * size - Size (in bytes) of the new memory region to be re-allocated.
- *
- * Return Value:
- * The address of the re-allocated memory (NULL on failure to re-allocate)
- *
- * Assumptions:
- * 1. realloc() resides in user-space
- * 2. The address of the user space realloc() is provided in user_map.h
- * 3. The user-space realloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *krealloc(FAR void *oldmem, size_t size)
-{
- return KREALLOC(oldmem, size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_kzalloc.c b/nuttx/mm/kmm_kzalloc.c
deleted file mode 100644
index 4775312c6..000000000
--- a/nuttx/mm/kmm_kzalloc.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * mm/kmm_kzalloc.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KZALLOC(s) ((kzalloc_t)CONFIG_USER_ZALLOC)(s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*kzalloc_t)(size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kzalloc
- *
- * Description:
- * This is a simple redirection to the user-space zalloc() function.
- *
- * Parameters:
- * size - Size (in bytes) of the memory region to be allocated.
- *
- * Return Value:
- * The address of the allocated memory (NULL on failure to allocate)
- *
- * Assumptions:
- * 1. zalloc() resides in user-space
- * 2. The address of the user space zalloc() is provided in user_map.h
- * 3. The user-space zalloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *kzalloc(size_t size)
-{
- return KZALLOC(size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_semaphore.c b/nuttx/mm/kmm_semaphore.c
deleted file mode 100644
index b391e5151..000000000
--- a/nuttx/mm/kmm_semaphore.c
+++ /dev/null
@@ -1,140 +0,0 @@
-/************************************************************************
- * mm/kmm_semaphore.c
- *
- * Copyright (C) 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* These values are obtained from user_map.h */
-
-#define KTRYSEMAPHORE() ((kmtrysemaphore_t) CONFIG_USER_MMTRYSEM )()
-#define KGIVESEMAPHORE() ((kmgivesemaphore_t)CONFIG_USER_MMGIVESEM)()
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef int (*kmtrysemaphore_t)(void);
-typedef void (*kmgivesemaphore_t)(void);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_trysemaphore
- *
- * Description:
- * This is a simple redirection to the user-space mm_trysemaphore()
- * function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * OK on success; a negated errno on failure
- *
- * Assumptions:
- * 1. mm_trysemaphore() resides in user-space
- * 2. The address of the user space mm_trysemaphore() is provided in
- * user_map.h
- * 3. The user-space mm_semaphore() is callable from kernel-space.
- *
- ************************************************************************/
-
-int kmm_trysemaphore(void)
-{
- return KTRYSEMAPHORE();
-}
-
-/************************************************************************
- * Name: kmm_givesemaphore
- *
- * Description:
- * This is a simple redirection to the user-space mm_givesemaphore()
- * function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * OK on success; a negated errno on failure
- *
- * Assumptions:
- * 1. mm_givesemaphore() resides in user-space
- * 2. The address of the user space mm_givesemaphore() is provided in
- * user_map.h
- * 3. The user-space mm_semaphore() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_givesemaphore(void)
-{
- KGIVESEMAPHORE();
-}
-
-#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c
index 8930f6190..6246cfc4b 100644
--- a/nuttx/mm/mm_initialize.c
+++ b/nuttx/mm/mm_initialize.c
@@ -53,13 +53,6 @@
* Public Variables
****************************************************************************/
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-/* This is the user heap */
-
-struct mm_heap_s g_mmheap;
-
-#endif
-
/****************************************************************************
* Private Functions
****************************************************************************/
diff --git a/nuttx/mm/mm_kernel.c b/nuttx/mm/mm_kernel.c
new file mode 100644
index 000000000..207d3e28f
--- /dev/null
+++ b/nuttx/mm/mm_kernel.c
@@ -0,0 +1,282 @@
+/************************************************************************
+ * mm/mm_kernel.c
+ *
+ * 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.
+ *
+ ************************************************************************/
+
+/************************************************************************
+ * Included Files
+ ************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/kmalloc.h>
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP) && defined(__KERNEL__)
+
+/************************************************************************
+ * Pre-processor definition
+ ************************************************************************/
+
+/************************************************************************
+ * Private Types
+ ************************************************************************/
+
+/************************************************************************
+ * Public Data
+ ************************************************************************/
+
+/* This is the kernel heap */
+
+struct mm_heap_s g_kmmheap;
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: kmm_initialize
+ *
+ * Description:
+ * Initialize the kernel heap data structures, providing the initial
+ * heap region.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the (initial) memory region
+ * heap_size - The size (in bytes) if the (initial) memory region.
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void kmm_initialize(FAR void *heap_start, size_t heap_size)
+{
+ return mm_initialize(&g_kmmheap, heap_start, heap_size);
+}
+
+/************************************************************************
+ * Name: kmm_addregion
+ *
+ * Description:
+ * This function adds a region of contiguous memory to the kernel heap.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the memory region
+ * heap_size - The size (in bytes) if the memory region.
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void kmm_addregion(FAR void *heap_start, size_t heap_size)
+{
+ return mm_addregion(&g_kmmheap, heap_start, heap_size);
+}
+
+/************************************************************************
+ * Name: kmalloc
+ *
+ * Description:
+ * Allocate memory from the kernel heap.
+ *
+ * Parameters:
+ * size - Size (in bytes) of the memory region to be allocated.
+ *
+ * Return Value:
+ * The address of the allocated memory (NULL on failure to allocate)
+ *
+ ************************************************************************/
+
+FAR void *kmalloc(size_t size)
+{
+ return mm_malloc(&g_kmmheap, size);
+}
+
+/************************************************************************
+ * Name: kzalloc
+ *
+ * Description:
+ * Allocate and zero memory from the kernel heap.
+ *
+ * Parameters:
+ * size - Size (in bytes) of the memory region to be allocated.
+ *
+ * Return Value:
+ * The address of the allocated memory (NULL on failure to allocate)
+ *
+ ************************************************************************/
+
+FAR void *kzalloc(size_t size)
+{
+ return mm_zalloc(&g_kmmheap, size);
+}
+
+/************************************************************************
+ * Name: krealloc
+ *
+ * Description:
+ * Re-allocate memory in the kernel heap.
+ *
+ * Parameters:
+ * oldmem - The old memory allocated
+ * newsize - Size (in bytes) of the new memory region to be re-allocated.
+ *
+ * Return Value:
+ * The address of the re-allocated memory (NULL on failure to re-allocate)
+ *
+ ************************************************************************/
+
+FAR void *krealloc(FAR void *oldmem, size_t newsize)
+{
+ return mm_realloc(&g_kmmheap, oldmem, newsize);
+}
+
+/************************************************************************
+ * Name: kfree
+ *
+ * Description:
+ * Return allocated memory to the kernel heap.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void kfree(FAR void *mem)
+{
+ DEBUGASSERT(kmm_heapmember(mem));
+ return mm_free(&g_kmmheap, mem);
+}
+
+/************************************************************************
+ * Name: kmm_trysemaphore
+ *
+ * Description:
+ * Try to take the kernel heap semaphore.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * OK on success; a negated errno on failure
+ *
+ ************************************************************************/
+
+int kmm_trysemaphore(void)
+{
+ return mm_trysemaphore(&g_kmmheap);
+}
+
+/************************************************************************
+ * Name: kmm_givesemaphore
+ *
+ * Description:
+ * Give the kernel heap semaphore.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * OK on success; a negated errno on failure
+ *
+ ************************************************************************/
+
+void kmm_givesemaphore(void)
+{
+ return mm_givesemaphore(&g_kmmheap);
+}
+
+/************************************************************************
+ * Name: kmm_heapmember
+ *
+ * Description:
+ * Check if an address lies in the kernel heap.
+ *
+ * Parameters:
+ * mem - The address to check
+ *
+ * Return Value:
+ * true if the address is a member of the kernel heap. false if not
+ * not. If the address is not a member of the kernel heap, then it
+ * must be a member of the user-space heap (unchecked)
+ *
+ ************************************************************************/
+
+bool kmm_heapmember(FAR void *mem)
+{
+#if CONFIG_MM_REGIONS > 1
+ int i;
+
+ /* A valid address from the kernel heap for this region would have to lie
+ * between the region's two guard nodes.
+ */
+
+ for (i = 0; i < g_kmmheap.mm_nregions; i++)
+ {
+ if (mem > (FAR void *)g_kmmheap.mm_heapstart[i] &&
+ mem < (FAR void *)g_kmmheap.mm_heapend[i])
+ {
+ return true;
+ }
+ }
+
+ /* The address does not like any any region assigned to kernel heap */
+
+ return false;
+
+#else
+ /* A valid address from the kernel heap would have to lie between the
+ * two guard nodes.
+ */
+
+ if (mem > (FAR void *)g_kmmheap.mm_heapstart[0] &&
+ mem < (FAR void *)g_kmmheap.mm_heapend[0])
+ {
+ return true;
+ }
+
+ /* Otherwise, the address does not lie in the kernel heap */
+
+ return false;
+
+#endif
+}
+
+#endif /* CONFIG_NUTTX_KERNEL && CONFIG_MM_KERNEL_HEAP && __KERNEL__ */
diff --git a/nuttx/mm/mm_kerneluser.c b/nuttx/mm/mm_kerneluser.c
new file mode 100644
index 000000000..da1f2716e
--- /dev/null
+++ b/nuttx/mm/mm_kerneluser.c
@@ -0,0 +1,306 @@
+/************************************************************************
+ * mm/mm_kerneluser.c
+ *
+ * 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.
+ *
+ ************************************************************************/
+
+/************************************************************************
+ * Included Files
+ ************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/kmalloc.h>
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
+
+/* This logic is all tentatively and, hopefully, will grow in usability.
+ * For now, the kernel-mode build uses the memory manager that is
+ * provided in the user-space build. That is awkward but reasonable for
+ * the current level of support: At present, only memory protection is
+ * provided. Kernel-mode code may call into user-mode code, but not
+ * vice-versa. So hosting the memory manager in user-space allows the
+ * memory manager to be shared in both kernel- and user-mode spaces.
+ *
+ * In the longer run, if an MMU is support that can provide virtualized
+ * memory, then some SLAB memory manager will be required in kernel-space
+ * with some kind of brk() system call to obtain mapped heap space.
+ *
+ * In the current build model, the user-space module is built first. The
+ * file user_map.h is generated in the first pass and contains the
+ * addresses of the memory manager needed in this file:
+ */
+
+#include <arch/board/user_map.h>
+
+/************************************************************************
+ * Pre-processor definition
+ ************************************************************************/
+
+/* These values are obtained from user_map.h */
+
+#define KINITIALIZE(h,s) ((kminitialize_t)CONFIG_USER_MMINIT)(h,s)
+#define KADDREGION(h,s) ((kmaddregion_t)CONFIG_USER_MMADDREGION)(h,s)
+#define KMALLOC(s) ((kmalloc_t)CONFIG_USER_MALLOC)(s)
+#define KZALLOC(s) ((kzalloc_t)CONFIG_USER_ZALLOC)(s)
+#define KREALLOC(p,s) ((krealloc_t)CONFIG_USER_REALLOC)(p,s)
+#define KFREE(p) ((kfree_t)CONFIG_USER_FREE)(p)
+#define KTRYSEMAPHORE() ((kmtrysemaphore_t) CONFIG_USER_MMTRYSEM )()
+#define KGIVESEMAPHORE() ((kmgivesemaphore_t)CONFIG_USER_MMGIVESEM)()
+
+/************************************************************************
+ * Private Types
+ ************************************************************************/
+
+typedef void (*kminitialize_t)(FAR void*, size_t);
+typedef void (*kmaddregion_t)(FAR void*, size_t);
+typedef FAR void *(*kmalloc_t)(size_t);
+typedef FAR void *(*kzalloc_t)(size_t);
+typedef FAR void *(*krealloc_t)(FAR void*, size_t);
+typedef void (*kfree_t)(FAR void *);
+typedef int (*kmtrysemaphore_t)(void);
+typedef void (*kmgivesemaphore_t)(void);
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: kumm_initialize
+ *
+ * Description:
+ * This is a simple redirection to the user-space mm_initialize()
+ * function.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the (initial) memory region
+ * heap_size - The size (in bytes) if the (initial) memory region.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * 1. mm_initialize() resides in user-space
+ * 2. The address of the user space mm_initialize() is provided in
+ * user_map.h
+ * 3. The user-space mm_initialize() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+void kumm_initialize(FAR void *heap_start, size_t heap_size)
+{
+ return KINITIALIZE(heap_start, heap_size);
+}
+
+/************************************************************************
+ * Name: kumm_addregion
+ *
+ * Description:
+ * This is a simple redirection to the user-space mm_addregion()
+ * function.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the memory region
+ * heap_size - The size (in bytes) if the memory region.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * 1. mm_addregion() resides in user-space
+ * 2. The address of the user space mm_addregion() is provided in
+ * user_map.h
+ * 3. The user-space mm_addregion() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+void kumm_addregion(FAR void *heap_start, size_t heap_size)
+{
+ return KADDREGION(heap_start, heap_size);
+}
+
+/************************************************************************
+ * Name: kumalloc
+ *
+ * Description:
+ * This is a simple redirection to the user-space malloc() function.
+ *
+ * Parameters:
+ * size - Size (in bytes) of the memory region to be allocated.
+ *
+ * Return Value:
+ * The address of the allocated memory (NULL on failure to allocate)
+ *
+ * Assumptions:
+ * 1. malloc() resides in user-space
+ * 2. The address of the user space malloc() is provided in user_map.h
+ * 3. The user-space malloc() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+FAR void *kumalloc(size_t size)
+{
+ return KMALLOC(size);
+}
+
+/************************************************************************
+ * Name: kuzalloc
+ *
+ * Description:
+ * This is a simple redirection to the user-space zalloc() function.
+ *
+ * Parameters:
+ * size - Size (in bytes) of the memory region to be allocated.
+ *
+ * Return Value:
+ * The address of the allocated memory (NULL on failure to allocate)
+ *
+ * Assumptions:
+ * 1. zalloc() resides in user-space
+ * 2. The address of the user space zalloc() is provided in user_map.h
+ * 3. The user-space zalloc() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+FAR void *kuzalloc(size_t size)
+{
+ return KZALLOC(size);
+}
+
+/************************************************************************
+ * Name: kurealloc
+ *
+ * Description:
+ * This is a simple redirection to the user-space realloc() function.
+ *
+ * Parameters:
+ * oldmem - The old memory allocated
+ * newsize - Size (in bytes) of the new memory region to be re-allocated.
+ *
+ * Return Value:
+ * The address of the re-allocated memory (NULL on failure to re-allocate)
+ *
+ * Assumptions:
+ * 1. realloc() resides in user-space
+ * 2. The address of the user space realloc() is provided in user_map.h
+ * 3. The user-space realloc() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+FAR void *kurealloc(FAR void *oldmem, size_t newsize)
+{
+ return KREALLOC(oldmem, newsize);
+}
+
+/************************************************************************
+ * Name: kufree
+ *
+ * Description:
+ * This is a simple redirection to the user-space free() function.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * 1. free() resides in user-space
+ * 2. The address of the user space free() is provided in user_map.h
+ * 3. The user-space free() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+void kufree(FAR void *mem)
+{
+#ifdef CONFIG_MM_KERNEL_HEAP
+ DEBUGASSERT(!kmm_heapmember(mem));
+#endif
+ return KFREE(mem);
+}
+
+/************************************************************************
+ * Name: kumm_trysemaphore
+ *
+ * Description:
+ * This is a simple redirection to the user-space mm_trysemaphore()
+ * function.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * 1. mm_trysemaphore() resides in user-space
+ * 2. The address of the user space mm_trysemaphore() is provided in
+ * user_map.h
+ * 3. The user-space mm_semaphore() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+int kumm_trysemaphore(void)
+{
+ return KTRYSEMAPHORE();
+}
+
+/************************************************************************
+ * Name: kumm_givesemaphore
+ *
+ * Description:
+ * This is a simple redirection to the user-space mm_givesemaphore()
+ * function.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * 1. mm_givesemaphore() resides in user-space
+ * 2. The address of the user space mm_givesemaphore() is provided in
+ * user_map.h
+ * 3. The user-space mm_semaphore() is callable from kernel-space.
+ *
+ ************************************************************************/
+
+void kumm_givesemaphore(void)
+{
+ KGIVESEMAPHORE();
+}
+
+#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/umm_semaphore.c b/nuttx/mm/mm_user.c
index d554268ab..ed5ba5eb9 100644
--- a/nuttx/mm/umm_semaphore.c
+++ b/nuttx/mm/mm_user.c
@@ -1,7 +1,7 @@
/************************************************************************
- * mm/umm_semaphore.c
+ * mm/mm_user.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * 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
@@ -51,6 +51,14 @@
************************************************************************/
/************************************************************************
+ * Public Data
+ ************************************************************************/
+
+/* This is the user heap */
+
+struct mm_heap_s g_mmheap;
+
+/************************************************************************
* Private Functions
************************************************************************/
@@ -59,10 +67,56 @@
************************************************************************/
/************************************************************************
+ * Name: umm_initialize
+ *
+ * Description:
+ * This is a simple wrapper for the mm_initialize() function. This
+ * function is exported from the user-space blob so that the kernel
+ * can initialize the user-mode allocator.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the (initial) memory region
+ * heap_size - The size (in bytes) if the (initial) memory region.
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void umm_initialize(FAR void *heap_start, size_t heap_size)
+{
+ mm_initialize(&g_mmheap, heap_start, heap_size);
+}
+
+/************************************************************************
+ * Name: umm_addregion
+ *
+ * Description:
+ * This is a simple wrapper for the mm_addregion() function. This
+ * function is exported from the user-space blob so that the kernel
+ * can initialize the user-mode allocator.
+ *
+ * Parameters:
+ * heap_start - Address of the beginning of the memory region
+ * heap_size - The size (in bytes) if the memory region.
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void umm_addregion(FAR void *heap_start, size_t heap_size)
+{
+ mm_addregion(&g_mmheap, heap_start, heap_size);
+}
+
+/************************************************************************
* Name: umm_trysemaphore
*
* Description:
- * This is a simple wrapper for the mm_trysemaphore() function.
+ * This is a simple wrapper for the mm_trysemaphore() function. This
+ * function is exported from the user-space blob so that the kernel
+ * can manage the user-mode allocator.
*
* Parameters:
* None
@@ -81,7 +135,9 @@ int umm_trysemaphore(void)
* Name: umm_givesemaphore
*
* Description:
- * This is a simple wrapper for the mm_givesemaphore() function.
+ * This is a simple wrapper for the mm_givesemaphore() function. This
+ * function is exported from the user-space blob so that the kernel
+ * can manage the user-mode allocator.
*
* Parameters:
* None
@@ -96,4 +152,4 @@ void umm_givesemaphore(void)
mm_givesemaphore(&g_mmheap);
}
-#endif /* !CONFIG_NUTTX_KERNEL || __KERNEL__ */
+#endif /* !CONFIG_NUTTX_KERNEL || !__KERNEL__ */
diff --git a/nuttx/mm/umm_addregion.c b/nuttx/mm/umm_addregion.c
deleted file mode 100644
index 181723155..000000000
--- a/nuttx/mm/umm_addregion.c
+++ /dev/null
@@ -1,81 +0,0 @@
-/************************************************************************
- * mm/umm_addregion.c
- *
- * 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/mm.h>
-
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: umm_addregion
- *
- * Description:
- * This is a simple wrapper for the mm_addregion() function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the memory region
- * heap_size - The size (in bytes) if the memory region.
- *
- * Return Value:
- * None
- *
- ************************************************************************/
-
-void umm_addregion(FAR void *heap_start, size_t heap_size)
-{
- mm_addregion(&g_mmheap, heap_start, heap_size);
-}
-
-#endif /* !CONFIG_NUTTX_KERNEL || !__KERNEL__ */
diff --git a/nuttx/mm/umm_initialize.c b/nuttx/mm/umm_initialize.c
deleted file mode 100644
index 13a1fe015..000000000
--- a/nuttx/mm/umm_initialize.c
+++ /dev/null
@@ -1,81 +0,0 @@
-/************************************************************************
- * mm/umm_initialize.c
- *
- * 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.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/mm.h>
-
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: umm_initialize
- *
- * Description:
- * This is a simple wrapper for the mm_initialize() function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the (initial) memory region
- * heap_size - The size (in bytes) if the (initial) memory region.
- *
- * Return Value:
- * None
- *
- ************************************************************************/
-
-void umm_initialize(FAR void *heap_start, size_t heap_size)
-{
- mm_initialize(&g_mmheap, heap_start, heap_size);
-}
-
-#endif /* !CONFIG_NUTTX_KERNEL || !__KERNEL__ */