summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog6
-rw-r--r--nuttx/include/nuttx/kmalloc.h5
-rw-r--r--nuttx/include/nuttx/mm.h239
-rw-r--r--nuttx/include/stdlib.h63
-rw-r--r--nuttx/mm/Kconfig21
-rw-r--r--nuttx/mm/Makefile.test67
-rw-r--r--nuttx/mm/mm_addfreechunk.c5
-rw-r--r--nuttx/mm/mm_calloc.c35
-rw-r--r--nuttx/mm/mm_environment.h139
-rw-r--r--nuttx/mm/mm_free.c16
-rw-r--r--nuttx/mm/mm_initialize.c9
-rw-r--r--nuttx/mm/mm_internal.h277
-rw-r--r--nuttx/mm/mm_mallinfo.c19
-rw-r--r--nuttx/mm/mm_malloc.c17
-rw-r--r--nuttx/mm/mm_memalign.c19
-rw-r--r--nuttx/mm/mm_realloc.c19
-rw-r--r--nuttx/mm/mm_sem.c25
-rw-r--r--nuttx/mm/mm_shrinkchunk.c7
-rw-r--r--nuttx/mm/mm_size2ndx.c5
-rw-r--r--nuttx/mm/mm_test.c536
-rw-r--r--nuttx/mm/mm_zalloc.c35
21 files changed, 431 insertions, 1133 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 62d0fe287..2bc475683 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4272,7 +4272,7 @@
was closed by the remote peer). That excludes the listen socket which
was never connected. This does introduce a new problem, however. If
the socket was not closed, but lost the connection through an abnormal
- event, then poll/select will hang. That needs to be revisited.\
+ event, then poll/select will hang. That needs to be revisited.
(2013-03-07)
* fs/fs_selected.c: Was not checking if the timeout parameter was NULL
but would, instead, setup a bogus timeout based on whatever it found at
@@ -4284,4 +4284,6 @@
* mm/: Move all memory manager globals into a structure. A reference
to this structure is now passed internally between mm APIs. This
change will (eventually) support multiple heaps and heap allocators.
-
+ (2013-03-07).
+ * mm/ and include/nuttx/mm.h: Implement support for multiple heaps.
+ (2013-03-07).
diff --git a/nuttx/include/nuttx/kmalloc.h b/nuttx/include/nuttx/kmalloc.h
index d6a1bd0b4..6bf04ac0b 100644
--- a/nuttx/include/nuttx/kmalloc.h
+++ b/nuttx/include/nuttx/kmalloc.h
@@ -77,9 +77,6 @@ extern "C"
#ifndef CONFIG_NUTTX_KERNEL
-struct mm_heap_s;
-extern struct mm_heap_s g_mmheap;
-
# define kmm_initialize(h,s) mm_initialize(h,s)
# define kmm_addregion(h,s) mm_addregion(h,s)
# define kmm_trysemaphore() mm_trysemaphore(&g_mmheap)
@@ -94,7 +91,7 @@ extern struct mm_heap_s g_mmheap;
void kmm_initialize(FAR void *heap_start, size_t heap_size);
void kmm_addregion(FAR void *heapstart, size_t heapsize);
-int kmm_trysemaphore(void);
+int kmm_trysemaphore(void);
void kmm_givesemaphore(void);
FAR void *kmalloc(size_t);
diff --git a/nuttx/include/nuttx/mm.h b/nuttx/include/nuttx/mm.h
index feb45a931..1345bbd13 100644
--- a/nuttx/include/nuttx/mm.h
+++ b/nuttx/include/nuttx/mm.h
@@ -41,25 +41,178 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
+#include <semaphore.h>
/****************************************************************************
* 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.
+ */
-/****************************************************************************
- * Global Data
- ****************************************************************************/
+#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 (or 15)
+ * 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))
/****************************************************************************
- * Global Function Prototypes
+ * Public Types
****************************************************************************/
+/* Determines 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)
+
+/* This describes one heap (possibly with multiple regions) */
+
+struct mm_heap_s
+{
+ /* Mutually exclusive access to this data set is enforced with
+ * the following un-named semaphore.
+ */
+
+ sem_t mm_semaphore;
+ pid_t mm_holder;
+ int mm_counts_held;
+
+ /* This is the size of the heap provided to mm */
+
+ size_t mm_heapsize;
+
+ /* This is the first and last nodes of the heap */
+
+ FAR struct mm_allocnode_s *mm_heapstart[CONFIG_MM_REGIONS];
+ FAR struct mm_allocnode_s *mm_heapend[CONFIG_MM_REGIONS];
+
+#if CONFIG_MM_REGIONS > 1
+ int mm_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.
+ */
+
+ struct mm_freenode_s mm_nodelist[MM_NNODES];
+};
+
/****************************************************************************
- * Global Function Prototypes
+ * Public Data
****************************************************************************/
-#ifdef __cplusplus
+#undef EXTERN
+#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
@@ -67,6 +220,17 @@ extern "C"
#define EXTERN extern
#endif
+#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
+/* This is the user heap */
+
+EXTERN struct mm_heap_s g_mmheap;
+
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
/* Functions contained in mm_initialize.c ***********************************/
void mm_initialize(FAR void *heap_start, size_t heap_size);
@@ -74,10 +238,69 @@ void mm_addregion(FAR void *heapstart, size_t heapsize);
/* Functions contained in mm_sem.c ******************************************/
-struct mm_heap_s;
-int mm_trysemaphore(FAR struct mm_heap_s *heap);
+void mm_seminitialize(FAR struct mm_heap_s *heap);
+void mm_takesemaphore(FAR struct mm_heap_s *heap);
+int mm_trysemaphore(FAR struct mm_heap_s *heap);
void mm_givesemaphore(FAR struct mm_heap_s *heap);
+/* Functions contained in mm_malloc.c ***************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_malloc(FAR struct mm_heap_s *heap, size_t size);
+#endif
+
+/* Functions contained in mm_free.c *****************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+void mm_free(FAR struct mm_heap_s *heap, FAR void *mem);
+#endif
+
+/* Functions contained in mm_realloc.c **************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem,
+ size_t size);
+#endif
+
+/* Functions contained in mm_calloc.c ***************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_calloc(FAR struct mm_heap_s *heap, size_t n, size_t elem_size);
+#endif
+
+/* Functions contained in mm_zalloc.c ***************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_zalloc(FAR struct mm_heap_s *heap, size_t size);
+#endif
+
+/* Functions contained in mm_memalign.c *************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
+ size_t size);
+#endif
+
+/* Functions contained in mm_mallinfo.c *************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+int mm_mallinfo(FAR struct mm_heap_s *heap, FAR struct mallinfo *info);
+#endif
+
+/* Functions contained in mm_shrinkchunk.c **********************************/
+
+void mm_shrinkchunk(FAR struct mm_heap_s *heap,
+ FAR struct mm_allocnode_s *node, size_t size);
+
+/* Functions contained in mm_addfreechunk.c *********************************/
+
+void mm_addfreechunk(FAR struct mm_heap_s *heap,
+ FAR struct mm_freenode_s *node);
+
+/* Functions contained in mm_size2ndx.c.c ***********************************/
+
+int mm_size2ndx(size_t size);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/stdlib.h b/nuttx/include/stdlib.h
index 27696e0fa..ad4344ade 100644
--- a/nuttx/include/stdlib.h
+++ b/nuttx/include/stdlib.h
@@ -107,47 +107,48 @@ struct mallinfo
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
/* Random number generation */
-EXTERN void srand(unsigned int seed);
-EXTERN int rand(void);
+void srand(unsigned int seed);
+int rand(void);
/* Environment variable support */
#ifndef CONFIG_DISABLE_ENIVRON
-EXTERN FAR char **get_environ_ptr( void );
-EXTERN FAR char *getenv(FAR const char *name);
-EXTERN int putenv(FAR const char *string);
-EXTERN int clearenv(void);
-EXTERN int setenv(const char *name, const char *value, int overwrite);
-EXTERN int unsetenv(const char *name);
+FAR char **get_environ_ptr( void );
+FAR char *getenv(FAR const char *name);
+int putenv(FAR const char *string);
+int clearenv(void);
+int setenv(const char *name, const char *value, int overwrite);
+int unsetenv(const char *name);
#endif
/* Process exit functions */
-EXTERN void exit(int status) noreturn_function;
-EXTERN void abort(void) noreturn_function;
+void exit(int status) noreturn_function;
+void abort(void) noreturn_function;
#ifdef CONFIG_SCHED_ATEXIT
-EXTERN int atexit(CODE void (*func)(void));
+int atexit(CODE void (*func)(void));
#endif
#ifdef CONFIG_SCHED_ONEXIT
-EXTERN int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg);
+int on_exit(CODE void (*func)(int, FAR void *), FAR void *arg);
#endif
/* String to binary conversions */
-EXTERN long strtol(const char *, char **, int);
-EXTERN unsigned long strtoul(const char *, char **, int);
+long strtol(const char *, char **, int);
+unsigned long strtoul(const char *, char **, int);
#ifdef CONFIG_HAVE_LONG_LONG
-EXTERN long long strtoll(const char *, char **, int);
-EXTERN unsigned long long strtoull(const char *, char **, int);
+long long strtoll(const char *, char **, int);
+unsigned long long strtoull(const char *, char **, int);
#endif
-EXTERN double_t strtod(const char *, char **);
+double_t strtod(const char *, char **);
#define atoi(nptr) strtol((nptr), NULL, 10)
#define atol(nptr) strtol((nptr), NULL, 10)
@@ -158,30 +159,30 @@ EXTERN double_t strtod(const char *, char **);
/* Memory Management */
-EXTERN FAR void *malloc(size_t);
-EXTERN void free(FAR void*);
-EXTERN FAR void *realloc(FAR void*, size_t);
-EXTERN FAR void *memalign(size_t, size_t);
-EXTERN FAR void *zalloc(size_t);
-EXTERN FAR void *calloc(size_t, size_t);
+FAR void *malloc(size_t);
+void free(FAR void*);
+FAR void *realloc(FAR void*, size_t);
+FAR void *memalign(size_t, size_t);
+FAR void *zalloc(size_t);
+FAR void *calloc(size_t, size_t);
/* Misc */
-EXTERN int abs(int j);
-EXTERN long int labs(long int j);
+int abs(int j);
+long int labs(long int j);
#ifdef CONFIG_HAVE_LONG_LONG
-EXTERN long long int llabs(long long int j);
+long long int llabs(long long int j);
#endif
/* Sorting */
-EXTERN void qsort(void *base, size_t nmemb, size_t size,
- int(*compar)(const void *, const void *));
+void qsort(void *base, size_t nmemb, size_t size,
+ int(*compar)(const void *, const void *));
#ifdef CONFIG_CAN_PASS_STRUCTS
-EXTERN struct mallinfo mallinfo(void);
+struct mallinfo mallinfo(void);
#else
-EXTERN int mallinfo(struct mallinfo *info);
+int mallinfo(struct mallinfo *info);
#endif
#undef EXTERN
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index 5da12b65e..911ae5545 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -3,6 +3,18 @@
# see misc/tools/kconfig-language.txt.
#
+config MM_MULTIHEAP
+ bool "Build support for multiple heaps"
+ default n
+ ---help---
+ Build interfaces to support multiple heaps. This should not be
+ confused with memory regions. One heap may be composed of multiple,
+ non-contiguous memory regions. The fact that the heap is composed
+ of such multiple regions is invisible to the end-user (other than
+ the heap comes pre-fragemented). Multiple heaps, on the other hand,
+ supports a separate set of allocators that operate on a separate set
+ of memory regions.
+
config MM_SMALL
bool "Small memory model"
default n
@@ -16,6 +28,8 @@ config MM_SMALL
CONFIG_MM_SMALL can be defined so that those MCUs will also benefit
from the smaller, 16-bit-based allocation overhead.
+ NOTE: If MM_MULTIHEAP is selected, then this applies to all heaps.
+
config MM_REGIONS
int "Number of memory regions"
default 1
@@ -25,18 +39,21 @@ config MM_REGIONS
that the memory manager must handle and enables the API
mm_addregion(start, end);
+ NOTE: If MM_MULTIHEAP is selected, then this maximum number of regions
+ applies to all heaps.
+
config ARCH_HAVE_HEAP2
bool
config HEAP2_BASE
- hex "Start address of second heap region"
+ hex "Start address of second user 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"
+ int "Size of the second user heap region"
default 0
depends on ARCH_HAVE_HEAP2
---help---
diff --git a/nuttx/mm/Makefile.test b/nuttx/mm/Makefile.test
deleted file mode 100644
index 8a9e0d886..000000000
--- a/nuttx/mm/Makefile.test
+++ /dev/null
@@ -1,67 +0,0 @@
-############################################################################
-# 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.
-#
-############################################################################
-
--include $(TOPDIR)/Make.defs
-
-SRCS = mm_test.c mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c
-SRCS += mm_shrinkchunk.c mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c
-SRCS += 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)
- rm -f *.o1
diff --git a/nuttx/mm/mm_addfreechunk.c b/nuttx/mm/mm_addfreechunk.c
index 61c11baaf..7931c59bb 100644
--- a/nuttx/mm/mm_addfreechunk.c
+++ b/nuttx/mm/mm_addfreechunk.c
@@ -37,8 +37,9 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/mm/mm_calloc.c b/nuttx/mm/mm_calloc.c
index 576081a16..0a433947d 100644
--- a/nuttx/mm/mm_calloc.c
+++ b/nuttx/mm/mm_calloc.c
@@ -37,8 +37,11 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -49,6 +52,28 @@
****************************************************************************/
/****************************************************************************
+ * Name: mm_calloc
+ *
+ * Descripton:
+ * calloc calculates the size of the allocation and calls zalloc
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_calloc(FAR struct mm_heap_s *heap, size_t n, size_t elem_size)
+{
+ FAR void *ret = NULL;
+
+ if (n > 0 && elem_size > 0)
+ {
+ ret = mm_zalloc(heap, n * elem_size);
+ }
+
+ return ret;
+}
+#endif
+
+/****************************************************************************
* Name: calloc
*
* Descripton:
@@ -56,8 +81,12 @@
*
****************************************************************************/
+#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
FAR void *calloc(size_t n, size_t elem_size)
{
+#ifdef CONFIG_MM_MULTIHEAP
+ return mm_calloc(&g_mmheap, n, elem_size);
+#else
FAR void *ret = NULL;
if (n > 0 && elem_size > 0)
@@ -66,4 +95,6 @@ FAR void *calloc(size_t n, size_t elem_size)
}
return ret;
+#endif
}
+#endif
diff --git a/nuttx/mm/mm_environment.h b/nuttx/mm/mm_environment.h
deleted file mode 100644
index 0f9967bcb..000000000
--- a/nuttx/mm/mm_environment.h
+++ /dev/null
@@ -1,139 +0,0 @@
-/****************************************************************************
- * 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 configuration 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 <semaphore.h>
-# include <errno.h>
-# include <assert.h>
-# include <nuttx/mm.h>
-# include <debug.h>
-#else
-# include <sys/types.h>
-
-# include <stdio.h>
-# include <string.h>
-# include <semaphore.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 */
-
-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)
-
-/* Misc. NuttX-isms */
-
-#define OK 0
-
-/* 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
index 7f7d92b16..220b9bca0 100644
--- a/nuttx/mm/mm_free.c
+++ b/nuttx/mm/mm_free.c
@@ -37,10 +37,13 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
+#include <stdlib.h>
#include <assert.h>
+#include <debug.h>
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -51,7 +54,7 @@
****************************************************************************/
/****************************************************************************
- * Name: _mm_free
+ * Name: mm_free
*
* Description:
* Returns a chunk of memory to the list of free nodes, merging with
@@ -59,7 +62,10 @@
*
****************************************************************************/
-static inline void _mm_free(FAR struct mm_heap_s *heap, FAR void *mem)
+#ifndef CONFIG_MM_MULTIHEAP
+static inline
+#endif
+void mm_free(FAR struct mm_heap_s *heap, FAR void *mem)
{
FAR struct mm_freenode_s *node;
FAR struct mm_freenode_s *prev;
@@ -164,6 +170,6 @@ static inline void _mm_free(FAR struct mm_heap_s *heap, FAR void *mem)
#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
void free(FAR void *mem)
{
- _mm_free(&g_mmheap, mem);
+ mm_free(&g_mmheap, mem);
}
#endif
diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c
index d536774ee..37df3ab5f 100644
--- a/nuttx/mm/mm_initialize.c
+++ b/nuttx/mm/mm_initialize.c
@@ -37,8 +37,13 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/mm/mm_internal.h b/nuttx/mm/mm_internal.h
deleted file mode 100644
index 9f1616978..000000000
--- a/nuttx/mm/mm_internal.h
+++ /dev/null
@@ -1,277 +0,0 @@
-/****************************************************************************
- * mm/mm_internal.h
- *
- * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#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
- ****************************************************************************/
-
-/* Determines 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)
-
-/* This describes one heap (possibly with multiple regions) */
-
-struct mm_heap_s
-{
- /* Mutually exclusive access to this data set is enforced with
- * the following un-named semaphore.
- */
-
- sem_t mm_semaphore;
- pid_t mm_holder;
- int mm_counts_held;
-
- /* This is the size of the heap provided to mm */
-
- size_t mm_heapsize;
-
- /* This is the first and last nodes of the heap */
-
- FAR struct mm_allocnode_s *mm_heapstart[CONFIG_MM_REGIONS];
- FAR struct mm_allocnode_s *mm_heapend[CONFIG_MM_REGIONS];
-
-#if CONFIG_MM_REGIONS > 1
- int mm_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.
- */
-
- struct mm_freenode_s mm_nodelist[MM_NNODES];
-};
-
-/* 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
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C"
-{
-#else
-#define EXTERN extern
-#endif
-
-#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
-/* This is the user heap */
-
-EXTERN struct mm_heap_s g_mmheap;
-
-#endif
-
-/****************************************************************************
- * 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_heap_s *heap,
- FAR struct mm_allocnode_s *node, size_t size);
-void mm_addfreechunk(FAR struct mm_heap_s *heap,
- FAR struct mm_freenode_s *node);
-int mm_size2ndx(size_t size);
-void mm_seminitialize(FAR struct mm_heap_s *heap);
-void mm_takesemaphore(FAR struct mm_heap_s *heap);
-void mm_givesemaphore(FAR struct mm_heap_s *heap);
-#ifdef MM_TEST
-int mm_getsemaphore(FAR struct mm_heap_s *heap);
-#endif
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __MM_MM_INTERNAL_H */
diff --git a/nuttx/mm/mm_mallinfo.c b/nuttx/mm/mm_mallinfo.c
index 37432a157..578eadd27 100644
--- a/nuttx/mm/mm_mallinfo.c
+++ b/nuttx/mm/mm_mallinfo.c
@@ -37,10 +37,13 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
+#include <stdlib.h>
#include <assert.h>
+#include <debug.h>
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -55,15 +58,17 @@
****************************************************************************/
/****************************************************************************
- * Name: _mm_mallinfo
+ * Name: mm_mallinfo
*
* Description:
* mallinfo returns a copy of updated current heap information.
*
****************************************************************************/
-static inline int _mm_mallinfo(FAR struct mm_heap_s *heap,
- FAR struct mallinfo *info)
+#ifndef CONFIG_MM_MULTIHEAP
+static inline
+#endif
+int mm_mallinfo(FAR struct mm_heap_s *heap, FAR struct mallinfo *info)
{
struct mm_allocnode_s *node;
size_t mxordblk = 0;
@@ -148,7 +153,7 @@ struct mallinfo mallinfo(void)
{
struct mallinfo info;
- _mm_mallinfo(&g_mmheap, &info);
+ mm_mallinfo(&g_mmheap, &info);
return info;
}
@@ -156,7 +161,7 @@ struct mallinfo mallinfo(void)
int mallinfo(struct mallinfo *info)
{
- return _mm_mallinfo(&g_mmheap, info);
+ return mm_mallinfo(&g_mmheap, info);
}
#endif
diff --git a/nuttx/mm/mm_malloc.c b/nuttx/mm/mm_malloc.c
index 331f8eefd..aa7683454 100644
--- a/nuttx/mm/mm_malloc.c
+++ b/nuttx/mm/mm_malloc.c
@@ -37,14 +37,12 @@
* Included Files
****************************************************************************/
-/* Special definitions when we operate in the normal vs. the host-pc test
- * environement.
- */
+#include <nuttx/config.h>
+#include <stdlib.h>
#include <assert.h>
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -71,7 +69,7 @@
****************************************************************************/
/****************************************************************************
- * Name: _mm_malloc
+ * Name: mm_malloc
*
* Description:
* Find the smallest chunk that satisfies the request. Take the memory from
@@ -81,7 +79,10 @@
*
****************************************************************************/
-static inline FAR void *_mm_malloc(FAR struct mm_heap_s *heap, size_t size)
+#ifndef CONFIG_MM_MULTIHEAP
+static inline
+#endif
+FAR void *mm_malloc(FAR struct mm_heap_s *heap, size_t size)
{
FAR struct mm_freenode_s *node;
void *ret = NULL;
@@ -229,7 +230,7 @@ static inline FAR void *_mm_malloc(FAR struct mm_heap_s *heap, size_t size)
#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
FAR void *malloc(size_t size)
{
- return _mm_malloc(&g_mmheap, size);
+ return mm_malloc(&g_mmheap, size);
}
#endif
diff --git a/nuttx/mm/mm_memalign.c b/nuttx/mm/mm_memalign.c
index d06964534..aa23cc9d6 100644
--- a/nuttx/mm/mm_memalign.c
+++ b/nuttx/mm/mm_memalign.c
@@ -37,10 +37,12 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
+#include <stdlib.h>
#include <assert.h>
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -51,7 +53,7 @@
****************************************************************************/
/****************************************************************************
- * Name: _mm_memalign
+ * Name: mm_memalign
*
* Description:
* memalign requests more than enough space from malloc, finds a region
@@ -63,8 +65,11 @@
*
****************************************************************************/
-static inline FAR void *_mm_memalign(FAR struct mm_heap_s *heap,
- size_t alignment, size_t size)
+#ifndef CONFIG_MM_MULTIHEAP
+static inline
+#endif
+FAR void *mm_memalign(FAR struct mm_heap_s *heap, size_t alignment,
+ size_t size)
{
FAR struct mm_allocnode_s *node;
size_t rawchunk;
@@ -213,7 +218,7 @@ static inline FAR void *_mm_memalign(FAR struct mm_heap_s *heap,
****************************************************************************/
/****************************************************************************
- * Name: _mm_memalign
+ * Name: memalign
*
* Description:
* memalign requests more than enough space from malloc, finds a region
@@ -229,7 +234,7 @@ static inline FAR void *_mm_memalign(FAR struct mm_heap_s *heap,
FAR void *memalign(size_t alignment, size_t size)
{
- return _mm_memalign(&g_mmheap, alignment, size);
+ return mm_memalign(&g_mmheap, alignment, size);
}
#endif
diff --git a/nuttx/mm/mm_realloc.c b/nuttx/mm/mm_realloc.c
index 5364a97a8..4b5a479b4 100644
--- a/nuttx/mm/mm_realloc.c
+++ b/nuttx/mm/mm_realloc.c
@@ -37,10 +37,14 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
+#include <stdlib.h>
#include <string.h>
-#include "mm_environment.h"
#include <stdio.h>
-#include "mm_internal.h"
+#include <assert.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -51,7 +55,7 @@
****************************************************************************/
/****************************************************************************
- * Name: _mm_realloc
+ * Name: mm_realloc
*
* Description:
* If the reallocation is for less space, then:
@@ -73,8 +77,11 @@
*
****************************************************************************/
-static inline FAR void *_mm_realloc(FAR struct mm_heap_s *heap,
- FAR void *oldmem, size_t size)
+#ifndef CONFIG_MM_MULTIHEAP
+static inline
+#endif
+FAR void *mm_realloc(FAR struct mm_heap_s *heap, FAR void *oldmem,
+ size_t size)
{
FAR struct mm_allocnode_s *oldnode;
FAR struct mm_freenode_s *prev;
@@ -383,7 +390,7 @@ static inline FAR void *_mm_realloc(FAR struct mm_heap_s *heap,
FAR void *realloc(FAR void *oldmem, size_t size)
{
- return _mm_realloc(&g_mmheap, oldmem, size);
+ return mm_realloc(&g_mmheap, oldmem, size);
}
#endif
diff --git a/nuttx/mm/mm_sem.c b/nuttx/mm/mm_sem.c
index 61e4fc2f0..f986e9923 100644
--- a/nuttx/mm/mm_sem.c
+++ b/nuttx/mm/mm_sem.c
@@ -37,13 +37,13 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
+#include <nuttx/config.h>
#include <unistd.h>
#include <errno.h>
#include <assert.h>
-#include "mm_internal.h"
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -106,7 +106,6 @@ void mm_seminitialize(FAR struct mm_heap_s *heap)
*
****************************************************************************/
-#ifndef MM_TEST
int mm_trysemaphore(FAR struct mm_heap_s *heap)
{
pid_t my_pid = getpid();
@@ -136,7 +135,6 @@ int mm_trysemaphore(FAR struct mm_heap_s *heap)
return OK;
}
}
-#endif
/****************************************************************************
* Name: mm_takesemaphore
@@ -170,7 +168,7 @@ void mm_takesemaphore(FAR struct mm_heap_s *heap)
* the wait was awakened by a signal.
*/
- ASSERT(mm_errno == EINTR);
+ ASSERT(errno == EINTR);
}
/* We have it. Claim the stake and return */
@@ -220,20 +218,3 @@ void mm_givesemaphore(FAR struct mm_heap_s *heap)
}
}
-/****************************************************************************
- * Name: mm_getsemaphore
- *
- * Description:
- * Return the current value of the MM semaphore (for test purposes only)
- *
- ****************************************************************************/
-
-#ifdef MM_TEST
-int mm_getsemaphore(FAR struct mm_heap_s *heap)
-{
- int sval;
- sem_getvalue(&heap->mm_semaphore, &sval);
- return sval;
-}
-#endif
-
diff --git a/nuttx/mm/mm_shrinkchunk.c b/nuttx/mm/mm_shrinkchunk.c
index c20aaf0fb..b88baa6d4 100644
--- a/nuttx/mm/mm_shrinkchunk.c
+++ b/nuttx/mm/mm_shrinkchunk.c
@@ -37,8 +37,11 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <assert.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/mm/mm_size2ndx.c b/nuttx/mm/mm_size2ndx.c
index b2a0a8e14..038b92142 100644
--- a/nuttx/mm/mm_size2ndx.c
+++ b/nuttx/mm/mm_size2ndx.c
@@ -37,8 +37,9 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/mm/mm_test.c b/nuttx/mm/mm_test.c
deleted file mode 100644
index 483fd165c..000000000
--- a/nuttx/mm/mm_test.c
+++ /dev/null
@@ -1,536 +0,0 @@
-/************************************************************************
- * mm/mm_test.c
- *
- * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <semaphore.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_mmheap.mm_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_mmheap.mm_nregions; region++)
-#endif
- {
- /* Visit each node in each region */
-
- for (node = g_mmheap.mm_heapstart[region];
- node < g_mmheap.mm_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_mmheap.mm_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(&g_mmheap);
- 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(&g_mmheap);
- 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(&g_mmheap);
- 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(&g_mmheap);
- 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(&g_mmheap);
- 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
index 075777d0c..bf25aed84 100644
--- a/nuttx/mm/mm_zalloc.c
+++ b/nuttx/mm/mm_zalloc.c
@@ -37,8 +37,12 @@
* Included Files
****************************************************************************/
-#include "mm_environment.h"
-#include "mm_internal.h"
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+#include <string.h>
+
+#include <nuttx/mm.h>
/****************************************************************************
* Pre-processor Definitions
@@ -49,6 +53,27 @@
****************************************************************************/
/****************************************************************************
+ * Name: mm_zalloc
+ *
+ * Description:
+ * mm_zalloc calls mm_malloc, then zeroes out the allocated chunk.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MM_MULTIHEAP
+FAR void *mm_zalloc(FAR struct mm_heap_s *heap, size_t size)
+{
+ FAR void *alloc = mm_malloc(heap, size);
+ if (alloc)
+ {
+ memset(alloc, 0, size);
+ }
+
+ return alloc;
+}
+#endif
+
+/****************************************************************************
* Name: zalloc
*
* Description:
@@ -56,8 +81,12 @@
*
****************************************************************************/
+#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
FAR void *zalloc(size_t size)
{
+#ifdef CONFIG_MM_MULTIHEAP
+ return mm_zalloc(&g_mmheap, size);
+#else
FAR void *alloc = malloc(size);
if (alloc)
{
@@ -65,4 +94,6 @@ FAR void *zalloc(size_t size)
}
return alloc;
+#endif
}
+#endif