summaryrefslogtreecommitdiff
path: root/nuttx/mm
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-08-31 10:54:55 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-08-31 10:54:55 -0600
commitd646bcf4f5e2d0662b5b7261ff08d8f99457e261 (patch)
treec7b1c76b9e30faa72f2cd7600cafa112c2b75b4c /nuttx/mm
parent2a8958c4efcab8dcc8fda9cd31bdcf462801669d (diff)
downloadpx4-nuttx-d646bcf4f5e2d0662b5b7261ff08d8f99457e261.tar.gz
px4-nuttx-d646bcf4f5e2d0662b5b7261ff08d8f99457e261.tar.bz2
px4-nuttx-d646bcf4f5e2d0662b5b7261ff08d8f99457e261.zip
Remove CONFIG_MM_MULTIHEAP. Non-multiheap operation is no longer supported
Diffstat (limited to 'nuttx/mm')
-rw-r--r--nuttx/mm/Kconfig20
-rw-r--r--nuttx/mm/Makefile24
-rw-r--r--nuttx/mm/kmm_calloc.c67
-rw-r--r--nuttx/mm/kmm_free.c82
-rw-r--r--nuttx/mm/kmm_mallinfo.c90
-rw-r--r--nuttx/mm/kmm_malloc.c89
-rw-r--r--nuttx/mm/kmm_memalign.c80
-rw-r--r--nuttx/mm/kmm_realloc.c78
-rw-r--r--nuttx/mm/kmm_zalloc.c73
-rw-r--r--nuttx/mm/mm_calloc.c36
-rw-r--r--nuttx/mm/mm_free.c28
-rw-r--r--nuttx/mm/mm_kernel.c98
-rw-r--r--nuttx/mm/mm_mallinfo.c41
-rw-r--r--nuttx/mm/mm_malloc.c31
-rw-r--r--nuttx/mm/mm_memalign.c48
-rw-r--r--nuttx/mm/mm_realloc.c62
-rw-r--r--nuttx/mm/mm_zalloc.c28
-rw-r--r--nuttx/mm/umm_calloc.c69
-rw-r--r--nuttx/mm/umm_free.c74
-rw-r--r--nuttx/mm/umm_mallinfo.c90
-rw-r--r--nuttx/mm/umm_malloc.c91
-rw-r--r--nuttx/mm/umm_memalign.c78
-rw-r--r--nuttx/mm/umm_realloc.c80
-rw-r--r--nuttx/mm/umm_zalloc.c75
24 files changed, 1159 insertions, 373 deletions
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index 006b8cf52..fd01ad5ce 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -3,22 +3,10 @@
# see misc/tools/kconfig-language.txt.
#
-config MM_MULTIHEAP
- bool "Build support for multiple heaps"
- default n
- ---help---
- Build interfaces to support multiple heaps. This should not be
- confused with memory regions. One heap may be composed of multiple,
- non-contiguous memory regions. The fact that the heap is composed
- of such multiple regions is invisible to the end-user (other than
- the heap comes pre-fragmented). Multiple heaps, on the other hand,
- supports a separate set of allocators that operate on a separate set
- of memory regions.
-
config MM_KERNEL_HEAP
bool "Support a protected, kernel heap"
default y
- depends on (BUILD_PROTECTED && MM_MULTIHEAP) || BUILD_KERNEL
+ depends on BUILD_PROTECTED || BUILD_KERNEL
---help---
Partition heap memory into two parts: (1) a protected, kernel-mode
heap accessible only by the NuttX kernel, and (2) an unprotected
@@ -62,9 +50,6 @@ config MM_SMALL
only 4-byte alignment. This may be important on some platforms where
64-bit data is in allocated structures and 8-byte alignment is required.
- NOTE: If MM_MULTIHEAP is selected, then this selection applies to all
- heaps.
-
config MM_REGIONS
int "Number of memory regions"
default 1
@@ -74,9 +59,6 @@ config MM_REGIONS
that the memory manager must handle and enables the API
mm_addregion(heap, start, end);
- NOTE: If MM_MULTIHEAP is selected, then this maximum number of regions
- applies to all heaps.
-
config ARCH_HAVE_HEAP2
bool
default n
diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
index 349ced9f8..ef57255b0 100644
--- a/nuttx/mm/Makefile
+++ b/nuttx/mm/Makefile
@@ -51,23 +51,23 @@ endif
# 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 = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c
+CSRCS += mm_shrinkchunk.c
+CSRCS += mm_calloc.c mm_free.c mm_mallinfo.c mm_malloc.c mm_memalign.c
+CSRCS += mm_realloc.c mm_zalloc.c
-# Allocator instances
+# User allocator
CSRCS += mm_user.c
-ifeq ($(CONFIG_BUILD_PROTECTED),y)
-ifeq ($(CONFIG_MM_KERNEL_HEAP),y)
-CSRCS += mm_kernel.c
-endif
-else
-ifeq ($(CONFIG_BUILD_KERNEL),y)
+CSRCS += umm_calloc.c umm_free.c umm_mallinfo.c umm_malloc.c
+CSRCS += umm_memalign.c umm_realloc.c umm_zalloc.c
+
+# Kernel allocator
+
ifeq ($(CONFIG_MM_KERNEL_HEAP),y)
CSRCS += mm_kernel.c
-endif
-endif
+CSRCS += kmm_calloc.c kmm_free.c kmm_mallinfo.c kmm_malloc.c
+CSRCS += kmm_memalign.c kmm_realloc.c kmm_zalloc.c
endif
# An optional granule allocator
diff --git a/nuttx/mm/kmm_calloc.c b/nuttx/mm/kmm_calloc.c
new file mode 100644
index 000000000..db8ac185f
--- /dev/null
+++ b/nuttx/mm/kmm_calloc.c
@@ -0,0 +1,67 @@
+/****************************************************************************
+ * mm/kmm_calloc.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kmm_calloc
+ *
+ * Description:
+ * kmm_calloc is a thin wrapper for mm_calloc()
+ *
+ ****************************************************************************/
+
+FAR void *kmm_calloc(size_t n, size_t elem_size)
+{
+ return mm_calloc(&g_kmmheap, n, elem_size);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_free.c b/nuttx/mm/kmm_free.c
new file mode 100644
index 000000000..e118d7853
--- /dev/null
+++ b/nuttx/mm/kmm_free.c
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * mm/kmm_free.c
+ *
+ * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * Name: kfree
+ *
+ * Description:
+ * Returns a chunk of kernel memory to the list of free nodes, merging
+ * with adjacent free chunks if possible.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void kfree(FAR void *mem)
+{
+ DEBUGASSERT(kmm_heapmember(mem));
+ mm_free(&g_kmmheap, mem);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_mallinfo.c b/nuttx/mm/kmm_mallinfo.c
new file mode 100644
index 000000000..d7c3ab475
--- /dev/null
+++ b/nuttx/mm/kmm_mallinfo.c
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * mm/kmm_mallinfo.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kmm_mallinfo
+ *
+ * Description:
+ * kmm_mallinfo returns a copy of updated current heap information for the
+ * kernel heap
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+
+struct mallinfo kmm_mallinfo(void)
+{
+ struct mallinfo info;
+ mm_mallinfo(&g_kmmheap, &info);
+ return info;
+}
+
+#else
+
+int kmm_mallinfo(struct mallinfo *info)
+{
+ return mm_mallinfo(&g_kmmheap, info);
+}
+
+#endif /* CONFIG_CAN_PASS_STRUCTS */
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_malloc.c b/nuttx/mm/kmm_malloc.c
new file mode 100644
index 000000000..3646d3bae
--- /dev/null
+++ b/nuttx/mm/kmm_malloc.c
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * mm/kmm_malloc.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * 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);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_memalign.c b/nuttx/mm/kmm_memalign.c
new file mode 100644
index 000000000..b7fc3d599
--- /dev/null
+++ b/nuttx/mm/kmm_memalign.c
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * mm/kmm_memalign.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * Name: kmemalign
+ *
+ * Description:
+ * Allocate aligned memory in the kernel heap.
+ *
+ * Parameters:
+ * alignment - Log2 byte alignment
+ * size - Size (in bytes) of the new memory region to be allocated.
+ *
+ * Return Value:
+ * The address of the re-allocated memory (NULL on failure to allocate)
+ *
+ ************************************************************************/
+
+FAR void *kmemalign(size_t alignment, size_t size)
+{
+ return mm_memalign(&g_kmmheap, alignment, size);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_realloc.c b/nuttx/mm/kmm_realloc.c
new file mode 100644
index 000000000..cd3d383b4
--- /dev/null
+++ b/nuttx/mm/kmm_realloc.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * mm/kmm_realloc.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/kmm_zalloc.c b/nuttx/mm/kmm_zalloc.c
new file mode 100644
index 000000000..db14972ee
--- /dev/null
+++ b/nuttx/mm/kmm_zalloc.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ * mm/kmm_zalloc.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_KERNEL_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * 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);
+}
+
+#endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/nuttx/mm/mm_calloc.c b/nuttx/mm/mm_calloc.c
index 90276dd6a..c78ede8d4 100644
--- a/nuttx/mm/mm_calloc.c
+++ b/nuttx/mm/mm_calloc.c
@@ -39,8 +39,6 @@
#include <nuttx/config.h>
-#include <stdlib.h>
-
#include <nuttx/mm.h>
/****************************************************************************
@@ -48,18 +46,17 @@
****************************************************************************/
/****************************************************************************
- * Global Functions
+ * Public Functions
****************************************************************************/
/****************************************************************************
* Name: mm_calloc
*
- * Descripton:
- * calloc calculates the size of the allocation and calls zalloc
+ * Descriptor:
+ * mm_calloc() calculates the size of the allocation and calls mm_zalloc()
*
****************************************************************************/
-#ifdef CONFIG_MM_MULTIHEAP
FAR void *mm_calloc(FAR struct mm_heap_s *heap, size_t n, size_t elem_size)
{
FAR void *ret = NULL;
@@ -71,30 +68,3 @@ FAR void *mm_calloc(FAR struct mm_heap_s *heap, size_t n, size_t elem_size)
return ret;
}
-#endif
-
-/****************************************************************************
- * Name: calloc
- *
- * Descripton:
- * calloc calculates the size of the allocation and calls zalloc
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-FAR void *calloc(size_t n, size_t elem_size)
-{
-#ifdef CONFIG_MM_MULTIHEAP
- return mm_calloc(&g_mmheap, n, elem_size);
-#else
- FAR void *ret = NULL;
-
- if (n > 0 && elem_size > 0)
- {
- ret = zalloc(n * elem_size);
- }
-
- return ret;
-#endif
-}
-#endif
diff --git a/nuttx/mm/mm_free.c b/nuttx/mm/mm_free.c
index a75564b35..bcc04abc9 100644
--- a/nuttx/mm/mm_free.c
+++ b/nuttx/mm/mm_free.c
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <stdlib.h>
#include <assert.h>
#include <debug.h>
@@ -54,6 +53,10 @@
****************************************************************************/
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: mm_free
*
* Description:
@@ -62,9 +65,6 @@
*
****************************************************************************/
-#ifndef CONFIG_MM_MULTIHEAP
-static inline
-#endif
void mm_free(FAR struct mm_heap_s *heap, FAR void *mem)
{
FAR struct mm_freenode_s *node;
@@ -153,23 +153,3 @@ void mm_free(FAR struct mm_heap_s *heap, FAR void *mem)
mm_addfreechunk(heap, node);
mm_givesemaphore(heap);
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: free
- *
- * Description:
- * Returns a chunk of memory to the list of free nodes, merging with
- * adjacent free chunks if possible.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-void free(FAR void *mem)
-{
- mm_free(&g_mmheap, mem);
-}
-#endif
diff --git a/nuttx/mm/mm_kernel.c b/nuttx/mm/mm_kernel.c
index fcb7f1380..5435b9316 100644
--- a/nuttx/mm/mm_kernel.c
+++ b/nuttx/mm/mm_kernel.c
@@ -112,104 +112,6 @@ void kmm_addregion(FAR void *heap_start, size_t 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: kmemalign
- *
- * Description:
- * Allocate aligned memory in the kernel heap.
- *
- * Parameters:
- * alignment - Log2 byte alignment
- * size - Size (in bytes) of the new memory region to be allocated.
- *
- * Return Value:
- * The address of the re-allocated memory (NULL on failure to allocate)
- *
- ************************************************************************/
-
-FAR void *kmemalign(size_t alignment, size_t size)
-{
- return mm_memalign(&g_kmmheap, alignment, size);
-}
-
-/************************************************************************
- * 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:
diff --git a/nuttx/mm/mm_mallinfo.c b/nuttx/mm/mm_mallinfo.c
index e89408f36..6f00a8f03 100644
--- a/nuttx/mm/mm_mallinfo.c
+++ b/nuttx/mm/mm_mallinfo.c
@@ -58,6 +58,10 @@
****************************************************************************/
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: mm_mallinfo
*
* Description:
@@ -65,9 +69,6 @@
*
****************************************************************************/
-#ifndef CONFIG_MM_MULTIHEAP
-static inline
-#endif
int mm_mallinfo(FAR struct mm_heap_s *heap, FAR struct mallinfo *info)
{
struct mm_allocnode_s *node;
@@ -137,37 +138,3 @@ int mm_mallinfo(FAR struct mm_heap_s *heap, FAR struct mallinfo *info)
info->fordblks = fordblks;
return OK;
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: kmallinfo and mallinfo
- *
- * Description:
- * mallinfo returns a copy of updated current heap information for either
- * the user heap (mallinfo) or the kernel heap (kmallinfo).
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-# ifdef CONFIG_CAN_PASS_STRUCTS
-
-struct mallinfo mallinfo(void)
-{
- struct mallinfo info;
-
- mm_mallinfo(&g_mmheap, &info);
- return info;
-}
-
-# else
-
-int mallinfo(struct mallinfo *info)
-{
- return mm_mallinfo(&g_mmheap, info);
-}
-
-#endif
-#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/mm_malloc.c b/nuttx/mm/mm_malloc.c
index 2566e1511..47237f99f 100644
--- a/nuttx/mm/mm_malloc.c
+++ b/nuttx/mm/mm_malloc.c
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <stdlib.h>
#include <assert.h>
#include <debug.h>
@@ -70,6 +69,10 @@
****************************************************************************/
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: mm_malloc
*
* Description:
@@ -80,9 +83,6 @@
*
****************************************************************************/
-#ifndef CONFIG_MM_MULTIHEAP
-static inline
-#endif
FAR void *mm_malloc(FAR struct mm_heap_s *heap, size_t size)
{
FAR struct mm_freenode_s *node;
@@ -212,26 +212,3 @@ FAR void *mm_malloc(FAR struct mm_heap_s *heap, size_t size)
return ret;
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: malloc
- *
- * Description:
- * Find the smallest chunk that satisfies the request. Take the memory from
- * that chunk, save the remaining, smaller chunk (if any).
- *
- * 8-byte alignment of the allocated data is assured.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-FAR void *malloc(size_t size)
-{
- return mm_malloc(&g_mmheap, size);
-}
-#endif
-
diff --git a/nuttx/mm/mm_memalign.c b/nuttx/mm/mm_memalign.c
index 6846350b4..a45d7ffe4 100644
--- a/nuttx/mm/mm_memalign.c
+++ b/nuttx/mm/mm_memalign.c
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <stdlib.h>
#include <assert.h>
#include <nuttx/mm.h>
@@ -47,22 +46,16 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* If multiple heaps are used, then the heap must be passed as a parameter to
- * mm_malloc(). In the single heap case, mm_malloc() is not available and
- * we have to use malloc() (which, internally, will use the same heap).
- */
-
-#ifdef CONFIG_MM_MULTIHEAP
-# define MM_MALLOC(h,s) mm_malloc(h,s)
-#else
-# define MM_MALLOC(h,s) malloc(s)
-#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: mm_memalign
*
* Description:
@@ -75,9 +68,6 @@
*
****************************************************************************/
-#ifndef CONFIG_MM_MULTIHEAP
-static inline
-#endif
FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
size_t size)
{
@@ -87,13 +77,13 @@ FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
size_t mask = (size_t)(alignment - 1);
size_t allocsize;
- /* If this requested alignement less than or equal to the natural alignment
+ /* If this requested alinement's less than or equal to the natural alignment
* of malloc, then just let malloc do the work.
*/
if (alignment <= MM_MIN_CHUNK)
{
- return MM_MALLOC(heap, size);
+ return mm_malloc(heap, size);
}
/* Adjust the size to account for (1) the size of the allocated node, (2)
@@ -113,7 +103,7 @@ FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
/* Then malloc that size */
- rawchunk = (size_t)MM_MALLOC(heap, allocsize);
+ rawchunk = (size_t)mm_malloc(heap, allocsize);
if (rawchunk == 0)
{
return NULL;
@@ -222,27 +212,3 @@ FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
mm_givesemaphore(heap);
return (FAR void*)alignedchunk;
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: memalign
- *
- * Description:
- * memalign requests more than enough space from malloc, finds a region
- * within that chunk that meets the alignment request and then frees any
- * leading or trailing space.
- *
- * The alignment argument must be a power of two (not checked). 8-byte
- * alignment is guaranteed by normal malloc calls.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-FAR void *memalign(size_t alignment, size_t size)
-{
- return mm_memalign(&g_mmheap, alignment, size);
-}
-#endif
diff --git a/nuttx/mm/mm_realloc.c b/nuttx/mm/mm_realloc.c
index 658ea1df1..c85e12766 100644
--- a/nuttx/mm/mm_realloc.c
+++ b/nuttx/mm/mm_realloc.c
@@ -49,25 +49,16 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* If multiple heaps are used, then the heap must be passed as a parameter to
- * mm_malloc() and mm_free(). In the single heap case, mm_malloc() and
- * mm_free() are not available and we have to use malloc() and free() (which,
- * internally, will use the same heap).
- */
-
-#ifdef CONFIG_MM_MULTIHEAP
-# define MM_MALLOC(h,s) mm_malloc(h,s)
-# define MM_FREE(h,m) mm_free(h,m)
-#else
-# define MM_MALLOC(h,s) malloc(s)
-# define MM_FREE(h,m) free(m)
-#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: mm_realloc
*
* Description:
@@ -90,9 +81,6 @@
*
****************************************************************************/
-#ifndef CONFIG_MM_MULTIHEAP
-static inline
-#endif
FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem,
size_t size)
{
@@ -108,14 +96,14 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem,
if (!oldmem)
{
- return MM_MALLOC(heap, size);
+ return mm_malloc(heap, size);
}
/* If size is zero, then realloc is equivalent to free */
if (size <= 0)
{
- MM_FREE(heap, oldmem);
+ mm_free(heap, oldmem);
return NULL;
}
@@ -361,47 +349,13 @@ FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem,
*/
mm_givesemaphore(heap);
- newmem = (FAR void*)MM_MALLOC(heap, size);
+ newmem = (FAR void*)mm_malloc(heap, size);
if (newmem)
{
memcpy(newmem, oldmem, oldsize);
- MM_FREE(heap, oldmem);
+ mm_free(heap, oldmem);
}
return newmem;
}
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: realloc
- *
- * Description:
- * If the reallocation is for less space, then:
- *
- * (1) the current allocation is reduced in size
- * (2) the remainder at the end of the allocation is returned to the
- * free list.
- *
- * If the request is for more space and the current allocation can be
- * extended, it will be extended by:
- *
- * (1) Taking the additional space from the following free chunk, or
- * (2) Taking the additional space from the preceding free chunk.
- * (3) Or both
- *
- * If the request is for more space but the current chunk cannot be
- * extended, then malloc a new buffer, copy the data into the new buffer,
- * and free the old buffer.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-FAR void *realloc(FAR void *oldmem, size_t size)
-{
- return mm_realloc(&g_mmheap, oldmem, size);
-}
-#endif
diff --git a/nuttx/mm/mm_zalloc.c b/nuttx/mm/mm_zalloc.c
index 805fab82d..c665adc04 100644
--- a/nuttx/mm/mm_zalloc.c
+++ b/nuttx/mm/mm_zalloc.c
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <stdlib.h>
#include <string.h>
#include <nuttx/mm.h>
@@ -60,7 +59,6 @@
*
****************************************************************************/
-#ifdef CONFIG_MM_MULTIHEAP
FAR void *mm_zalloc(FAR struct mm_heap_s *heap, size_t size)
{
FAR void *alloc = mm_malloc(heap, size);
@@ -71,29 +69,3 @@ FAR void *mm_zalloc(FAR struct mm_heap_s *heap, size_t size)
return alloc;
}
-#endif
-
-/****************************************************************************
- * Name: zalloc
- *
- * Description:
- * zalloc calls malloc, then zeroes out the allocated chunk.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_MM_USER_HEAP
-FAR void *zalloc(size_t size)
-{
-#ifdef CONFIG_MM_MULTIHEAP
- return mm_zalloc(&g_mmheap, size);
-#else
- FAR void *alloc = malloc(size);
- if (alloc)
- {
- memset(alloc, 0, size);
- }
-
- return alloc;
-#endif
-}
-#endif
diff --git a/nuttx/mm/umm_calloc.c b/nuttx/mm/umm_calloc.c
new file mode 100644
index 000000000..fd3ac60f2
--- /dev/null
+++ b/nuttx/mm/umm_calloc.c
@@ -0,0 +1,69 @@
+/****************************************************************************
+ * mm/umm_calloc.c
+ *
+ * Copyright (C) 2007, 2009, 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: calloc
+ *
+ * Description:
+ * calloc is a thin wrapper for mm_calloc()
+ *
+ ****************************************************************************/
+
+FAR void *calloc(size_t n, size_t elem_size)
+{
+ return mm_calloc(&g_mmheap, n, elem_size);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_free.c b/nuttx/mm/umm_free.c
new file mode 100644
index 000000000..366bf4560
--- /dev/null
+++ b/nuttx/mm/umm_free.c
@@ -0,0 +1,74 @@
+/****************************************************************************
+ * mm/umm_free.c
+ *
+ * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: free
+ *
+ * Description:
+ * Returns a chunk of user memory to the list of free nodes, merging with
+ * adjacent free chunks if possible.
+ *
+ ****************************************************************************/
+
+void free(FAR void *mem)
+{
+ mm_free(&g_mmheap, mem);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_mallinfo.c b/nuttx/mm/umm_mallinfo.c
new file mode 100644
index 000000000..9ef03aec7
--- /dev/null
+++ b/nuttx/mm/umm_mallinfo.c
@@ -0,0 +1,90 @@
+/****************************************************************************
+ * mm/umm_mallinfo.c
+ *
+ * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mallinfo
+ *
+ * Description:
+ * mallinfo returns a copy of updated current heap information for the
+ * user heap.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+
+struct mallinfo mallinfo(void)
+{
+ struct mallinfo info;
+ mm_mallinfo(&g_mmheap, &info);
+ return info;
+}
+
+#else
+
+int mallinfo(struct mallinfo *info)
+{
+ return mm_mallinfo(&g_mmheap, info);
+}
+
+#endif /* CONFIG_CAN_PASS_STRUCTS */
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_malloc.c b/nuttx/mm/umm_malloc.c
new file mode 100644
index 000000000..6d08fbc29
--- /dev/null
+++ b/nuttx/mm/umm_malloc.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * mm/umm_malloc.c
+ *
+ * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * Name: malloc
+ *
+ * Description:
+ * Allocate memory from the user 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 *malloc(size_t size)
+{
+ return mm_malloc(&g_mmheap, size);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_memalign.c b/nuttx/mm/umm_memalign.c
new file mode 100644
index 000000000..429b81f89
--- /dev/null
+++ b/nuttx/mm/umm_memalign.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * mm/umm_memalign.c
+ *
+ * Copyright (C) 2007, 2009, 2011, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: memalign
+ *
+ * Description:
+ * memalign requests more than enough space from malloc, finds a region
+ * within that chunk that meets the alignment request and then frees any
+ * leading or trailing space.
+ *
+ * The alignment argument must be a power of two (not checked). 8-byte
+ * alignment is guaranteed by normal malloc calls.
+ *
+ ****************************************************************************/
+
+FAR void *memalign(size_t alignment, size_t size)
+{
+ return mm_memalign(&g_mmheap, alignment, size);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_realloc.c b/nuttx/mm/umm_realloc.c
new file mode 100644
index 000000000..4f5391938
--- /dev/null
+++ b/nuttx/mm/umm_realloc.c
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * mm/mm_realloc.c
+ *
+ * Copyright (C) 2007, 2009, 2013-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: krealloc
+ *
+ * Description:
+ * Re-allocate memory in the user 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 *realloc(FAR void *oldmem, size_t size)
+{
+ return mm_realloc(&g_mmheap, oldmem, size);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */
diff --git a/nuttx/mm/umm_zalloc.c b/nuttx/mm/umm_zalloc.c
new file mode 100644
index 000000000..84da8c37b
--- /dev/null
+++ b/nuttx/mm/umm_zalloc.c
@@ -0,0 +1,75 @@
+/****************************************************************************
+ * mm/mm_zalloc.c
+ *
+ * Copyright (C) 2007, 2009, 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
+
+#ifdef CONFIG_MM_USER_HEAP
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************
+ * Name: kzalloc
+ *
+ * Description:
+ * Allocate and zero memory from the user 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 *zalloc(size_t size)
+{
+ return mm_zalloc(&g_mmheap, size);
+}
+
+#endif /* CONFIG_MM_USER_HEAP */