summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-08 22:01:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-08 22:01:50 +0000
commitf2c129b281fc8fa30eccb9b34df534f954ee3c47 (patch)
treea5ff5a1a0415f7fabf66180ccb432243740f4d74 /nuttx/sched
parent5e160bcf59441ce40088ca089cbeb4461a0b0d6a (diff)
downloadpx4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.tar.gz
px4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.tar.bz2
px4-nuttx-f2c129b281fc8fa30eccb9b34df534f954ee3c47.zip
up_addregion should use kmm_addregion; move garbage kmm*.c file to mm/. for now
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5721 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile7
-rw-r--r--nuttx/sched/kmm_addregion.c113
-rw-r--r--nuttx/sched/kmm_initialize.c113
-rw-r--r--nuttx/sched/kmm_kfree.c110
-rw-r--r--nuttx/sched/kmm_kmalloc.c110
-rw-r--r--nuttx/sched/kmm_krealloc.c111
-rw-r--r--nuttx/sched/kmm_kzalloc.c110
-rw-r--r--nuttx/sched/kmm_semaphore.c140
-rw-r--r--nuttx/sched/os_bringup.c6
9 files changed, 6 insertions, 814 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 1292eb449..0ee88bf8e 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -181,9 +181,6 @@ endif
IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
-KMM_SRCS = kmm_initialize.c kmm_addregion.c kmm_semaphore.c
-KMM_SRCS = kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
-
CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(GRP_SRCS) $(SCHED_SRCS) $(WDOG_SRCS)
CSRCS += $(TIME_SRCS) $(SEM_SRCS) $(TIMER_SRCS) $(PGFILL_SRCS)
CSRCS += $(IRQ_SRCS)
@@ -208,10 +205,6 @@ ifneq ($(CONFIG_DISABLE_ENVIRON),y)
CSRCS += $(ENV_SRCS)
endif
-ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CSRCS += $(KMM_SRCS)
-endif
-
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/sched/kmm_addregion.c b/nuttx/sched/kmm_addregion.c
deleted file mode 100644
index 652367f5a..000000000
--- a/nuttx/sched/kmm_addregion.c
+++ /dev/null
@@ -1,113 +0,0 @@
-/************************************************************************
- * sched/kmm_addregion.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KADDREGION(h,s) ((kmaddregion_t)CONFIG_USER_MMADDREGION)(h,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kmaddregion_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_addregion
- *
- * Description:
- * This is a simple redirection to the user-space mm_addregion()
- * function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the memory region
- * heap_size - The size (in bytes) if the memory region.
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. mm_addregion() resides in user-space
- * 2. The address of the user space mm_addregion() is provided in
- * user_map.h
- * 3. The user-space mm_addregion() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_addregion(FAR void *heap_start, size_t heap_size)
-{
- return KADDREGION(heap_start, heap_size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_initialize.c b/nuttx/sched/kmm_initialize.c
deleted file mode 100644
index 6dd08951b..000000000
--- a/nuttx/sched/kmm_initialize.c
+++ /dev/null
@@ -1,113 +0,0 @@
-/************************************************************************
- * sched/kmm_initialize.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KINITIALIZE(h,s) ((kminitialize_t)CONFIG_USER_MMINIT)(h,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kminitialize_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_initialize
- *
- * Description:
- * This is a simple redirection to the user-space mm_initialize()
- * function.
- *
- * Parameters:
- * heap_start - Address of the beginning of the (initial) memory region
- * heap_size - The size (in bytes) if the (initial) memory region.
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. mm_initialize() resides in user-space
- * 2. The address of the user space mm_initialize() is provided in
- * user_map.h
- * 3. The user-space mm_initialize() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_initialize(FAR void *heap_start, size_t heap_size)
-{
- return KINITIALIZE(heap_start, heap_size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_kfree.c b/nuttx/sched/kmm_kfree.c
deleted file mode 100644
index 0f0eaa6c2..000000000
--- a/nuttx/sched/kmm_kfree.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * sched/kmm_kfree.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KFREE(p) ((kfree_t)CONFIG_USER_FREE)(p)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef void (*kfree_t)(FAR void *);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kfree
- *
- * Description:
- * This is a simple redirection to the user-space free() function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * None
- *
- * Assumptions:
- * 1. free() resides in user-space
- * 2. The address of the user space free() is provided in user_map.h
- * 3. The user-space free() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kfree(FAR void *mem)
-{
- return KFREE(mem);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_kmalloc.c b/nuttx/sched/kmm_kmalloc.c
deleted file mode 100644
index 5e34c157f..000000000
--- a/nuttx/sched/kmm_kmalloc.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * sched/kmm_kmalloc.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KMALLOC(s) ((kmalloc_t)CONFIG_USER_MALLOC)(s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*kmalloc_t)(size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmalloc
- *
- * Description:
- * This is a simple redirection to the user-space malloc() function.
- *
- * Parameters:
- * size - Size (in bytes) of the memory region to be allocated.
- *
- * Return Value:
- * The address of the allocated memory (NULL on failure to allocate)
- *
- * Assumptions:
- * 1. malloc() resides in user-space
- * 2. The address of the user space malloc() is provided in user_map.h
- * 3. The user-space malloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *kmalloc(size_t size)
-{
- return KMALLOC(size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_krealloc.c b/nuttx/sched/kmm_krealloc.c
deleted file mode 100644
index 3d3726566..000000000
--- a/nuttx/sched/kmm_krealloc.c
+++ /dev/null
@@ -1,111 +0,0 @@
-/************************************************************************
- * sched/kmm_krealloc.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KREALLOC(p,s) ((krealloc_t)CONFIG_USER_REALLOC)(p,s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*krealloc_t)(FAR void*, size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: krealloc
- *
- * Description:
- * This is a simple redirection to the user-space realloc() function.
- *
- * Parameters:
- * oldmem - The old memory allocated
- * size - Size (in bytes) of the new memory region to be re-allocated.
- *
- * Return Value:
- * The address of the re-allocated memory (NULL on failure to re-allocate)
- *
- * Assumptions:
- * 1. realloc() resides in user-space
- * 2. The address of the user space realloc() is provided in user_map.h
- * 3. The user-space realloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *krealloc(FAR void *oldmem, size_t size)
-{
- return KREALLOC(oldmem, size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_kzalloc.c b/nuttx/sched/kmm_kzalloc.c
deleted file mode 100644
index 42bcfcc0f..000000000
--- a/nuttx/sched/kmm_kzalloc.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/************************************************************************
- * sched/kmm_kzalloc.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* This value is obtained from user_map.h */
-
-#define KZALLOC(s) ((kzalloc_t)CONFIG_USER_ZALLOC)(s)
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef FAR void *(*kzalloc_t)(size_t);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kzalloc
- *
- * Description:
- * This is a simple redirection to the user-space zalloc() function.
- *
- * Parameters:
- * size - Size (in bytes) of the memory region to be allocated.
- *
- * Return Value:
- * The address of the allocated memory (NULL on failure to allocate)
- *
- * Assumptions:
- * 1. zalloc() resides in user-space
- * 2. The address of the user space zalloc() is provided in user_map.h
- * 3. The user-space zalloc() is callable from kernel-space.
- *
- ************************************************************************/
-
-FAR void *kzalloc(size_t size)
-{
- return KZALLOC(size);
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/kmm_semaphore.c b/nuttx/sched/kmm_semaphore.c
deleted file mode 100644
index 7fce747b6..000000000
--- a/nuttx/sched/kmm_semaphore.c
+++ /dev/null
@@ -1,140 +0,0 @@
-/************************************************************************
- * sched/kmm_semaphore.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************/
-
-/************************************************************************
- * Included Files
- ************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/kmalloc.h>
-
-#ifdef CONFIG_NUTTX_KERNEL
-
-/* This logic is all tentatively and, hopefully, will grow in usability.
- * For now, the kernel-mode build uses the memory manager that is
- * provided in the user-space build. That is awkward but reasonable for
- * the current level of support: At present, only memory protection is
- * provided. Kernel-mode code may call into user-mode code, but not
- * vice-versa. So hosting the memory manager in user-space allows the
- * memory manager to be shared in both kernel- and user-mode spaces.
- *
- * In the longer run, if an MMU is support that can provide virtualized
- * memory, then some SLAB memory manager will be required in kernel-space
- * with some kind of brk() system call to obtain mapped heap space.
- *
- * In the current build model, the user-space module is built first. The
- * file user_map.h is generated in the first pass and contains the
- * addresses of the memory manager needed in this file:
- */
-
-#include <arch/board/user_map.h>
-
-/************************************************************************
- * Pre-processor definition
- ************************************************************************/
-
-/* These values are obtained from user_map.h */
-
-#define KTRYSEMAPHORE() ((kmtrysemaphore_t) CONFIG_USER_MMTRYSEM )()
-#define KGIVESEMAPHORE() ((kmgivesemaphore_t)CONFIG_USER_MMGIVESEM)()
-
-/************************************************************************
- * Private Types
- ************************************************************************/
-
-typedef int (*kmtrysemaphore_t)(void);
-typedef void (*kmgivesemaphore_t)(void);
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: kmm_trysemaphore
- *
- * Description:
- * This is a simple redirection to the user-space mm_trysemaphore()
- * function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * OK on success; a negated errno on failure
- *
- * Assumptions:
- * 1. mm_trysemaphore() resides in user-space
- * 2. The address of the user space mm_trysemaphore() is provided in
- * user_map.h
- * 3. The user-space mm_semaphore() is callable from kernel-space.
- *
- ************************************************************************/
-
-int kmm_trysemaphore(void)
-{
- return KTRYSEMAPHORE();
-}
-
-/************************************************************************
- * Name: kmm_givesemaphore
- *
- * Description:
- * This is a simple redirection to the user-space mm_givesemaphore()
- * function.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * OK on success; a negated errno on failure
- *
- * Assumptions:
- * 1. mm_givesemaphore() resides in user-space
- * 2. The address of the user space mm_givesemaphore() is provided in
- * user_map.h
- * 3. The user-space mm_semaphore() is callable from kernel-space.
- *
- ************************************************************************/
-
-void kmm_givesemaphore(void)
-{
- KGIVESEMAPHORE();
-}
-
-#endif /* CONFIG_NUTTX_KERNEL */
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index 2fcb9ff7b..fbaad1a7a 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -195,6 +195,12 @@ int os_bringup(void)
/* Once the operating system has been initialized, the system must be
* started by spawning the user init thread of execution. This is the
* first user-mode thead.
+ *
+ * In a kernel build (CONFIG_NUTTX_KERNEL), it is expected that this user
+ * initialization function will:
+ *
+ * - Call mm_initialized() to initialize the user memmory manager, and
+ * - Is so configured, call work_usrstart() to start the user work thread.
*/
svdbg("Starting init thread\n");