summaryrefslogtreecommitdiff
path: root/nuttx/mm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-08 22:01:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-08 22:01:50 +0000
commitf2c129b281fc8fa30eccb9b34df534f954ee3c47 (patch)
treea5ff5a1a0415f7fabf66180ccb432243740f4d74 /nuttx/mm
parent5e160bcf59441ce40088ca089cbeb4461a0b0d6a (diff)
downloadpx4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.tar.gz
px4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.tar.bz2
px4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.zip
up_addregion should use kmm_addregion; move garbage kmm*.c file to mm/. for now
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5721 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/mm')
-rw-r--r--nuttx/mm/Kconfig2
-rw-r--r--nuttx/mm/Makefile72
-rw-r--r--nuttx/mm/README.txt14
-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.c75
11 files changed, 881 insertions, 89 deletions
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index 911ae5545..9724eb407 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -37,7 +37,7 @@ config MM_REGIONS
If the architecture includes multiple, non-contiguous regions of
memory to allocate from, this specifies the number of memory regions
that the memory manager must handle and enables the API
- mm_addregion(start, end);
+ mm_addregion(heap, start, end);
NOTE: If MM_MULTIHEAP is selected, then this maximum number of regions
applies to all heaps.
diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
index da41f9f57..4b7412b43 100644
--- a/nuttx/mm/Makefile
+++ b/nuttx/mm/Makefile
@@ -1,7 +1,7 @@
############################################################################
# mm/Makefile
#
-# Copyright (C) 2007, 2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007, 2012, 2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -35,22 +35,29 @@
-include $(TOPDIR)/Make.defs
-ASRCS =
-CSRCS = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \
- mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \
- mm_memalign.c mm_free.c mm_mallinfo.c
+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
+
+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
+endif
ifeq ($(CONFIG_GRAN),y)
-CSRCS += mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c
+CSRCS += mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c
endif
-AOBJS = $(ASRCS:.S=$(OBJEXT))
-COBJS = $(CSRCS:.c=$(OBJEXT))
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
-SRCS = $(ASRCS) $(CSRCS)
-OBJS = $(AOBJS) $(COBJS)
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
-BIN = libmm$(LIBEXT)
+UBIN = libumm$(LIBEXT)
+KBIN = libkmm$(LIBEXT)
+BIN = libmm$(LIBEXT)
all: $(BIN)
@@ -63,14 +70,57 @@ $(COBJS): %$(OBJEXT): %.c
$(BIN): $(OBJS)
$(call ARCHIVE, $@, $(OBJS))
+ifneq ($(BIN),$(UBIN))
+.userlib:
+ $(Q) $(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
+ $(Q) touch .userlib
+
+$(UBIN): kclean .userlib
+endif
+
+ifneq ($(BIN),$(KBIN))
+.kernlib:
+ $(Q) $(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES)
+ $(Q) touch .kernlib
+
+$(KBIN): uclean .kernlib
+endif
+
.depend: Makefile $(SRCS)
$(Q) $(MKDEP) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
$(Q) touch $@
depend: .depend
+# Clean Targets:
+# Clean user-mode temporary files (retaining the UBIN binary)
+
+uclean:
+ifneq ($(OBJEXT),)
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ $(Q) if exist .userlib ]; then del *$(OBJEXT)
+else
+ $(Q) ( if [ -f .userlib ]; then rm -f *$(OBJEXT); fi )
+endif
+endif
+ $(call DELFILE, .userlib)
+
+# Clean kernel-mode temporary files (retaining the KBIN binary)
+
+kclean:
+ifneq ($(OBJEXT),)
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ $(Q) if exist .kernlib ]; then del *$(OBJEXT)
+else
+ $(Q) ( if [ -f .kernlib ]; then rm -f *$(OBJEXT); fi )
+endif
+endif
+ $(call DELFILE, .kernlib)
+
clean:
$(call DELFILE, $(BIN))
+ $(call DELFILE, $(UBIN))
+ $(call DELFILE, $(KBIN))
$(call CLEAN)
distclean: clean
diff --git a/nuttx/mm/README.txt b/nuttx/mm/README.txt
index 2668432e3..d2f307849 100644
--- a/nuttx/mm/README.txt
+++ b/nuttx/mm/README.txt
@@ -32,19 +32,7 @@ This directory contains the NuttX memory management logic. This include:
o Alignment: All allocations are aligned to 8- or 4-bytes for large
and small models, respectively.
-2) Test Program. There is also a host-best test program that can be
- used to verify the memory manager. These are the file:
-
- Makefile.test, mm_test.c, and mm_environment.h.
-
- Build instructions:
-
- make -f Makefile.test
-
- The executable will be built in the top-level directory as nuttx/mm_text
- (or mm_test.exe under Cygwin).
-
-3) Granule Allocator. A non-standard granule allocator is also available
+2) Granule Allocator. A non-standard granule allocator is also available
in this directory The granule allocator allocates memory in units
of a fixed sized block ("granule"). Allocations may be aligned to a user-
provided address boundary.
diff --git a/nuttx/mm/kmm_addregion.c b/nuttx/mm/kmm_addregion.c
new file mode 100644
index 000000000..c53fe9cfe
--- /dev/null
+++ b/nuttx/mm/kmm_addregion.c
@@ -0,0 +1,113 @@
+/************************************************************************
+ * 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(&g_kmmheap, heap_start, heap_size);
+}
+
+#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/mm/kmm_initialize.c b/nuttx/mm/kmm_initialize.c
new file mode 100644
index 000000000..c5f5df05d
--- /dev/null
+++ b/nuttx/mm/kmm_initialize.c
@@ -0,0 +1,113 @@
+/************************************************************************
+ * 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
new file mode 100644
index 000000000..c4e31ebfa
--- /dev/null
+++ b/nuttx/mm/kmm_kfree.c
@@ -0,0 +1,110 @@
+/************************************************************************
+ * 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
new file mode 100644
index 000000000..e2c347342
--- /dev/null
+++ b/nuttx/mm/kmm_kmalloc.c
@@ -0,0 +1,110 @@
+/************************************************************************
+ * 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
new file mode 100644
index 000000000..d5bebff38
--- /dev/null
+++ b/nuttx/mm/kmm_krealloc.c
@@ -0,0 +1,111 @@
+/************************************************************************
+ * 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
new file mode 100644
index 000000000..4775312c6
--- /dev/null
+++ b/nuttx/mm/kmm_kzalloc.c
@@ -0,0 +1,110 @@
+/************************************************************************
+ * 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
new file mode 100644
index 000000000..b391e5151
--- /dev/null
+++ b/nuttx/mm/kmm_semaphore.c
@@ -0,0 +1,140 @@
+/************************************************************************
+ * 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 37df3ab5f..8930f6190 100644
--- a/nuttx/mm/mm_initialize.c
+++ b/nuttx/mm/mm_initialize.c
@@ -65,7 +65,11 @@ struct mm_heap_s g_mmheap;
****************************************************************************/
/****************************************************************************
- * Name: _mm_addregion
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_addregion
*
* Description:
* This function adds a region of contiguous memory to the selected heap.
@@ -82,8 +86,8 @@ struct mm_heap_s g_mmheap;
*
****************************************************************************/
-static inline void _mm_addregion(FAR struct mm_heap_s *heap,
- FAR void *heapstart, size_t heapsize)
+void mm_addregion(FAR struct mm_heap_s *heap, FAR void *heapstart,
+ size_t heapsize)
{
FAR struct mm_freenode_s *node;
uintptr_t heapbase;
@@ -149,7 +153,7 @@ static inline void _mm_addregion(FAR struct mm_heap_s *heap,
}
/****************************************************************************
- * Name: _mm_initialize
+ * Name: mm_initialize
*
* Description:
* Initialize the selected heap data structures, providing the initial
@@ -167,8 +171,8 @@ static inline void _mm_addregion(FAR struct mm_heap_s *heap,
*
****************************************************************************/
-static inline void _mm_initialize(FAR struct mm_heap_s *heap,
- FAR void *heapstart, size_t heapsize)
+void mm_initialize(FAR struct mm_heap_s *heap, FAR void *heapstart,
+ size_t heapsize)
{
int i;
@@ -209,62 +213,5 @@ static inline void _mm_initialize(FAR struct mm_heap_s *heap,
/* Add the initial region of memory to the heap */
- _mm_addregion(heap, heapstart, heapsize);
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: mm_initialize
- *
- * Description:
- * This this function is called during initialization to initialize the
- * user heap.
- *
- * Parameters:
- * heapstart - Start of the initial heap region
- * heapsize - Size of the initial heap region
- *
- * Return Value:
- * None
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-
-void mm_initialize(FAR void *heapstart, size_t heapsize)
-{
- _mm_initialize(&g_mmheap, heapstart, heapsize);
+ mm_addregion(heap, heapstart, heapsize);
}
-
-#endif
-
-/****************************************************************************
- * Name: mm_addregion
- *
- * Description:
- * This function adds a region of contiguous memory to the user heap.
- *
- * Parameters:
- * heapstart - Start of the heap region
- * heapsize - Size of the heap region
- *
- * Return Value:
- * None
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-
-void mm_addregion(FAR void *heapstart, size_t heapsize)
-{
- _mm_addregion(&g_mmheap, heapstart, heapsize);
-}
-
-#endif