aboutsummaryrefslogtreecommitdiff
path: root/nuttx/mm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:18:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:18:44 +0000
commit57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff (patch)
tree25d07d14e920d31c0b1947c9ca586f2a01fc32d8 /nuttx/mm
downloadpx4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.tar.gz
px4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.tar.bz2
px4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.zip
Resync new repository with old repo r5166
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5153 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/mm')
-rw-r--r--nuttx/mm/Kconfig85
-rw-r--r--nuttx/mm/Makefile81
-rw-r--r--nuttx/mm/Makefile.test64
-rw-r--r--nuttx/mm/README.txt71
-rw-r--r--nuttx/mm/mm_addfreechunk.c91
-rw-r--r--nuttx/mm/mm_calloc.c69
-rw-r--r--nuttx/mm/mm_environment.h131
-rw-r--r--nuttx/mm/mm_free.c153
-rw-r--r--nuttx/mm/mm_gran.h132
-rw-r--r--nuttx/mm/mm_granalloc.c358
-rw-r--r--nuttx/mm/mm_grancritical.c116
-rw-r--r--nuttx/mm/mm_granfree.c170
-rw-r--r--nuttx/mm/mm_graninit.c231
-rw-r--r--nuttx/mm/mm_initialize.c216
-rw-r--r--nuttx/mm/mm_internal.h243
-rw-r--r--nuttx/mm/mm_mallinfo.c146
-rw-r--r--nuttx/mm/mm_malloc.c201
-rw-r--r--nuttx/mm/mm_memalign.c208
-rw-r--r--nuttx/mm/mm_realloc.c352
-rw-r--r--nuttx/mm/mm_sem.c247
-rw-r--r--nuttx/mm/mm_shrinkchunk.c139
-rw-r--r--nuttx/mm/mm_size2ndx.c76
-rw-r--r--nuttx/mm/mm_test.c535
-rw-r--r--nuttx/mm/mm_zalloc.c68
24 files changed, 4183 insertions, 0 deletions
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
new file mode 100644
index 000000000..5da12b65e
--- /dev/null
+++ b/nuttx/mm/Kconfig
@@ -0,0 +1,85 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config MM_SMALL
+ bool "Small memory model"
+ default n
+ ---help---
+ Each memory allocation has a small allocation overhead. The size
+ of that overhead is normally determined by the "width" of the
+ address support by the MCU. MCUs that support 16-bit addressability
+ have smaller overhead than devices that support 32-bit addressability.
+ However, there are many MCUs that support 32-bit addressability *but*
+ have internal SRAM of size less than or equal to 64Kb. In this case,
+ CONFIG_MM_SMALL can be defined so that those MCUs will also benefit
+ from the smaller, 16-bit-based allocation overhead.
+
+config MM_REGIONS
+ int "Number of memory regions"
+ default 1
+ ---help---
+ 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);
+
+config ARCH_HAVE_HEAP2
+ bool
+
+config HEAP2_BASE
+ hex "Start address of second heap region"
+ default 0x00000000
+ depends on ARCH_HAVE_HEAP2
+ ---help---
+ The base address of the second heap region.
+
+config HEAP2_SIZE
+ int "Size of the second heap region"
+ default 0
+ depends on ARCH_HAVE_HEAP2
+ ---help---
+ The size of the second heap region.
+
+config GRAN
+ bool "Enable Granule Allocator"
+ default n
+ ---help---
+ Enable granual allocator support. Allocations will be aligned to the
+ granule size; allocations will be in units of the granule size.
+ Larger granules will give better performance and less overhead but
+ more losses of memory due to alignment and quantization waste.
+
+ NOTE: The current implementation also restricts the maximum
+ allocation size to 32 granaules. That restriction could be
+ eliminated with some additional coding effort.
+
+config GRAN_SINGLE
+ bool "Single Granule Allocator"
+ default n
+ depends on GRAN
+ ---help---
+ Select if there is only one instance of the granule allocator (i.e.,
+ gran_initialize will be called only once. In this case, (1) there
+ are a few optimizations that can can be done and (2) the GRAN_HANDLE
+ is not needed.
+
+config GRAN_INTR
+ bool "Interrupt level support"
+ default n
+ depends on GRAN
+ ---help---
+ Normally mutual exclusive access to granule allocator data is assured
+ using a semaphore. If this option is set then, instead, mutual
+ exclusion logic will disable interrupts. While this options is more
+ invasive to system performance, it will also support use of the granule
+ allocator from interrupt level logic.
+
+config DEBUG_GRAN
+ bool "Granule Allocator Debug"
+ default n
+ depends on GRAN && DEBUG
+ ---help---
+ Just like CONFIG_DEBUG_MM, but only generates ouput from the gran
+ allocation logic.
diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
new file mode 100644
index 000000000..0ccf5a09a
--- /dev/null
+++ b/nuttx/mm/Makefile
@@ -0,0 +1,81 @@
+############################################################################
+# mm/Makefile
+#
+# Copyright (C) 2007, 2012 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.
+#
+############################################################################
+
+-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
+
+ifeq ($(CONFIG_GRAN),y)
+CSRCS += mm_graninit.c mm_granalloc.c mm_granfree.c mm_grancritical.c
+endif
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = libmm$(LIBEXT)
+
+all: $(BIN)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+$(BIN): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f $(BIN) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/mm/Makefile.test b/nuttx/mm/Makefile.test
new file mode 100644
index 000000000..63cab910e
--- /dev/null
+++ b/nuttx/mm/Makefile.test
@@ -0,0 +1,64 @@
+############################################################################
+# mm/Makefile.test
+#
+# Copyright (C) 2007, 2008 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.
+#
+############################################################################
+
+SRCS = mm_test.c 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
+OBJS = $(SRCS:.c=.o1)
+
+LIBS = -lpthread -lc
+
+CC = gcc
+LD = gcc
+
+DEFINES = -DMM_TEST=1
+WARNIGNS = -Wall -Wstrict-prototypes -Wshadow
+CFLAGS = -g $(DEFINES)
+LDFLAGS =
+
+BIN = ../mm_test
+
+all: $(BIN)
+
+$(OBJS): %.o1: %.c
+ @echo "Compiling $<"
+ $(CC) -c $(CFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ @echo "Linking {$(OBJS)} to produce $@"
+ $(LD) $(LDFLAGS) $(OBJS) $(LIBS) -o $@
+
+clean:
+ @rm -f $(BIN) *.o1 *~
diff --git a/nuttx/mm/README.txt b/nuttx/mm/README.txt
new file mode 100644
index 000000000..b0b80deae
--- /dev/null
+++ b/nuttx/mm/README.txt
@@ -0,0 +1,71 @@
+mm/README.txt
+=============
+
+This directory contains the NuttX memory management logic. This include:
+
+1) The standard memory management functions as prototyped in stdlib.h as
+ specified in the Base definitions volume of IEEE Std 1003.1-2001. This
+ include the files:
+
+ o Standard Interfaces: mm_malloc.c, mm_calloc.c, mm_realloc.c,
+ mm_memalign.c, mm_free.c
+ o Less-Standard Interfaces: mm_zalloc.c, mm_mallinfo.c
+ o Internal Implementation: mm_initialize.c mm_sem.c mm_addfreechunk.c
+ mm_size2ndx.c mm_shrinkchunk.c, mm_internal.h
+ o Build and Configuration files: Kconfig, Makefile
+
+ Memory Models:
+
+ o Small Memory Model. If the MCU supports only 16-bit data addressing
+ then the small memory model is automatically used. The maximum size
+ of the heap is then 64K. The small memory model can also be forced
+ MCUs with wider addressing by defining CONFIG_SMALL_MEMORY in the
+ NuttX configuration file.
+ o Large Memory Model. Otherwise, the allocator uses a model that
+ supports a heap of up to 4G.
+
+ This implementation uses a variable length allocator with the following
+ properties:
+
+ o Overhead: Either 8- or 4-bytes per allocation for large and small
+ models, respectively.
+ 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
+ in this directory The granule allocator allocates memory in units
+ of a fixed sized block ("granule"). All memory is aligned to the size
+ of one granule.
+
+ The granule allocator interfaces are defined in nuttx/include/nuttx/gran.h.
+ The granule allocator consists of these files in this directory:
+
+ mm_gran.h, mm_granalloc.c, mm_grancritical.c, mm_granfree.c
+ mm_graninit.c
+
+ The granule allocator is not used anywhere within the base NuttX code
+ as of this writing. The intent of the granule allocator is to provide
+ a tool to support platform-specific management of aligned DMA memory.
+
+ NOTE: Because each granule is aligned to the granule size and each
+ allocations is in units of the granule size, selection of the granule
+ size is important: Larger granules will give better performance and
+ less overhead but more losses of memory due to alignment and quantization
+ waste.
+
+ The current implementation also restricts the maximum allocation size
+ to 32 granules. That restriction could be eliminated with some
+ additional coding effort, but currently requires larger granule
+ sizes for larger allocations.
diff --git a/nuttx/mm/mm_addfreechunk.c b/nuttx/mm/mm_addfreechunk.c
new file mode 100644
index 000000000..fdda3ed8d
--- /dev/null
+++ b/nuttx/mm/mm_addfreechunk.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * mm/mm_addfreechunk.c
+ *
+ * Copyright (C) 2007, 2009 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_addfreechunk
+ *
+ * Description:
+ * Add a free chunk to the node next. It is assumed that the caller holds
+ * the mm semaphore
+ *
+ ****************************************************************************/
+
+void mm_addfreechunk(FAR struct mm_freenode_s *node)
+{
+ FAR struct mm_freenode_s *next;
+ FAR struct mm_freenode_s *prev;
+
+ /* Convert the size to a nodelist index */
+
+ int ndx = mm_size2ndx(node->size);
+
+ /* Now put the new node int the next */
+
+ for (prev = &g_nodelist[ndx], next = g_nodelist[ndx].flink;
+ next && next->size && next->size < node->size;
+ prev = next, next = next->flink);
+
+ /* Does it go in mid next or at the end? */
+
+ prev->flink = node;
+ node->blink = prev;
+ node->flink = next;
+
+ if (next)
+ {
+ /* The new node goes between prev and next */
+
+ next->blink = node;
+ }
+}
diff --git a/nuttx/mm/mm_calloc.c b/nuttx/mm/mm_calloc.c
new file mode 100644
index 000000000..576081a16
--- /dev/null
+++ b/nuttx/mm/mm_calloc.c
@@ -0,0 +1,69 @@
+/****************************************************************************
+ * mm/mm_calloc.c
+ *
+ * Copyright (C) 2007, 2009 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: calloc
+ *
+ * Descripton:
+ * calloc calculates the size of the allocation and calls zalloc
+ *
+ ****************************************************************************/
+
+FAR void *calloc(size_t n, size_t elem_size)
+{
+ FAR void *ret = NULL;
+
+ if (n > 0 && elem_size > 0)
+ {
+ ret = zalloc(n * elem_size);
+ }
+
+ return ret;
+}
diff --git a/nuttx/mm/mm_environment.h b/nuttx/mm/mm_environment.h
new file mode 100644
index 000000000..d28fbf1d7
--- /dev/null
+++ b/nuttx/mm/mm_environment.h
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * mm/mm_environment.h
+ *
+ * Copyright (C) 2007-2009, 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.
+ *
+ ****************************************************************************/
+
+#ifndef __MM_MM_ENVIRONMENT_H
+#define __MM_MM_ENVIRONMENT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* The platform configuratioin file will not be included when the memory
+ * manager is built for the host-based test harness.
+ */
+
+#ifndef MM_TEST
+# include <nuttx/config.h>
+# include <nuttx/compiler.h>
+# include <sys/types.h>
+# include <stdlib.h>
+# include <string.h>
+# include <debug.h>
+# include <errno.h>
+# include <assert.h>
+# include <nuttx/mm.h>
+#else
+# include <sys/types.h>
+# include <string.h>
+# include <assert.h>
+#endif
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Special definitions used when the memory mnager is built for the host-
+ * based test harness.
+ */
+
+#ifdef MM_TEST
+
+/* Fake NuttX dependencies */
+
+# define FAR /* Normally in compiler.h */
+# define CONFIG_CPP_HAVE_VARARGS 1 /* Normally in compiler.h */
+# define CONFIG_MM_REGIONS 2 /* Normally in config.h */
+# undef CONFIG_MM_SMALL /* Normally in config.h */
+# define CONFIG_CAN_PASS_STRUCTS 1 /* Normally in config.h */
+# undef CONFIG_SMALL_MEMORY /* Normally in config.h */
+
+extern void mm_addregion(FAR void *heapstart, size_t heapsize);
+
+/* Use the real system errno */
+
+# define mm_errno errno
+
+/* When built for the test harness, we change the names of the exported
+ * functions so that they do not collide with the host libc names.
+ */
+
+# define malloc mm_malloc
+# define memalign mm_memalign
+# define realloc mm_realloc
+# define zalloc mm_zalloc
+# define calloc mm_calloc
+# define free mm_free
+
+/* Use normal libc assertion functions */
+
+# undef ASSERT
+# define ASSERT(e) assert(e)
+# undef DEBUGASSERT
+# define DEBUGASSERT(e) assert(e)
+
+/* Debug macros are always on */
+
+# define CONFIG_DEBUG 1
+
+# undef mdbg
+# define mdbg(format, arg...) printf(format, ##arg)
+# undef mvdg
+# define mvdbg(format, arg...) printf(format, ##arg)
+# undef mlldbg
+# define mlldbg(format, arg...) printf(format, ##arg)
+# undef mllvdg
+# define mllvdbg(format, arg...) printf(format, ##arg)
+
+#else
+# define mm_errno get_errno()
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __MM_MM_ENVIRONMENT_H */
diff --git a/nuttx/mm/mm_free.c b/nuttx/mm/mm_free.c
new file mode 100644
index 000000000..b34b8a459
--- /dev/null
+++ b/nuttx/mm/mm_free.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * mm/mm_free.c
+ *
+ * Copyright (C) 2007, 2009 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 <assert.h>
+
+#include "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: free
+ *
+ * Description:
+ * Returns a chunk of memory into the list of free nodes, merging with
+ * adjacent free chunks if possible.
+ *
+ ****************************************************************************/
+
+void free(FAR void *mem)
+{
+ FAR struct mm_freenode_s *node;
+ FAR struct mm_freenode_s *prev;
+ FAR struct mm_freenode_s *next;
+
+ mvdbg("Freeing %p\n", mem);
+
+ /* Protect against attempts to free a NULL reference */
+
+ if (!mem)
+ {
+ return;
+ }
+
+ /* We need to hold the MM semaphore while we muck with the
+ * nodelist.
+ */
+
+ mm_takesemaphore();
+
+ /* Map the memory chunk into a free node */
+
+ node = (FAR struct mm_freenode_s *)((char*)mem - SIZEOF_MM_ALLOCNODE);
+ node->preceding &= ~MM_ALLOC_BIT;
+
+ /* Check if the following node is free and, if so, merge it */
+
+ next = (FAR struct mm_freenode_s *)((char*)node + node->size);
+ if ((next->preceding & MM_ALLOC_BIT) == 0)
+ {
+ FAR struct mm_allocnode_s *andbeyond;
+
+ /* Get the node following the next node (which will
+ * become the new next node). We know that we can never
+ * index past the tail chunk because it is always allocated.
+ */
+
+ andbeyond = (FAR struct mm_allocnode_s*)((char*)next + next->size);
+
+ /* Remove the next node. There must be a predecessor,
+ * but there may not be a successor node.
+ */
+
+ DEBUGASSERT(next->blink);
+ next->blink->flink = next->flink;
+ if (next->flink)
+ {
+ next->flink->blink = next->blink;
+ }
+
+ /* Then merge the two chunks */
+
+ node->size += next->size;
+ andbeyond->preceding = node->size | (andbeyond->preceding & MM_ALLOC_BIT);
+ next = (FAR struct mm_freenode_s *)andbeyond;
+ }
+
+ /* Check if the preceding node is also free and, if so, merge
+ * it with this node
+ */
+
+ prev = (FAR struct mm_freenode_s *)((char*)node - node->preceding);
+ if ((prev->preceding & MM_ALLOC_BIT) == 0)
+ {
+ /* Remove the node. There must be a predecessor, but there may
+ * not be a successor node.
+ */
+
+ DEBUGASSERT(prev->blink);
+ prev->blink->flink = prev->flink;
+ if (prev->flink)
+ {
+ prev->flink->blink = prev->blink;
+ }
+
+ /* Then merge the two chunks */
+
+ prev->size += node->size;
+ next->preceding = prev->size | (next->preceding & MM_ALLOC_BIT);
+ node = prev;
+ }
+
+ /* Add the merged node to the nodelist */
+
+ mm_addfreechunk(node);
+ mm_givesemaphore();
+}
diff --git a/nuttx/mm/mm_gran.h b/nuttx/mm/mm_gran.h
new file mode 100644
index 000000000..a4f51490d
--- /dev/null
+++ b/nuttx/mm/mm_gran.h
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * mm/mm_gran.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __MM_MM_GRAN_H
+#define __MM_MM_GRAN_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <semaphore.h>
+
+#include <arch/types.h>
+#include <nuttx/gran.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Sizes of things */
+
+#define SIZEOF_GAT(n) \
+ ((n + 31) >> 5)
+#define SIZEOF_GRAN_S(n) \
+ (sizeof(struct gran_s) + sizeof(uint32_t) * (SIZEOF_GAT(n) - 1))
+
+/* Debug */
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG_GRAM
+# define gramdbg(format, arg...) dbg(format, ##arg)
+# define gramvdbg(format, arg...) vdbg(format, ##arg)
+# else
+# define gramdbg(format, arg...) mdbg(format, ##arg)
+# define gramvdbg(format, arg...) mvdbg(format, ##arg)
+# endif
+#else
+# ifdef CONFIG_DEBUG_GRAM
+# define gramdbg dbg
+# define gramvdbg vdbg
+# else
+# define gramdbg (void)
+# define gramvdbg (void)
+# endif
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* This structure represents the state of on granual allocation */
+
+struct gran_s
+{
+ uint8_t log2gran; /* Log base 2 of the size of one granule */
+ uint16_t ngranules; /* The total number of (aligned) granules in the heap */
+#ifdef CONFIG_GRAN_INTR
+ irqstate_t irqstate; /* For exclusive access to the GAT */
+#else
+ sem_t exclsem; /* For exclusive access to the GAT */
+#endif
+ uintptr_t heapstart; /* The aligned start of the granule heap */
+ uint32_t gat[1]; /* Start of the granule allocation table */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* State of the single GRAN allocator */
+
+#ifdef CONFIG_GRAN_SINGLE
+extern FAR struct gran_s *g_graninfo;
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_enter_critical and gran_leave_critical
+ *
+ * Description:
+ * Critical section management for the granule allocator.
+ *
+ * Input Parameters:
+ * priv - Pointer to the gran state
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void gran_enter_critical(FAR struct gran_s *priv);
+void gran_leave_critical(FAR struct gran_s *priv);
+
+#endif /* __MM_MM_GRAN_H */
diff --git a/nuttx/mm/mm_granalloc.c b/nuttx/mm/mm_granalloc.c
new file mode 100644
index 000000000..e95709b31
--- /dev/null
+++ b/nuttx/mm/mm_granalloc.c
@@ -0,0 +1,358 @@
+/****************************************************************************
+ * mm/mm_granalloc.c
+ *
+ * Copyright (C) 2012 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 <nuttx/gran.h>
+
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_common_alloc
+ *
+ * Description:
+ * Allocate memory from the granule heap.
+ *
+ * Input Parameters:
+ * priv - The granule heap state structure.
+ * alloc - The adress of the allocation.
+ * ngranules - The number of granules allocated
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void gran_mark_allocated(FAR struct gran_s *priv,
+ uintptr_t alloc,
+ unsigned int ngranules)
+{
+ unsigned int granno;
+ unsigned int gatidx;
+ unsigned int gatbit;
+ unsigned int avail;
+ uint32_t gatmask;
+
+ /* Determine the granule number of the allocation */
+
+ granno = (alloc - priv->heapstart) >> priv->log2gran;
+
+ /* Determine the GAT table index associated with the allocation */
+
+ gatidx = granno >> 5;
+ gatbit = granno & 31;
+
+ /* Mark bits in the GAT entry or entries */
+
+ avail = 32 - gatbit;
+ if (ngranules > avail)
+ {
+ /* Mark bits in the first GAT entry */
+
+ gatmask =0xffffffff << gatbit;
+ DEBUGASSERT((priv->gat[gatidx] & gatmask) == 0);
+
+ priv->gat[gatidx] |= gatmask;
+ ngranules -= avail;
+
+ /* Mark bits in the second GAT entry */
+
+ gatmask = 0xffffffff >> (32 - ngranules);
+ DEBUGASSERT((priv->gat[gatidx+1] & gatmask) == 0);
+
+ priv->gat[gatidx+1] |= gatmask;
+ }
+
+ /* Handle the case where where all of the granules come from one entry */
+
+ else
+ {
+ /* Mark bits in a single GAT entry */
+
+ gatmask = 0xffffffff >> (32 - ngranules);
+ gatmask <<= gatbit;
+ DEBUGASSERT((priv->gat[gatidx] & gatmask) == 0);
+
+ priv->gat[gatidx] |= gatmask;
+ return;
+ }
+
+}
+
+/****************************************************************************
+ * Name: gran_common_alloc
+ *
+ * Description:
+ * Allocate memory from the granule heap.
+ *
+ * Input Parameters:
+ * priv - The granule heap state structure.
+ * size - The size of the memory region to allocate.
+ *
+ * Returned Value:
+ * On success, a non-NULL pointer to the allocated memory is returned.
+ *
+ ****************************************************************************/
+
+static inline FAR void *gran_common_alloc(FAR struct gran_s *priv, size_t size)
+{
+ unsigned int ngranules;
+ size_t tmpmask;
+ uintptr_t alloc;
+ uint32_t curr;
+ uint32_t next;
+ uint32_t mask;
+ int granidx;
+ int gatidx;
+ int bitidx;
+ int shift;
+
+ DEBUGASSERT(priv && size <= 32 * (1 << priv->log2gran));
+
+ if (priv && size > 0)
+ {
+ /* Get exclusive access to the GAT */
+
+ gran_enter_critical(priv);
+
+ /* How many contiguous granules we we need to find? */
+
+ tmpmask = (1 << priv->log2gran) - 1;
+ ngranules = (size + tmpmask) >> priv->log2gran;
+
+ /* Then create mask for that number of granules */
+
+ DEBUGASSERT(ngranules <= 32);
+ mask = 0xffffffff >> (32 - ngranules);
+
+ /* Now search the granule allocation table for that number of contiguous */
+
+ alloc = priv->heapstart;
+
+ for (granidx = 0; granidx < priv->ngranules; granidx += 32)
+ {
+ /* Get the GAT index associated with the granule table entry */
+
+ gatidx = granidx >> 5;
+ curr = priv->gat[gatidx];
+
+ /* Handle the case where there are no free granules in the entry */
+
+ if (curr == 0xffffffff)
+ {
+ alloc += (32 << priv->log2gran);
+ continue;
+ }
+
+ /* Get the next entry from the GAT to support a 64 bit shift */
+
+ if (granidx < priv->ngranules)
+ {
+ next = priv->gat[gatidx + 1];
+ }
+
+ /* Use all ones when are at the last entry in the GAT (meaning
+ * nothing can be allocated.
+ */
+
+ else
+ {
+ next = 0xffffffff;
+ }
+
+ /* Search through the allocations in the 'curr' GAT entry
+ * to see if we can satisfy the allocation starting in that
+ * entry.
+ *
+ * This loop continues until either all of the bits have been
+ * examined (bitidx >= 32), or until there are insufficient
+ * granules left to satisfy the allocation.
+ */
+
+ for (bitidx = 0;
+ bitidx < 32 && (granidx + bitidx + ngranules) <= priv->ngranules;
+ )
+ {
+ /* Break out if there are no further free bits in 'curr'.
+ * All of the zero bits might have gotten shifted out.
+ */
+
+ if (curr == 0xffffffff)
+ {
+ break;
+ }
+
+ /* Check for the first zero bit in the lower or upper 16-bits.
+ * From the test above, we know that at least one of the 32-
+ * bits in 'curr' is zero.
+ */
+
+ else if ((curr & 0x0000ffff) == 0x0000ffff)
+ {
+ /* Not in the lower 16 bits. The first free bit must be
+ * in the upper 16 bits.
+ */
+
+ shift = 16;
+ }
+
+ /* We know that the first free bit is now within the lower 16
+ * bits of 'curr'. Is it in the upper or lower byte?
+ */
+
+ else if ((curr & 0x0000ff) == 0x000000ff)
+ {
+ /* Not in the lower 8 bits. The first free bit must be in
+ * the upper 8 bits.
+ */
+
+ shift = 8;
+ }
+
+ /* We know that the first free bit is now within the lower 4
+ * bits of 'curr'. Is it in the upper or lower nibble?
+ */
+
+ else if ((curr & 0x00000f) == 0x0000000f)
+ {
+ /* Not in the lower 4 bits. The first free bit must be in
+ * the upper 4 bits.
+ */
+
+ shift = 4;
+ }
+
+ /* We know that the first free bit is now within the lower 4 bits
+ * of 'curr'. Is it in the upper or lower pair?
+ */
+
+ else if ((curr & 0x000003) == 0x00000003)
+ {
+ /* Not in the lower 2 bits. The first free bit must be in
+ * the upper 2 bits.
+ */
+
+ shift = 2;
+ }
+
+ /* We know that the first free bit is now within the lower 4 bits
+ * of 'curr'. Check if we have the allocation at this bit position.
+ */
+
+ else if ((curr & mask) == 0)
+ {
+ /* Yes.. mark these granules allocated */
+
+ gran_mark_allocated(priv, alloc, ngranules);
+
+ /* And return the allocation address */
+
+ gran_leave_critical(priv);
+ return (FAR void *)alloc;
+ }
+
+ /* The free allocation does not start at this position */
+
+ else
+ {
+ shift = 1;
+ }
+
+ /* Set up for the next time through the loop. Perform a 64
+ * bit shift to move to the next gram position andi ncrement
+ * to the next candidate allocation address.
+ */
+
+ alloc += (shift << priv->log2gran);
+ curr = (curr >> shift) | (next << (32 - shift));
+ next >>= shift;
+ bitidx += shift;
+ }
+ }
+ }
+
+ gran_leave_critical(priv);
+ return NULL;
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_alloc
+ *
+ * Description:
+ * Allocate memory from the granule heap.
+ *
+ * NOTE: The current implementation also restricts the maximum allocation
+ * size to 32 granules. That restriction could be eliminated with some
+ * additional coding effort.
+ *
+ * Input Parameters:
+ * handle - The handle previously returned by gran_initialize
+ * size - The size of the memory region to allocate.
+ *
+ * Returned Value:
+ * On success, either a non-NULL pointer to the allocated memory (if
+ * CONFIG_GRAN_SINGLE) or zero (if !CONFIG_GRAN_SINGLE) is returned.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+FAR void *gran_alloc(size_t size)
+{
+ return gran_common_alloc(g_graninfo, size);
+}
+#else
+FAR void *gran_alloc(GRAN_HANDLE handle, size_t size)
+{
+ return gran_common_alloc((FAR struct gran_s *)handle, size);
+}
+#endif
+
+#endif /* CONFIG_GRAN */
diff --git a/nuttx/mm/mm_grancritical.c b/nuttx/mm/mm_grancritical.c
new file mode 100644
index 000000000..190aa3e7d
--- /dev/null
+++ b/nuttx/mm/mm_grancritical.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * mm/mm_grancritical.c
+ *
+ * Copyright (C) 2012 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 <assert.h>
+#include <errno.h>
+
+#include <arch/irq.h>
+#include <nuttx/gran.h>
+
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_enter_critical and gran_leave_critical
+ *
+ * Description:
+ * Critical section management for the granule allocator.
+ *
+ * Input Parameters:
+ * priv - Pointer to the gran state
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void gran_enter_critical(FAR struct gran_s *priv)
+{
+#ifdef CONFIG_GRAN_INTR
+ priv->irqstate = irqsave();
+#else
+ int ret;
+
+ /* Continue waiting if we are awakened by a signal */
+
+ do
+ {
+ ret = sem_wait(&priv->exclsem);
+ if (ret < 0)
+ {
+ DEBUGASSERT(errno == EINTR);
+ }
+ }
+ while (ret < 0);
+#endif
+}
+
+void gran_leave_critical(FAR struct gran_s *priv)
+{
+#ifdef CONFIG_GRAN_INTR
+ irqrestore(priv->irqstate);
+#else
+ sem_post(&priv->exclsem);
+#endif
+}
+
+
+#endif /* CONFIG_GRAN */
+
+
diff --git a/nuttx/mm/mm_granfree.c b/nuttx/mm/mm_granfree.c
new file mode 100644
index 000000000..fcab11af9
--- /dev/null
+++ b/nuttx/mm/mm_granfree.c
@@ -0,0 +1,170 @@
+/****************************************************************************
+ * mm/mm_granfree.c
+ *
+ * Copyright (C) 2012 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 <nuttx/gran.h>
+
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_common_free
+ *
+ * Description:
+ * Return memory to the granule heap.
+ *
+ * Input Parameters:
+ * handle - The handle previously returned by gran_initialize
+ * memory - A pointer to memory previoiusly allocated by gran_alloc.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void gran_common_free(FAR struct gran_s *priv,
+ FAR void *memory, size_t size)
+{
+ unsigned int granno;
+ unsigned int gatidx;
+ unsigned int gatbit;
+ unsigned int granmask;
+ unsigned int ngranules;
+ unsigned int avail;
+ uint32_t gatmask;
+
+ DEBUGASSERT(priv && memory && size <= 32 * (1 << priv->log2gran));
+
+ /* Get exclusive access to the GAT */
+
+ gran_enter_critical(priv);
+
+ /* Determine the granule number of the first granule in the allocation */
+
+ granno = ((uintptr_t)memory - priv->heapstart) >> priv->log2gran;
+
+ /* Determine the GAT table index and bit number associated with the
+ * allocation.
+ */
+
+ gatidx = granno >> 5;
+ gatbit = granno & 31;
+
+ /* Determine the number of granules in the allocation */
+
+ granmask = (1 << priv->log2gran) - 1;
+ ngranules = (size + granmask) >> priv->log2gran;
+
+ /* Clear bits in the GAT entry or entries */
+
+ avail = 32 - gatbit;
+ if (ngranules > avail)
+ {
+ /* Clear bits in the first GAT entry */
+
+ gatmask = (0xffffffff << gatbit);
+ DEBUGASSERT((priv->gat[gatidx] & gatmask) == gatmask);
+
+ priv->gat[gatidx] &= ~gatmask;
+ ngranules -= avail;
+
+ /* Clear bits in the second GAT entry */
+
+ gatmask = 0xffffffff >> (32 - ngranules);
+ DEBUGASSERT((priv->gat[gatidx+1] & gatmask) == gatmask);
+
+ priv->gat[gatidx+1] &= ~gatmask;
+ }
+
+ /* Handle the case where where all of the granules came from one entry */
+
+ else
+ {
+ /* Clear bits in a single GAT entry */
+
+ gatmask = 0xffffffff >> (32 - ngranules);
+ gatmask <<= gatbit;
+ DEBUGASSERT((priv->gat[gatidx] & gatmask) == gatmask);
+
+ priv->gat[gatidx] &= ~gatmask;
+ }
+
+ gran_leave_critical(priv);
+}
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_free
+ *
+ * Description:
+ * Return memory to the granule heap.
+ *
+ * Input Parameters:
+ * handle - The handle previously returned by gran_initialize
+ * memory - A pointer to memory previoiusly allocated by gran_alloc.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+void gran_free(FAR void *memory, size_t size)
+{
+ return gran_common_free(g_graninfo, memory, size);
+}
+#else
+void gran_free(GRAN_HANDLE handle, FAR void *memory, size_t size)
+{
+ return gran_common_free((FAR struct gran_s *)handle, memory, size);
+}
+#endif
+
+#endif /* CONFIG_GRAN */
diff --git a/nuttx/mm/mm_graninit.c b/nuttx/mm/mm_graninit.c
new file mode 100644
index 000000000..16cebdcf3
--- /dev/null
+++ b/nuttx/mm/mm_graninit.c
@@ -0,0 +1,231 @@
+/****************************************************************************
+ * mm/mm_graninit.c
+ *
+ * Copyright (C) 2012 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 <assert.h>
+#include <errno.h>
+
+#include <nuttx/gran.h>
+
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* State of the single GRAN allocator */
+
+#ifdef CONFIG_GRAN_SINGLE
+FAR struct gran_s *g_graninfo;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_common_initialize
+ *
+ * Description:
+ * Perfrom common GRAN initialization.
+ *
+ * Input Parameters:
+ * info - Private granule data structure pointer
+ * heapstart - Start of the granule allocation heap
+ * heapsize - Size of heap in bytes
+ * log2gran - Log base 2 of the size of one granule. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc.
+ * log2align - Log base 2 of required alignment. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc. Note that
+ * log2gran must be greater than or equal to log2align
+ * so that all contiguous granules in memory will meet
+ * the minimum alignment requirement. A value of zero
+ * would mean that no alignment is required.
+ *
+ * Returned Value:
+ * On success, a non-NULL info structure is returned that may be used with
+ * other granule allocator interfaces.
+ *
+ ****************************************************************************/
+
+static inline FAR struct gran_s *
+gran_common_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran,
+ uint8_t log2align)
+{
+ FAR struct gran_s *priv;
+ uintptr_t heapend;
+ uintptr_t alignedstart;
+ unsigned int mask;
+ unsigned int alignedsize;
+ unsigned int ngranules;
+
+ /* Check parameters if debug is on. Note the the size of a granual is
+ * limited to 2**31 bytes and that the size of the granule must be greater
+ * than the alignment size.
+ */
+
+ DEBUGASSERT(heapstart && heapsize > 0 &&
+ log2gran > 0 && log2gran < 32 &&
+ log2gran > log2align);
+
+ /* Get the aligned start of the heap */
+
+ mask = (1 << log2align) - 1;
+ alignedstart = ((uintptr_t)heapstart + mask) & ~mask;
+
+ /* Determine the number of granules */
+
+ mask = (1 << log2gran) - 1;
+ heapend = (uintptr_t)heapstart + heapsize;
+ alignedsize = (heapend - alignedstart) & ~mask;
+ ngranules = alignedsize >> log2gran;
+
+ /* Allocate the information structure with a granule table of the
+ * correct size.
+ */
+
+ priv = ( FAR struct gran_s *)zalloc(SIZEOF_GRAN_S(ngranules));
+ if (priv)
+ {
+ /* Initialize non-zero elements of the granules heap info structure */
+
+ priv->log2gran = log2gran;
+ priv->ngranules = ngranules;
+ priv->heapstart = alignedstart;
+
+ /* Initialize mutual exclusion support */
+
+#ifndef CONFIG_GRAN_INTR
+ sem_init(&priv->exclsem, 0, 1);
+#endif
+ }
+
+ return priv;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gran_initialize
+ *
+ * Description:
+ * Set up one granule allocator instance. Allocations will be aligned to
+ * the alignment size (log2align; allocations will be in units of the
+ * granule size (log2gran). Larger granules will give better performance
+ * and less overhead but more losses of memory due to alignment
+ * quantization waste. Additional memory waste can occur form alignment;
+ * log2align should be set to 0 unless you are using the granule allocator
+ * to manage DMA memory and your hardware has specific memory alignment
+ * requirements.
+ *
+ * Geneneral Usage Summary. This is an example using the GCC section
+ * attribute to position a DMA heap in memory (logic in the linker script
+ * would assign the section .dmaheap to the DMA memory.
+ *
+ * FAR uint32_t g_dmaheap[DMAHEAP_SIZE] __attribute__((section(.dmaheap)));
+ *
+ * The heap is created by calling gran_initialize(). Here the granual size
+ * is set to 64 bytes (2**6) and the alignment to 16 bytes (2**4):
+ *
+ * GRAN_HANDLE handle = gran_initialize(g_dmaheap, DMAHEAP_SIZE, 6, 4);
+ *
+ * Then the GRAN_HANDLE can be used to allocate memory (There is no
+ * GRAN_HANDLE if CONFIG_GRAN_SINGLE=y):
+ *
+ * FAR uint8_t *dma_memory = (FAR uint8_t *)gran_alloc(handle, 47);
+ *
+ * The actual memory allocates will be 64 byte (wasting 17 bytes) and
+ * will be aligned at least to (1 << log2align).
+ *
+ * NOTE: The current implementation also restricts the maximum allocation
+ * size to 32 granules. That restriction could be eliminated with some
+ * additional coding effort.
+ *
+ * Input Parameters:
+ * heapstart - Start of the granule allocation heap
+ * heapsize - Size of heap in bytes
+ * log2gran - Log base 2 of the size of one granule. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc.
+ * log2align - Log base 2 of required alignment. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc. Note that
+ * log2gran must be greater than or equal to log2align
+ * so that all contiguous granules in memory will meet
+ * the minimum alignment requirement. A value of zero
+ * would mean that no alignment is required.
+ *
+ * Returned Value:
+ * On success, a non-NULL handle is returned that may be used with other
+ * granual allocator interfaces.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+int gran_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran,
+ uint8_t log2align)
+int gran_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran)
+{
+ g_graninfo = gran_common_initialize(heapstart, heapsize, log2gran,
+ log2align);
+ if (!g_graninfo)
+ {
+ return -ENOMEM;
+ }
+
+ return OK;
+}
+#else
+GRAN_HANDLE gran_initialize(FAR void *heapstart, size_t heapsize,
+ uint8_t log2gran, uint8_t log2align)
+{
+ return (GRAN_HANDLE)gran_common_initialize(heapstart, heapsize,
+ log2gran, log2align);
+}
+#endif
+
+#endif /* CONFIG_GRAN */
diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c
new file mode 100644
index 000000000..3a21d1759
--- /dev/null
+++ b/nuttx/mm/mm_initialize.c
@@ -0,0 +1,216 @@
+/****************************************************************************
+ * mm/mm_initialize.c
+ *
+ * Copyright (C) 2007, 2009, 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/* This is the size of the heap provided to mm */
+
+size_t g_heapsize;
+
+/* This is the first and last nodes of the heap */
+
+FAR struct mm_allocnode_s *g_heapstart[CONFIG_MM_REGIONS];
+FAR struct mm_allocnode_s *g_heapend[CONFIG_MM_REGIONS];
+
+#if CONFIG_MM_REGIONS > 1
+int g_nregions;
+#endif
+
+/* All free nodes are maintained in a doubly linked list. This array
+ * provides some hooks into the list at various points to speed searches for
+ * free nodes.
+ */
+
+FAR struct mm_freenode_s g_nodelist[MM_NNODES];
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_initialize
+ *
+ * Description:
+ * This is an internal OS function called only at power-up boot time.
+ *
+ * Parameters:
+ * heapstart - Start of the initial heap region
+ * heapsize - Size of the initial heap region
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void mm_initialize(FAR void *heapstart, size_t heapsize)
+{
+ int i;
+
+ mlldbg("Heap: start=%p size=%u\n", heapstart, heapsize);
+
+ /* The following two lines have cause problems for some ZiLog compilers
+ * in the past. Life is easier if we just the suppress them for those
+ * tools.
+ */
+
+#ifndef __ZILOG__
+ CHECK_ALLOCNODE_SIZE;
+ CHECK_FREENODE_SIZE;
+#endif
+
+ /* Set up global variables */
+
+ g_heapsize = 0;
+
+#if CONFIG_MM_REGIONS > 1
+ g_nregions = 0;
+#endif
+
+ /* Initialize the node array */
+
+ memset(g_nodelist, 0, sizeof(struct mm_freenode_s) * MM_NNODES);
+ for (i = 1; i < MM_NNODES; i++)
+ {
+ g_nodelist[i-1].flink = &g_nodelist[i];
+ g_nodelist[i].blink = &g_nodelist[i-1];
+ }
+
+ /* Initialize the malloc semaphore to one (to support one-at-
+ * a-time access to private data sets).
+ */
+
+ mm_seminitialize();
+
+ /* Add the initial region of memory to the heap */
+
+ mm_addregion(heapstart, heapsize);
+}
+
+/****************************************************************************
+ * Name: mm_addregion
+ *
+ * Description:
+ * This function gives a region of contiguous memory to the memory manager
+ *
+ * Parameters:
+ * heapstart - Start of the heap region
+ * heapsize - Size of the heap region
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void mm_addregion(FAR void *heapstart, size_t heapsize)
+{
+ FAR struct mm_freenode_s *node;
+ uintptr_t heapbase;
+ uintptr_t heapend;
+#if CONFIG_MM_REGIONS > 1
+ int IDX = g_nregions;
+#else
+# define IDX 0
+#endif
+
+ /* If the MCU handles wide addresses but the memory manager is configured
+ * for a small heap, then verify that the caller is not doing something
+ * crazy.
+ */
+
+#if defined(CONFIG_MM_SMALL) && !defined(CONFIG_SMALL_MEMORY)
+ DEBUGASSERT(heapsize <= MMSIZE_MAX+1);
+#endif
+
+ /* Adjust the provide heap start and size so that they are both aligned
+ * with the MM_MIN_CHUNK size.
+ */
+
+ heapbase = MM_ALIGN_UP((uintptr_t)heapstart);
+ heapend = MM_ALIGN_DOWN((uintptr_t)heapstart + (uintptr_t)heapsize);
+ heapsize = heapend - heapbase;
+
+ mlldbg("Region %d: base=%p size=%u\n", IDX+1, heapstart, heapsize);
+
+ /* Add the size of this region to the total size of the heap */
+
+ g_heapsize += heapsize;
+
+ /* Create two "allocated" guard nodes at the beginning and end of
+ * the heap. These only serve to keep us from allocating outside
+ * of the heap.
+ *
+ * And create one free node between the guard nodes that contains
+ * all available memory.
+ */
+
+ g_heapstart[IDX] = (FAR struct mm_allocnode_s *)heapbase;
+ g_heapstart[IDX]->size = SIZEOF_MM_ALLOCNODE;
+ g_heapstart[IDX]->preceding = MM_ALLOC_BIT;
+
+ node = (FAR struct mm_freenode_s *)(heapbase + SIZEOF_MM_ALLOCNODE);
+ node->size = heapsize - 2*SIZEOF_MM_ALLOCNODE;
+ node->preceding = SIZEOF_MM_ALLOCNODE;
+
+ g_heapend[IDX] = (FAR struct mm_allocnode_s *)(heapend - SIZEOF_MM_ALLOCNODE);
+ g_heapend[IDX]->size = SIZEOF_MM_ALLOCNODE;
+ g_heapend[IDX]->preceding = node->size | MM_ALLOC_BIT;
+
+#undef IDX
+
+#if CONFIG_MM_REGIONS > 1
+ g_nregions++;
+#endif
+
+ /* Add the single, large free node to the nodelist */
+
+ mm_addfreechunk(node);
+}
diff --git a/nuttx/mm/mm_internal.h b/nuttx/mm/mm_internal.h
new file mode 100644
index 000000000..21cf253d7
--- /dev/null
+++ b/nuttx/mm/mm_internal.h
@@ -0,0 +1,243 @@
+/****************************************************************************
+ * mm/mm_internal.h
+ *
+ * Copyright (C) 2007, 2009, 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.
+ *
+ ****************************************************************************/
+
+#ifndef __MM_MM_INTERNAL_H
+#define __MM_MM_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* If the MCU has a small (16-bit) address capability, then we will use
+ * a smaller chunk header that contains 16-bit size/offset information.
+ * We will also use the smaller header on MCUs with wider addresses if
+ * CONFIG_MM_SMALL is selected. This configuration is common with MCUs
+ * that have a large FLASH space, but only a tiny internal SRAM.
+ */
+
+#ifdef CONFIG_SMALL_MEMORY
+ /* If the MCU has a small addressing capability, then for the smaller
+ * chunk header.
+ */
+
+# undef CONFIG_MM_SMALL
+# define CONFIG_MM_SMALL 1
+#endif
+
+/* Chunk Header Definitions *************************************************/
+/* These definitions define the characteristics of allocator
+ *
+ * MM_MIN_SHIFT is used to define MM_MIN_CHUNK.
+ * MM_MIN_CHUNK - is the smallest physical chunk that can
+ * be allocated. It must be at least a large as
+ * sizeof(struct mm_freenode_s). Larger values may
+ * improve performance slightly, but will waste memory
+ * due to quantization losses.
+ *
+ * MM_MAX_SHIFT is used to define MM_MAX_CHUNK
+ * MM_MAX_CHUNK is the largest, contiguous chunk of memory
+ * that can be allocated. It can range from 16-bytes to
+ * 4Gb. Larger values of MM_MAX_SHIFT can cause larger
+ * data structure sizes and, perhaps, minor performance
+ * losses.
+ */
+
+#ifdef CONFIG_MM_SMALL
+# define MM_MIN_SHIFT 4 /* 16 bytes */
+# define MM_MAX_SHIFT 15 /* 32 Kb */
+#else
+# define MM_MIN_SHIFT 4 /* 16 bytes */
+# define MM_MAX_SHIFT 22 /* 4 Mb */
+#endif
+
+/* All other definitions derive from these two */
+
+#define MM_MIN_CHUNK (1 << MM_MIN_SHIFT)
+#define MM_MAX_CHUNK (1 << MM_MAX_SHIFT)
+#define MM_NNODES (MM_MAX_SHIFT - MM_MIN_SHIFT + 1)
+
+#define MM_GRAN_MASK (MM_MIN_CHUNK-1)
+#define MM_ALIGN_UP(a) (((a) + MM_GRAN_MASK) & ~MM_GRAN_MASK)
+#define MM_ALIGN_DOWN(a) ((a) & ~MM_GRAN_MASK)
+
+/* An allocated chunk is distinguished from a free chunk by
+ * bit 31 of the 'preceding' chunk size. If set, then this is
+ * an allocated chunk.
+ */
+
+#ifdef CONFIG_MM_SMALL
+# define MM_ALLOC_BIT 0x8000
+#else
+# define MM_ALLOC_BIT 0x80000000
+#endif
+#define MM_IS_ALLOCATED(n) \
+ ((int)((struct mm_allocnode_s*)(n)->preceding) < 0))
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Determine the size of the chunk size/offset type */
+
+#ifdef CONFIG_MM_SMALL
+ typedef uint16_t mmsize_t;
+# define MMSIZE_MAX 0xffff
+#else
+ typedef size_t mmsize_t;
+# define MMSIZE_MAX SIZE_MAX
+#endif
+
+/* This describes an allocated chunk. An allocated chunk is
+ * distinguished from a free chunk by bit 15/31 of the 'preceding' chunk
+ * size. If set, then this is an allocated chunk.
+ */
+
+struct mm_allocnode_s
+{
+ mmsize_t size; /* Size of this chunk */
+ mmsize_t preceding; /* Size of the preceding chunk */
+};
+
+/* What is the size of the allocnode? */
+
+#ifdef CONFIG_MM_SMALL
+# define SIZEOF_MM_ALLOCNODE 4
+#else
+# define SIZEOF_MM_ALLOCNODE 8
+#endif
+
+#define CHECK_ALLOCNODE_SIZE \
+ DEBUGASSERT(sizeof(struct mm_allocnode_s) == SIZEOF_MM_ALLOCNODE)
+
+/* This describes a free chunk */
+
+struct mm_freenode_s
+{
+ mmsize_t size; /* Size of this chunk */
+ mmsize_t preceding; /* Size of the preceding chunk */
+ FAR struct mm_freenode_s *flink; /* Supports a doubly linked list */
+ FAR struct mm_freenode_s *blink;
+};
+
+/* What is the size of the freenode? */
+
+#ifdef CONFIG_MM_SMALL
+# ifdef CONFIG_SMALL_MEMORY
+# define SIZEOF_MM_FREENODE 8
+# else
+# define SIZEOF_MM_FREENODE 12
+# endif
+#else
+# define SIZEOF_MM_FREENODE 16
+#endif
+
+#define CHECK_FREENODE_SIZE \
+ DEBUGASSERT(sizeof(struct mm_freenode_s) == SIZEOF_MM_FREENODE)
+
+/* Normally defined in stdlib.h */
+
+#ifdef MM_TEST
+struct mallinfo
+{
+ int arena; /* This is the total size of memory allocated
+ * for use by malloc in bytes. */
+ int ordblks; /* This is the number of free (not in use) chunks */
+ int mxordblk; /* Size of the largest free (not in use) chunk */
+ int uordblks; /* This is the total size of memory occupied by
+ * chunks handed out by malloc. */
+ int fordblks; /* This is the total size of memory occupied
+ * by free (not in use) chunks.*/
+};
+#endif
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/* This is the size of the heap provided to mm */
+
+extern size_t g_heapsize;
+
+/* This is the first and last nodes of the heap */
+
+extern FAR struct mm_allocnode_s *g_heapstart[CONFIG_MM_REGIONS];
+extern FAR struct mm_allocnode_s *g_heapend[CONFIG_MM_REGIONS];
+
+#if CONFIG_MM_REGIONS > 1
+extern int g_nregions;
+#else
+# define g_nregions 1
+#endif
+
+/* All free nodes are maintained in a doubly linked list. This
+ * array provides some hooks into the list at various points to
+ * speed searches for free nodes.
+ */
+
+extern FAR struct mm_freenode_s g_nodelist[MM_NNODES];
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef MM_TEST
+FAR void *mm_malloc(size_t);
+void mm_free(void*);
+FAR void *mm_realloc(void*, size_t);
+FAR void *mm_memalign(size_t, size_t);
+FAR void *mm_zalloc(size_t);
+FAR void *mm_calloc(size_t, size_t);
+#ifdef CONFIG_CAN_PASS_STRUCTS
+struct mallinfo mallinfo(void);
+#else
+int mallinfo(struct mallinfo *info);
+#endif
+#endif
+
+void mm_shrinkchunk(FAR struct mm_allocnode_s *node, size_t size);
+void mm_addfreechunk(FAR struct mm_freenode_s *node);
+int mm_size2ndx(size_t size);
+void mm_seminitialize(void);
+void mm_takesemaphore(void);
+void mm_givesemaphore(void);
+#ifdef MM_TEST
+int mm_getsemaphore(void);
+#endif
+
+#endif /* __MM_MM_INTERNAL_H */
diff --git a/nuttx/mm/mm_mallinfo.c b/nuttx/mm/mm_mallinfo.c
new file mode 100644
index 000000000..b725535d1
--- /dev/null
+++ b/nuttx/mm/mm_mallinfo.c
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * mm/mm_mallinfo.c
+ *
+ * Copyright (C) 2007, 2009 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 <assert.h>
+
+#include "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mallinfo
+ *
+ * Description:
+ * mallinfo returns a copy of updated current mallinfo.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+struct mallinfo mallinfo(void)
+#else
+int mallinfo(struct mallinfo *info)
+#endif
+{
+ struct mm_allocnode_s *node;
+ size_t mxordblk = 0;
+ int ordblks = 0; /* Number of non-inuse chunks */
+ size_t uordblks = 0; /* Total allocated space */
+ size_t fordblks = 0; /* Total non-inuse space */
+#if CONFIG_MM_REGIONS > 1
+ int region;
+#else
+# define region 0
+#endif
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ static struct mallinfo info;
+#else
+ if (!info)
+ {
+ return ERROR;
+ }
+#endif
+
+ /* Visit each region */
+
+#if CONFIG_MM_REGIONS > 1
+ for (region = 0; region < g_nregions; region++)
+#endif
+ {
+ /* Visit each node in the region */
+
+ for (node = g_heapstart[region];
+ node < g_heapend[region];
+ node = (struct mm_allocnode_s *)((char*)node + node->size))
+ {
+ mvdbg("region=%d node=%p preceding=%p\n", region, node, node->preceding);
+ if (node->preceding & MM_ALLOC_BIT)
+ {
+ uordblks += node->size;
+ }
+ else
+ {
+ ordblks++;
+ fordblks += node->size;
+ if (node->size > mxordblk)
+ {
+ mxordblk = node->size;
+ }
+ }
+ }
+
+ mvdbg("region=%d node=%p g_heapend=%p\n", region, node, g_heapend[region]);
+ DEBUGASSERT(node == g_heapend[region]);
+ uordblks += SIZEOF_MM_ALLOCNODE; /* account for the tail node */
+ }
+#undef region
+
+ DEBUGASSERT(uordblks + fordblks == g_heapsize);
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ info.arena = g_heapsize;
+ info.ordblks = ordblks;
+ info.mxordblk = mxordblk;
+ info.uordblks = uordblks;
+ info.fordblks = fordblks;
+ return info;
+#else
+ info->arena = g_heapsize;
+ info->ordblks = ordblks;
+ info->mxordblk = mxordblk;
+ info->uordblks = uordblks;
+ info->fordblks = fordblks;
+ return OK;
+#endif
+}
diff --git a/nuttx/mm/mm_malloc.c b/nuttx/mm/mm_malloc.c
new file mode 100644
index 000000000..8a21e7324
--- /dev/null
+++ b/nuttx/mm/mm_malloc.c
@@ -0,0 +1,201 @@
+/****************************************************************************
+ * mm/mm_malloc.c
+ *
+ * Copyright (C) 2007, 2009 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
+ ****************************************************************************/
+
+/* Special definitions when we operate in the normal vs. the host-pc test
+ * environement.
+ */
+
+#include <assert.h>
+
+#include "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifndef NULL
+# define NULL ((void*)0)
+#endif
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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.
+ *
+ ****************************************************************************/
+
+FAR void *malloc(size_t size)
+{
+ FAR struct mm_freenode_s *node;
+ void *ret = NULL;
+ int ndx;
+
+ /* Handle bad sizes */
+
+ if (size <= 0)
+ {
+ return NULL;
+ }
+
+ /* Adjust the size to account for (1) the size of the allocated node and
+ * (2) to make sure that it is an even multiple of our granule size.
+ */
+
+ size = MM_ALIGN_UP(size + SIZEOF_MM_ALLOCNODE);
+
+ /* We need to hold the MM semaphore while we muck with the nodelist. */
+
+ mm_takesemaphore();
+
+ /* Get the location in the node list to start the search. Special case
+ * really big allocations
+ */
+
+ if (size >= MM_MAX_CHUNK)
+ {
+ ndx = MM_NNODES-1;
+ }
+ else
+ {
+ /* Convert the request size into a nodelist index */
+
+ ndx = mm_size2ndx(size);
+ }
+
+ /* Search for a large enough chunk in the list of nodes. This list is
+ * ordered by size, but will have occasional zero sized nodes as we visit
+ * other g_nodelist[] entries.
+ */
+
+ for (node = g_nodelist[ndx].flink;
+ node && node->size < size;
+ node = node->flink);
+
+ /* If we found a node with non-zero size, then this is one to use. Since
+ * the list is ordered, we know that is must be best fitting chunk
+ * available.
+ */
+
+ if (node)
+ {
+ FAR struct mm_freenode_s *remainder;
+ FAR struct mm_freenode_s *next;
+ size_t remaining;
+
+ /* Remove the node. There must be a predecessor, but there may not be
+ * a successor node.
+ */
+
+ DEBUGASSERT(node->blink);
+ node->blink->flink = node->flink;
+ if (node->flink)
+ {
+ node->flink->blink = node->blink;
+ }
+
+ /* Check if we have to split the free node into one of the allocated
+ * size and another smaller freenode. In some cases, the remaining
+ * bytes can be smaller (they may be SIZEOF_MM_ALLOCNODE). In that
+ * case, we will just carry the few wasted bytes at the end of the
+ * allocation.
+ */
+
+ remaining = node->size - size;
+ if (remaining >= SIZEOF_MM_FREENODE)
+ {
+ /* Get a pointer to the next node in physical memory */
+
+ next = (FAR struct mm_freenode_s*)(((char*)node) + node->size);
+
+ /* Create the remainder node */
+
+ remainder = (FAR struct mm_freenode_s*)(((char*)node) + size);
+ remainder->size = remaining;
+ remainder->preceding = size;
+
+ /* Adjust the size of the node under consideration */
+
+ node->size = size;
+
+ /* Adjust the 'preceding' size of the (old) next node, preserving
+ * the allocated flag.
+ */
+
+ next->preceding = remaining | (next->preceding & MM_ALLOC_BIT);
+
+ /* Add the remainder back into the nodelist */
+
+ mm_addfreechunk(remainder);
+ }
+
+ /* Handle the case of an exact size match */
+
+ node->preceding |= MM_ALLOC_BIT;
+ ret = (void*)((char*)node + SIZEOF_MM_ALLOCNODE);
+ }
+
+ mm_givesemaphore();
+ mvdbg("Allocated %p, size %d\n", ret, size);
+ return ret;
+}
diff --git a/nuttx/mm/mm_memalign.c b/nuttx/mm/mm_memalign.c
new file mode 100644
index 000000000..87547c96b
--- /dev/null
+++ b/nuttx/mm/mm_memalign.c
@@ -0,0 +1,208 @@
+/****************************************************************************
+ * mm/mm_memalign.c
+ *
+ * Copyright (C) 2007, 2009, 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 <assert.h>
+
+#include "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global 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)
+{
+ FAR struct mm_allocnode_s *node;
+ size_t rawchunk;
+ size_t alignedchunk;
+ size_t mask = (size_t)(alignment - 1);
+ size_t allocsize;
+
+ /* If this requested alignement less than or equal to the natural alignment
+ * of malloc, then just let malloc do the work.
+ */
+
+ if (alignment <= MM_MIN_CHUNK)
+ {
+ return malloc(size);
+ }
+
+ /* Adjust the size to account for (1) the size of the allocated node, (2)
+ * to make sure that it is an even multiple of our granule size, and to
+ * include the alignment amount.
+ *
+ * Notice that we increase the allocation size by twice the requested
+ * alignment. We do this so that there will be at least two valid
+ * alignment points within the allocated memory.
+ *
+ * NOTE: These are sizes given to malloc and not chunk sizes. They do
+ * not include SIZEOF_MM_ALLOCNODE.
+ */
+
+ size = MM_ALIGN_UP(size); /* Make multiples of our granule size */
+ allocsize = size + 2*alignment; /* Add double full alignment size */
+
+ /* Then malloc that size */
+
+ rawchunk = (size_t)malloc(allocsize);
+ if (rawchunk == 0)
+ {
+ return NULL;
+ }
+
+ /* We need to hold the MM semaphore while we muck with the chunks and
+ * nodelist.
+ */
+
+ mm_takesemaphore();
+
+ /* Get the node associated with the allocation and the next node after
+ * the allocation.
+ */
+
+ node = (FAR struct mm_allocnode_s*)(rawchunk - SIZEOF_MM_ALLOCNODE);
+
+ /* Find the aligned subregion */
+
+ alignedchunk = (rawchunk + mask) & ~mask;
+
+ /* Check if there is free space at the beginning of the aligned chunk */
+
+ if (alignedchunk != rawchunk)
+ {
+ FAR struct mm_allocnode_s *newnode;
+ FAR struct mm_allocnode_s *next;
+ size_t precedingsize;
+
+ /* Get the node the next node after the allocation. */
+
+ next = (FAR struct mm_allocnode_s*)((char*)node + node->size);
+
+ /* Make sure that there is space to convert the preceding mm_allocnode_s
+ * into an mm_freenode_s. I think that this should always be true
+ */
+
+ DEBUGASSERT(alignedchunk >= rawchunk + 8);
+
+ newnode = (FAR struct mm_allocnode_s*)(alignedchunk - SIZEOF_MM_ALLOCNODE);
+
+ /* Preceding size is full size of the new 'node,' including
+ * SIZEOF_MM_ALLOCNODE
+ */
+
+ precedingsize = (size_t)newnode - (size_t)node;
+
+ /* If we were unlucky, then the alignedchunk can lie in such a position
+ * that precedingsize < SIZEOF_NODE_FREENODE. We can't let that happen
+ * because we are going to cast 'node' to struct mm_freenode_s below.
+ * This is why we allocated memory large enough to support two
+ * alignment points. In this case, we will simply use the second
+ * alignment point.
+ */
+
+ if (precedingsize < SIZEOF_MM_FREENODE)
+ {
+ alignedchunk += alignment;
+ newnode = (FAR struct mm_allocnode_s*)(alignedchunk - SIZEOF_MM_ALLOCNODE);
+ precedingsize = (size_t)newnode - (size_t)node;
+ }
+
+ /* Set up the size of the new node */
+
+ newnode->size = (size_t)next - (size_t)newnode;
+ newnode->preceding = precedingsize | MM_ALLOC_BIT;
+
+ /* Reduce the size of the original chunk and mark it not allocated, */
+
+ node->size = precedingsize;
+ node->preceding &= ~MM_ALLOC_BIT;
+
+ /* Fix the preceding size of the next node */
+
+ next->preceding = newnode->size | (next->preceding & MM_ALLOC_BIT);
+
+ /* Convert the newnode chunk size back into malloc-compatible size by
+ * subtracting the header size SIZEOF_MM_ALLOCNODE.
+ */
+
+ allocsize = newnode->size - SIZEOF_MM_ALLOCNODE;
+
+ /* Add the original, newly freed node to the free nodelist */
+
+ mm_addfreechunk((FAR struct mm_freenode_s *)node);
+
+ /* Replace the original node with the newlay realloaced,
+ * aligned node
+ */
+
+ node = newnode;
+ }
+
+ /* Check if there is free space at the end of the aligned chunk */
+
+ if (allocsize > size)
+ {
+ /* Shrink the chunk by that much -- remember, mm_shrinkchunk wants
+ * internal chunk sizes that include SIZEOF_MM_ALLOCNODE, and not the
+ * malloc-compatible sizes that we have.
+ */
+
+ mm_shrinkchunk(node, size + SIZEOF_MM_ALLOCNODE);
+ }
+
+ mm_givesemaphore();
+ return (FAR void*)alignedchunk;
+}
diff --git a/nuttx/mm/mm_realloc.c b/nuttx/mm/mm_realloc.c
new file mode 100644
index 000000000..b44938995
--- /dev/null
+++ b/nuttx/mm/mm_realloc.c
@@ -0,0 +1,352 @@
+/****************************************************************************
+ * mm/mm_realloc.c
+ *
+ * Copyright (C) 2007, 2009 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 <string.h>
+#include "mm_environment.h"
+#include <stdio.h>
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global 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.
+ *
+ ****************************************************************************/
+
+FAR void *realloc(FAR void *oldmem, size_t size)
+{
+ FAR struct mm_allocnode_s *oldnode;
+ FAR struct mm_freenode_s *prev;
+ FAR struct mm_freenode_s *next;
+ size_t oldsize;
+ size_t prevsize = 0;
+ size_t nextsize = 0;
+ FAR void *newmem;
+
+ /* If oldmem is NULL, then realloc is equivalent to malloc */
+
+ if (!oldmem)
+ {
+ return malloc(size);
+ }
+
+ /* If size is zero, then realloc is equivalent to free */
+
+ if (size <= 0)
+ {
+ free(oldmem);
+ return NULL;
+ }
+
+ /* Adjust the size to account for (1) the size of the allocated node and
+ * (2) to make sure that it is an even multiple of our granule size.
+ */
+
+ size = MM_ALIGN_UP(size + SIZEOF_MM_ALLOCNODE);
+
+ /* Map the memory chunk into an allocated node structure */
+
+ oldnode = (FAR struct mm_allocnode_s *)((FAR char*)oldmem - SIZEOF_MM_ALLOCNODE);
+
+ /* We need to hold the MM semaphore while we muck with the nodelist. */
+
+ mm_takesemaphore();
+
+ /* Check if this is a request to reduce the size of the allocation. */
+
+ oldsize = oldnode->size;
+ if (size <= oldsize)
+ {
+ /* Handle the special case where we are not going to change the size
+ * of the allocation.
+ */
+
+ if (size < oldsize)
+ {
+ mm_shrinkchunk(oldnode, size);
+ }
+
+ /* Then return the original address */
+
+ mm_givesemaphore();
+ return oldmem;
+ }
+
+ /* This is a request to increase the size of the allocation, Get the
+ * available sizes before and after the oldnode so that we can make the
+ * best decision
+ */
+
+ next = (FAR struct mm_freenode_s *)((FAR char*)oldnode + oldnode->size);
+ if ((next->preceding & MM_ALLOC_BIT) == 0)
+ {
+ nextsize = next->size;
+ }
+
+ prev = (FAR struct mm_freenode_s *)((FAR char*)oldnode - (oldnode->preceding & ~MM_ALLOC_BIT));
+ if ((prev->preceding & MM_ALLOC_BIT) == 0)
+ {
+ prevsize = prev->size;
+ }
+
+ /* Now, check if we can extend the current allocation or not */
+
+ if (nextsize + prevsize + oldsize >= size)
+ {
+ size_t needed = size - oldsize;
+ size_t takeprev = 0;
+ size_t takenext = 0;
+
+ /* Check if we can extend into the previous chunk and if the
+ * previous chunk is smaller than the next chunk.
+ */
+
+ if (prevsize > 0 && (nextsize >= prevsize || nextsize <= 0))
+ {
+ /* Can we get everything we need from the previous chunk? */
+
+ if (needed > prevsize)
+ {
+ /* No, take the whole previous chunk and get the
+ * rest that we need from the next chunk.
+ */
+
+ takeprev = prevsize;
+ takenext = needed - prevsize;
+ }
+ else
+ {
+ /* Yes, take what we need from the previous chunk */
+
+ takeprev = needed;
+ takenext = 0;
+ }
+
+ needed = 0;
+ }
+
+ /* Check if we can extend into the next chunk and if we still need
+ * more memory.
+ */
+
+ if (nextsize > 0 && needed)
+ {
+ /* Can we get everything we need from the next chunk? */
+
+ if (needed > nextsize)
+ {
+ /* No, take the whole next chunk and get the rest that we
+ * need from the previous chunk.
+ */
+
+ takeprev = needed - nextsize;
+ takenext = nextsize;
+ }
+ else
+ {
+ /* Yes, take what we need from the previous chunk */
+
+ takeprev = 0;
+ takenext = needed;
+ }
+ }
+
+ /* Extend into the previous free chunk */
+
+ newmem = oldmem;
+ if (takeprev)
+ {
+ FAR struct mm_allocnode_s *newnode;
+
+ /* Remove the previous node. There must be a predecessor, but
+ * there may not be a successor node.
+ */
+
+ DEBUGASSERT(prev->blink);
+ prev->blink->flink = prev->flink;
+ if (prev->flink)
+ {
+ prev->flink->blink = prev->blink;
+ }
+
+ /* Extend the node into the previous free chunk */
+
+ newnode = (FAR struct mm_allocnode_s *)((FAR char*)oldnode - takeprev);
+
+ /* Did we consume the entire preceding chunk? */
+
+ if (takeprev < prevsize)
+ {
+ /* No.. just take what we need from the previous chunk and put
+ * it back into the free list
+ */
+
+ prev->size -= takeprev;
+ newnode->size = oldsize + takeprev;
+ newnode->preceding = prev->size | MM_ALLOC_BIT;
+ next->preceding = newnode->size | (next->preceding & MM_ALLOC_BIT);
+
+ /* Return the previous free node to the nodelist (with the new size) */
+
+ mm_addfreechunk(prev);
+
+ /* Now we want to return newnode */
+
+ oldnode = newnode;
+ }
+ else
+ {
+ /* Yes.. update its size (newnode->preceding is already set) */
+
+ newnode->size += oldsize;
+ newnode->preceding |= MM_ALLOC_BIT;
+ next->preceding = newnode->size | (next->preceding & MM_ALLOC_BIT);
+ }
+
+ oldnode = newnode;
+ oldsize = newnode->size;
+
+ /* Now we have to move the user contents 'down' in memory. memcpy should
+ * should be save for this.
+ */
+
+ newmem = (FAR void*)((FAR char*)newnode + SIZEOF_MM_ALLOCNODE);
+ memcpy(newmem, oldmem, oldsize - SIZEOF_MM_ALLOCNODE);
+ }
+
+ /* Extend into the next free chunk */
+
+ if (takenext)
+ {
+ FAR struct mm_freenode_s *newnode;
+ FAR struct mm_allocnode_s *andbeyond;
+
+ /* Get the chunk following the next node (which could be the tail
+ * chunk)
+ */
+
+ andbeyond = (FAR struct mm_allocnode_s*)((char*)next + nextsize);
+
+ /* Remove the next node. There must be a predecessor, but there
+ * may not be a successor node.
+ */
+
+ DEBUGASSERT(next->blink);
+ next->blink->flink = next->flink;
+ if (next->flink)
+ {
+ next->flink->blink = next->blink;
+ }
+
+ /* Extend the node into the next chunk */
+
+ oldnode->size = oldsize + takenext;
+ newnode = (FAR struct mm_freenode_s *)((char*)oldnode + oldnode->size);
+
+ /* Did we consume the entire preceding chunk? */
+
+ if (takenext < nextsize)
+ {
+ /* No, take what we need from the next chunk and return it to
+ * the free nodelist.
+ */
+
+ newnode->size = nextsize - takenext;
+ newnode->preceding = oldnode->size;
+ andbeyond->preceding = newnode->size | (andbeyond->preceding & MM_ALLOC_BIT);
+
+ /* Add the new free node to the nodelist (with the new size) */
+
+ mm_addfreechunk(newnode);
+ }
+ else
+ {
+ /* Yes, just update some pointers. */
+
+ andbeyond->preceding = oldnode->size | (andbeyond->preceding & MM_ALLOC_BIT);
+ }
+ }
+
+ mm_givesemaphore();
+ return newmem;
+ }
+
+ /* The current chunk cannot be extended. Just allocate a new chunk and copy */
+
+ else
+ {
+ /* Allocate a new block. On failure, realloc must return NULL but
+ * leave the original memory in place.
+ */
+
+ mm_givesemaphore();
+ newmem = (FAR void*)malloc(size);
+ if (newmem)
+ {
+ memcpy(newmem, oldmem, oldsize);
+ free(oldmem);
+ }
+
+ return newmem;
+ }
+}
diff --git a/nuttx/mm/mm_sem.c b/nuttx/mm/mm_sem.c
new file mode 100644
index 000000000..19fff780b
--- /dev/null
+++ b/nuttx/mm/mm_sem.c
@@ -0,0 +1,247 @@
+/****************************************************************************
+ * mm/mm_sem.c
+ *
+ * Copyright (C) 2007-2009 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 "mm_environment.h"
+
+#include <unistd.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <assert.h>
+
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Define the following to enable semaphore state monitoring */
+//#define MONITOR_MM_SEMAPHORE 1
+
+#ifdef MONITOR_MM_SEMAPHORE
+# ifdef CONFIG_DEBUG
+# include <debug.h>
+# define msemdbg dbg
+# else
+# define msemdbg printf
+# endif
+#else
+# ifdef CONFIG_CPP_HAVE_VARARGS
+# define msemdbg(x...)
+# else
+# define msemdbg (void)
+# endif
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* Mutually exclusive access to this data set is enforced with
+ * the following (un-named) semaphore. */
+
+static sem_t g_mm_semaphore;
+static pid_t g_holder;
+static int g_counts_held;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_seminitialize
+ *
+ * Description:
+ * Initialize the MM mutex
+ *
+ ****************************************************************************/
+
+void mm_seminitialize(void)
+{
+ /* Initialize the MM semaphore to one (to support one-at-a-time access to
+ * private data sets.
+ */
+
+ (void)sem_init(&g_mm_semaphore, 0, 1);
+
+ g_holder = -1;
+ g_counts_held = 0;
+}
+
+/****************************************************************************
+ * Name: mm_trysemaphore
+ *
+ * Description:
+ * Try to take the MM mutex. This is called only from the OS in certain
+ * conditions when it is necessary to have exclusive access to the memory
+ * manager but it is impossible to wait on a semaphore (e.g., the idle
+ * process when it performs its background memory cleanup).
+ *
+ ****************************************************************************/
+
+#ifndef MM_TEST
+int mm_trysemaphore(void)
+{
+ pid_t my_pid = getpid();
+
+ /* Do I already have the semaphore? */
+
+ if (g_holder == my_pid)
+ {
+ /* Yes, just increment the number of references that I have */
+
+ g_counts_held++;
+ return OK;
+ }
+ else
+ {
+ /* Try to take the semaphore (perhaps waiting) */
+
+ if (sem_trywait(&g_mm_semaphore) != 0)
+ {
+ return ERROR;
+ }
+
+ /* We have it. Claim the stak and return */
+
+ g_holder = my_pid;
+ g_counts_held = 1;
+ return OK;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: mm_takesemaphore
+ *
+ * Description:
+ * Take the MM mutex. This is the normal action before all memory
+ * management actions.
+ *
+ ****************************************************************************/
+
+void mm_takesemaphore(void)
+{
+ pid_t my_pid = getpid();
+
+ /* Do I already have the semaphore? */
+
+ if (g_holder == my_pid)
+ {
+ /* Yes, just increment the number of references that I have */
+
+ g_counts_held++;
+ }
+ else
+ {
+ /* Take the semaphore (perhaps waiting) */
+
+ msemdbg("PID=%d taking\n", my_pid);
+ while (sem_wait(&g_mm_semaphore) != 0)
+ {
+ /* The only case that an error should occur here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(mm_errno == EINTR);
+ }
+
+ /* We have it. Claim the stake and return */
+
+ g_holder = my_pid;
+ g_counts_held = 1;
+ }
+
+ msemdbg("Holder=%d count=%d\n", g_holder, g_counts_held);
+}
+
+/****************************************************************************
+ * Name: mm_givesemaphore
+ *
+ * Description:
+ * Release the MM mutex when it is not longer needed.
+ *
+ ****************************************************************************/
+
+void mm_givesemaphore(void)
+{
+#ifdef CONFIG_DEBUG
+ pid_t my_pid = getpid();
+#endif
+
+ /* I better be holding at least one reference to the semaphore */
+
+ DEBUGASSERT(g_holder == my_pid);
+
+ /* Do I hold multiple references to the semphore */
+
+ if (g_counts_held > 1)
+ {
+ /* Yes, just release one count and return */
+
+ g_counts_held--;
+ msemdbg("Holder=%d count=%d\n", g_holder, g_counts_held);
+ }
+ else
+ {
+ /* Nope, this is the last reference I have */
+
+ msemdbg("PID=%d giving\n", my_pid);
+ g_holder = -1;
+ g_counts_held = 0;
+ ASSERT(sem_post(&g_mm_semaphore) == 0);
+ }
+}
+
+/****************************************************************************
+ * Name: mm_getsemaphore
+ *
+ * Description:
+ * Return the current value of the MM semaphore (for test purposes only)
+ *
+ ****************************************************************************/
+
+#ifdef MM_TEST
+int mm_getsemaphore(void)
+{
+ int sval;
+ sem_getvalue(&g_mm_semaphore, &sval);
+ return sval;
+}
+#endif
+
diff --git a/nuttx/mm/mm_shrinkchunk.c b/nuttx/mm/mm_shrinkchunk.c
new file mode 100644
index 000000000..e538e43ed
--- /dev/null
+++ b/nuttx/mm/mm_shrinkchunk.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * mm/mm_shrinkchunk.c
+ *
+ * Copyright (C) 2007, 2009 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_shrinkchunk
+ *
+ * Description:
+ * Reduce the size of the chunk specified by the node structure to the
+ * specified size. this internal logic is used both from memalign to
+ * dispose of any trailing memory in the aligned allocation and also by
+ * realloc when there is a request to reduce the size of an allocation.
+ *
+ * NOTES:
+ * (1) size is the whole chunk size (payload and header)
+ * (2) the caller must hold the MM semaphore.
+ *
+ ****************************************************************************/
+
+void mm_shrinkchunk(FAR struct mm_allocnode_s *node, size_t size)
+{
+ FAR struct mm_freenode_s *next;
+
+ /* Get a reference to the next node */
+
+ next = (FAR struct mm_freenode_s*)((char*)node + node->size);
+
+ /* Check if it is free */
+
+ if ((next->preceding & MM_ALLOC_BIT) == 0)
+ {
+ FAR struct mm_allocnode_s *andbeyond;
+ FAR struct mm_freenode_s *newnode;
+
+ /* Get the chunk next the next node (which could be the tail chunk) */
+
+ andbeyond = (FAR struct mm_allocnode_s*)((char*)next + next->size);
+
+ /* Remove the next node. There must be a predecessor, but there may
+ * not be a successor node.
+ */
+
+ DEBUGASSERT(next->blink);
+ next->blink->flink = next->flink;
+ if (next->flink)
+ {
+ next->flink->blink = next->blink;
+ }
+
+ /* Create a new chunk that will hold both the next chunk and the
+ * tailing memory from the aligned chunk.
+ */
+
+ newnode = (FAR struct mm_freenode_s*)((char*)node + size);
+
+ /* Set up the size of the new node */
+
+ newnode->size = next->size + node->size - size;
+ newnode->preceding = size;
+ node->size = size;
+ andbeyond->preceding = newnode->size | (andbeyond->preceding & MM_ALLOC_BIT);
+
+ /* Add the new node to the freenodelist */
+
+ mm_addfreechunk(newnode);
+ }
+
+ /* The next chunk is allocated. Try to free the end portion at the end
+ * chunk to be shrunk.
+ */
+
+ else if (node->size >= size + SIZEOF_MM_FREENODE)
+ {
+ FAR struct mm_freenode_s *newnode;
+
+ /* Create a new chunk that will hold both the next chunk and the
+ * tailing memory from the aligned chunk.
+ */
+
+ newnode = (FAR struct mm_freenode_s*)((char*)node + size);
+
+ /* Set up the size of the new node */
+
+ newnode->size = node->size - size;
+ newnode->preceding = size;
+ node->size = size;
+ next->preceding = newnode->size | MM_ALLOC_BIT;
+
+ /* Add the new node to the freenodelist */
+
+ mm_addfreechunk(newnode);
+ }
+}
diff --git a/nuttx/mm/mm_size2ndx.c b/nuttx/mm/mm_size2ndx.c
new file mode 100644
index 000000000..b2a0a8e14
--- /dev/null
+++ b/nuttx/mm/mm_size2ndx.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * mm/mm_size2ndx.c
+ *
+ * Copyright (C) 2007, 2009 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mm_size2ndx
+ *
+ * Description:
+ * Convert the size to a nodelist index.
+ *
+ ****************************************************************************/
+
+int mm_size2ndx(size_t size)
+{
+ int ndx = 0;
+
+ if (size >= MM_MAX_CHUNK)
+ {
+ return MM_NNODES-1;
+ }
+
+ size >>= MM_MIN_SHIFT;
+ while (size > 1)
+ {
+ ndx++;
+ size >>= 1;
+ }
+
+ return ndx;
+}
diff --git a/nuttx/mm/mm_test.c b/nuttx/mm/mm_test.c
new file mode 100644
index 000000000..b25a24095
--- /dev/null
+++ b/nuttx/mm/mm_test.c
@@ -0,0 +1,535 @@
+/************************************************************************
+ * mm/mm_test.c
+ *
+ * Copyright (C) 2007, 2009, 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 <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+
+/************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************/
+
+/* Fake NuttX dependencies */
+
+#define FAR
+#define CONFIG_MM_REGIONS 2
+#undef CONFIG_MM_SMALL
+#define CONFIG_CAN_PASS_STRUCTS 1
+#undef CONFIG_SMALL_MEMORY
+
+#include "mm_internal.h"
+
+/* Pre-processor Definitions */
+
+#define TEST_HEAP1_SIZE 0x00080000
+#define TEST_HEAP2_SIZE 0x00080000
+#define NTEST_ALLOCS 32
+
+/* #define STOP_ON_ERRORS do{}while(0) */
+#define STOP_ON_ERRORS exit(1)
+
+/************************************************************************
+ * Private Data
+ ************************************************************************/
+
+/* Test allocations */
+
+static const int alloc_sizes[NTEST_ALLOCS] =
+{
+ 1024, 12, 962, 5692, 10254, 111, 9932, 601,
+ 222, 2746, 3, 124321, 68, 776, 6750, 852,
+ 4732, 28, 901, 480, 5011, 1536, 2011, 81647,
+ 646, 1646, 69179, 194, 2590, 7, 969, 70
+};
+
+static const int realloc_sizes[NTEST_ALLOCS] =
+{
+ 18, 3088, 963, 123, 511, 11666, 3723, 42,
+ 9374, 1990, 1412, 6, 592, 4088, 11, 5040,
+ 8663, 91255, 28, 4346, 9172, 168, 229, 4734,
+ 59139, 221, 7830, 30421, 1666, 4, 812, 416
+};
+
+static const int random1[NTEST_ALLOCS] =
+{
+ 20, 11, 3, 31, 9, 29, 7, 17,
+ 21, 2, 26, 18, 14, 25, 0, 10,
+ 27, 19, 22, 28, 8, 30, 12, 15,
+ 4, 1, 24, 6, 16, 13, 5, 23
+};
+
+static const int random2[NTEST_ALLOCS] =
+{
+ 2, 19, 12, 23, 30, 11, 27, 4,
+ 20, 7, 0, 16, 28, 15, 5, 24,
+ 10, 17, 25, 31, 8, 29, 3, 26,
+ 9, 18, 22, 13, 1, 21, 14, 6
+};
+
+static const int random3[NTEST_ALLOCS] =
+{
+ 8, 17, 3, 18, 26, 23, 30, 11,
+ 12, 22, 4, 20, 25, 10, 27, 1,
+ 29, 14, 19, 21, 0, 31, 7, 24,
+ 9, 15, 2, 28, 16, 6, 13, 5
+};
+
+static const int alignment[NTEST_ALLOCS/2] =
+{
+ 128, 2048, 131072, 8192, 32, 32768, 16384 , 262144,
+ 512, 4096, 65536, 8, 64, 1024, 16, 4
+};
+
+static void *allocs[NTEST_ALLOCS];
+static struct mallinfo alloc_info;
+static unsigned int g_reportedheapsize = 0;
+static unsigned int g_actualheapsize = 0;
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: mm_findinfreelist
+ ************************************************************************/
+
+static int mm_findinfreelist(struct mm_freenode_s *node)
+{
+ struct mm_freenode_s *list;
+
+ for(list = &g_nodelist[0];
+ list;
+ list = list->flink)
+ {
+ if (list == node)
+ {
+ return 1;
+ }
+ }
+
+ return 0;
+}
+
+/************************************************************************
+ * Name: mm_showchunkinfo
+ ************************************************************************/
+
+static void mm_showchunkinfo(void)
+{
+ struct mm_allocnode_s *node;
+#if CONFIG_MM_REGIONS > 1
+ int region;
+#else
+# define region 0
+#endif
+ int found;
+
+ printf(" CHUNK LIST:\n");
+
+ /* Visit each region */
+
+#if CONFIG_MM_REGIONS > 1
+ for (region = 0; region < g_nregions; region++)
+#endif
+ {
+ /* Visit each node in each region */
+
+ for (node = g_heapstart[region];
+ node < g_heapend[region];
+ node = (struct mm_allocnode_s *)((char*)node + node->size))
+ {
+ printf(" %p 0x%08x 0x%08x %s",
+ node, node->size, node->preceding & ~MM_ALLOC_BIT,
+ node->preceding & MM_ALLOC_BIT ? "Allocated" : "Free ");
+ found = mm_findinfreelist((struct mm_freenode_s *)node);
+ if (found && (node->preceding & MM_ALLOC_BIT) != 0)
+ {
+ printf(" Should NOT have been in free list\n");
+ }
+ else if (!found && (node->preceding & MM_ALLOC_BIT) == 0)
+ {
+ printf(" SHOULD have been in free listT\n");
+ }
+ else
+ {
+ printf(" OK\n");
+ }
+ }
+ }
+#undef region
+}
+
+/************************************************************************
+ * Name: mm_showfreelist
+ ************************************************************************/
+
+static void mm_showfreelist(void)
+{
+ struct mm_freenode_s *prev;
+ struct mm_freenode_s *node;
+ int i = 0;
+
+ printf(" FREE NODE LIST:\n");
+ for(prev = NULL, node = &g_nodelist[0];
+ node;
+ prev = node, node = node->flink)
+ {
+ /* Dump "fake" nodes in a different way */
+
+ if (node->size == 0)
+ {
+ printf(" [NODE %2d] %08x %08x %08x\n",
+ i, node->preceding, (int)node->flink, (int)node->blink);
+ i++;
+ }
+ else
+ {
+ printf(" %08x %08x %08x %08x %08x\n",
+ (int)node, node->size, node->preceding, (int)node->flink, (int)node->blink);
+ }
+
+ /* Verify all backward links */
+
+ if (node->blink != prev)
+ {
+ fprintf(stderr, "Backward link is wrong: Is %p, should be %p\n",
+ node->blink, prev);
+ STOP_ON_ERRORS;
+ }
+ }
+}
+
+/************************************************************************
+ * Name: mm_showmallinfo
+ ************************************************************************/
+
+static void mm_showmallinfo(void)
+{
+ int sval;
+
+ mm_showchunkinfo();
+ mm_showfreelist();
+ alloc_info = mallinfo();
+ printf(" mallinfo:\n");
+ printf(" Total space allocated from system = %ld\n",
+ alloc_info.arena);
+ printf(" Number of non-inuse chunks = %ld\n",
+ alloc_info.ordblks);
+ printf(" Largest non-inuse chunk = %ld\n",
+ alloc_info.mxordblk);
+ printf(" Total allocated space = %ld\n",
+ alloc_info.uordblks);
+ printf(" Total non-inuse space = %ld\n",
+ alloc_info.fordblks);
+
+ sval = mm_getsemaphore();
+ if (sval != 1)
+ {
+ fprintf(stderr, "After mallinfo, semaphore count=%d, should be 1\n", sval);
+ STOP_ON_ERRORS;
+ }
+
+ if (!g_reportedheapsize)
+ {
+ g_reportedheapsize = alloc_info.uordblks + alloc_info.fordblks;
+ if (g_reportedheapsize > g_actualheapsize + 16*CONFIG_MM_REGIONS ||
+ g_reportedheapsize < g_actualheapsize -16*CONFIG_MM_REGIONS)
+ {
+ fprintf(stderr, "Total memory %d not close to uordlbks=%d + fordblks=%d = %d\n",
+ g_actualheapsize, alloc_info.uordblks, alloc_info.fordblks, g_reportedheapsize);
+ STOP_ON_ERRORS;
+ }
+ }
+ else if (alloc_info.uordblks + alloc_info.fordblks != g_reportedheapsize)
+ {
+ fprintf(stderr, "Total memory %d != uordlbks=%d + fordblks=%d\n",
+ g_reportedheapsize, alloc_info.uordblks, alloc_info.fordblks);
+ STOP_ON_ERRORS;
+ }
+}
+
+/************************************************************************
+ * Name: do_mallocs
+ ************************************************************************/
+
+static void do_mallocs(void **mem, const int *size, const int *rand,
+ int n)
+{
+ int sval;
+ int i;
+ int j;
+
+ for (i = 0; i < n; i++)
+ {
+ j = rand[i];
+ if (!mem[j])
+ {
+ printf("(%d)Allocating %d bytes\n", i, size[j]);
+ mem[j] = mm_malloc(size[j]);
+ printf("(%d)Memory allocated at %p\n", i, mem[j]);
+ if (mem[j] == NULL)
+ {
+ int allocsize = MM_ALIGN_UP(size[j] + SIZEOF_MM_ALLOCNODE);
+ fprintf(stderr, "(%d)malloc failed for allocsize=%d\n", i, allocsize);
+ if (allocsize > alloc_info.mxordblk)
+ {
+ fprintf(stderr, " Normal, largest free block is only %ld\n", alloc_info.mxordblk);
+ }
+ else
+ {
+ fprintf(stderr, " ERROR largest free block is %ld\n", alloc_info.mxordblk);
+ exit(1);
+ }
+ }
+ else
+ {
+ memset(mem[j], 0xAA, size[j]);
+ }
+
+ sval = mm_getsemaphore();
+ if (sval != 1)
+ {
+ fprintf(stderr, " After malloc semaphore count=%d, should be 1\n", sval);
+ STOP_ON_ERRORS;
+ }
+
+ mm_showmallinfo();
+ }
+ }
+}
+
+/************************************************************************
+ * Name: do_reallocs
+ ************************************************************************/
+
+static void do_reallocs(void **mem, const int *oldsize,
+ const int *newsize, const int *rand, int n)
+{
+ int sval;
+ int i;
+ int j;
+
+ for (i = 0; i < n; i++)
+ {
+ j = rand[i];
+ printf("(%d)Re-allocating at %p from %d to %d bytes\n",
+ i, mem[j], oldsize[j], newsize[j]);
+ mem[j] = mm_realloc(mem[j], newsize[j]);
+ printf("(%d)Memory re-allocated at %p\n", i, mem[j]);
+ if (mem[j] == NULL)
+ {
+ int allocsize = MM_ALIGN_UP(newsize[j] + SIZEOF_MM_ALLOCNODE);
+ fprintf(stderr, "(%d)realloc failed for allocsize=%d\n", i, allocsize);
+ if (allocsize > alloc_info.mxordblk)
+ {
+ fprintf(stderr, " Normal, largest free block is only %ld\n", alloc_info.mxordblk);
+ }
+ else
+ {
+ fprintf(stderr, " ERROR largest free block is %ld\n", alloc_info.mxordblk);
+ exit(1);
+ }
+ }
+ else
+ {
+ memset(mem[j], 0x55, newsize[j]);
+ }
+
+ sval = mm_getsemaphore();
+ if (sval != 1)
+ {
+ fprintf(stderr, " After realloc semaphore count=%d, should be 1\n", sval);
+ STOP_ON_ERRORS;
+ }
+
+ mm_showmallinfo();
+ }
+}
+
+/************************************************************************
+ * Name: do_memaligns
+ ************************************************************************/
+
+static void do_memaligns(void **mem, const int *size, const int *align,
+ const int *rand, int n)
+{
+ int sval;
+ int i;
+ int j;
+
+ for (i = 0; i < n; i++)
+ {
+ j = rand[i];
+ printf("(%d)Allocating %d bytes aligned to 0x%08x\n",
+ i, size[j], align[i]);
+ mem[j] = mm_memalign(align[i], size[j]);
+ printf("(%d)Memory allocated at %p\n", i, mem[j]);
+ if (mem[j] == NULL)
+ {
+ int allocsize = MM_ALIGN_UP(size[j] + SIZEOF_MM_ALLOCNODE) + 2*align[i];
+ fprintf(stderr, "(%d)memalign failed for allocsize=%d\n", i, allocsize);
+ if (allocsize > alloc_info.mxordblk)
+ {
+ fprintf(stderr, " Normal, largest free block is only %ld\n", alloc_info.mxordblk);
+ }
+ else
+ {
+ fprintf(stderr, " ERROR largest free block is %ld\n", alloc_info.mxordblk);
+ exit(1);
+ }
+ }
+ else
+ {
+ memset(mem[j], 0x33, size[j]);
+ }
+
+ sval = mm_getsemaphore();
+ if (sval != 1)
+ {
+ fprintf(stderr, " After memalign semaphore count=%d, should be 1\n", sval);
+ STOP_ON_ERRORS;
+ }
+
+ mm_showmallinfo();
+ }
+}
+
+/************************************************************************
+ * Name: do_frees
+ ************************************************************************/
+
+static void do_frees(void **mem, const int *size, const int *rand, int n)
+{
+ int sval;
+ int i;
+ int j;
+
+ for (i = 0; i < n; i++)
+ {
+ j = rand[i];
+ printf("(%d)Releasing memory at %p (size=%d bytes)\n",
+ i, mem[j], size[j]);
+ mm_free(mem[j]);
+ mem[j] = NULL;
+
+ sval = mm_getsemaphore();
+ if (sval != 1)
+ {
+ fprintf(stderr, " After free semaphore count=%d, should be 1\n", sval);
+ STOP_ON_ERRORS;
+ }
+
+ mm_showmallinfo();
+ }
+}
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: main
+ ************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ void *heap1_base;
+ void *heap2_base;
+ int i, j;
+
+ /* Allocate a heap */
+
+ printf("Allocating test heap #1 of %ldKb\n", TEST_HEAP1_SIZE/1024);
+ heap1_base = malloc(TEST_HEAP1_SIZE);
+ printf("Allocated heap1_base=%p\n", heap1_base);
+ if (heap1_base == 0)
+ {
+ fprintf(stderr, "Failed to allocate test heap #1\n");
+ exit(1);
+ }
+
+ printf("Allocating test heap #2 of %ldKb\n", TEST_HEAP2_SIZE/1024);
+ heap2_base = malloc(TEST_HEAP2_SIZE);
+ printf("Allocated heap2_base=%p\n", heap2_base);
+ if (heap2_base == 0)
+ {
+ fprintf(stderr, "Failed to allocate test heap #2\n");
+ exit(1);
+ }
+
+ /* Initialize the memory manager */
+
+ mm_initialize(heap1_base, TEST_HEAP1_SIZE);
+ g_actualheapsize = TEST_HEAP1_SIZE;
+ mm_showmallinfo();
+
+ mm_addregion(heap2_base, TEST_HEAP2_SIZE);
+ g_reportedheapsize = 0;
+ g_actualheapsize += TEST_HEAP2_SIZE;
+ mm_showmallinfo();
+
+ /* Allocate some memory */
+
+ do_mallocs(allocs, alloc_sizes, random1, NTEST_ALLOCS);
+
+ /* Re-allocate the memory */
+
+ do_reallocs(allocs, alloc_sizes, realloc_sizes, random2, NTEST_ALLOCS);
+
+ /* Release the memory */
+
+ do_frees(allocs, realloc_sizes, random3, NTEST_ALLOCS);
+
+ /* Allocate aligned memory */
+
+ do_memaligns(allocs, alloc_sizes, alignment, random2, NTEST_ALLOCS/2);
+ do_memaligns(allocs, alloc_sizes, alignment, &random2[NTEST_ALLOCS/2], NTEST_ALLOCS/2);
+
+ /* Release aligned memory */
+
+ do_frees(allocs, alloc_sizes, random1, NTEST_ALLOCS);
+
+ /* Clean up and exit */
+
+ free(heap1_base);
+ free(heap2_base);
+
+ printf("TEST COMPLETE\n");
+ return 0;
+}
diff --git a/nuttx/mm/mm_zalloc.c b/nuttx/mm/mm_zalloc.c
new file mode 100644
index 000000000..075777d0c
--- /dev/null
+++ b/nuttx/mm/mm_zalloc.c
@@ -0,0 +1,68 @@
+/****************************************************************************
+ * mm/mm_zalloc.c
+ *
+ * Copyright (C) 2007, 2009 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 "mm_environment.h"
+#include "mm_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: zalloc
+ *
+ * Description:
+ * zalloc calls malloc, then zeroes out the allocated chunk.
+ *
+ ****************************************************************************/
+
+FAR void *zalloc(size_t size)
+{
+ FAR void *alloc = malloc(size);
+ if (alloc)
+ {
+ memset(alloc, 0, size);
+ }
+
+ return alloc;
+}