From c2e0b7742ea0d530ed9cf9628f88994063c8d5c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 9 Mar 2013 01:27:42 +0000 Subject: With these fixes, the kernel build is basically functional (but there is more to be done) git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5722 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 7 ++- nuttx/Makefile.unix | 4 +- nuttx/Makefile.win | 4 +- nuttx/configs/sam3u-ek/kernel/Makefile | 8 +-- nuttx/configs/sam3u-ek/kernel/kernel.ld | 8 +-- nuttx/include/nuttx/kmalloc.h | 14 ++--- nuttx/include/nuttx/mm.h | 19 +++++++ nuttx/libc/Makefile | 9 +-- nuttx/mm/Kconfig | 24 +++++++- nuttx/mm/Makefile | 11 ++-- nuttx/mm/kmm_addregion.c | 2 +- nuttx/mm/umm_addregion.c | 81 +++++++++++++++++++++++++++ nuttx/mm/umm_initialize.c | 81 +++++++++++++++++++++++++++ nuttx/mm/umm_semaphore.c | 99 +++++++++++++++++++++++++++++++++ 14 files changed, 336 insertions(+), 35 deletions(-) create mode 100644 nuttx/mm/umm_addregion.c create mode 100644 nuttx/mm/umm_initialize.c create mode 100644 nuttx/mm/umm_semaphore.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f0720f02f..830203fbe 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4287,7 +4287,12 @@ (2013-03-08). * mm/ and include/nuttx/mm.h: Implement support for multiple heaps. (2013-03-08). - * arch/*/src: xyz_addregion() needs to call kmm_addregion, not mm_addretion. + * arch/*/src: xyz_addregion() needs to call kmm_addregion, not mm_addregion. (2013-03-08). * sched/kmm*.c: Move this garbage kmm*.c file to mm/. until I decide what to do with them (which is probably to just delete them). (2013-03-08). + * mm/mm_test.c and Makefile.test: Deleted the memory test. This was + a good test and helped me a lot when I wrote the memory manager, but + now it is in the way and paralyzing other efforts. So the memory unit + test was deleted. (2013-03-08) + diff --git a/nuttx/Makefile.unix b/nuttx/Makefile.unix index 21d3537bd..38cfc2222 100644 --- a/nuttx/Makefile.unix +++ b/nuttx/Makefile.unix @@ -520,7 +520,7 @@ lib/libuc$(LIBEXT): libc/libuc$(LIBEXT) $(Q) install libc/libuc$(LIBEXT) lib/libuc$(LIBEXT) mm/libumm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libumm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libumm$(LIBEXT) lib/libumm$(LIBEXT): mm/libumm$(LIBEXT) $(Q) install mm/libumm$(LIBEXT) lib/libumm$(LIBEXT) @@ -552,7 +552,7 @@ lib/libc$(LIBEXT): libc/libc$(LIBEXT) $(Q) install libc/libc$(LIBEXT) lib/libc$(LIBEXT) mm/libmm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) lib/libmm$(LIBEXT): mm/libmm$(LIBEXT) $(Q) install mm/libmm$(LIBEXT) lib/libmm$(LIBEXT) diff --git a/nuttx/Makefile.win b/nuttx/Makefile.win index 275b6b698..b8f371d8b 100644 --- a/nuttx/Makefile.win +++ b/nuttx/Makefile.win @@ -536,7 +536,7 @@ lib\libuc$(LIBEXT): libc\libuc$(LIBEXT) $(Q) install libc\libuc$(LIBEXT) lib\libuc$(LIBEXT) mm\libumm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libumm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libumm$(LIBEXT) lib\libumm$(LIBEXT): mm\libumm$(LIBEXT) $(Q) install mm\libumm$(LIBEXT) lib\libumm$(LIBEXT) @@ -568,7 +568,7 @@ lib\libc$(LIBEXT): libc\libc$(LIBEXT) $(Q) install libc\libc$(LIBEXT) lib\libc$(LIBEXT) mm\libmm$(LIBEXT): context - $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) EXTRADEFINES=$(KDEFINE) + $(Q) $(MAKE) -C mm TOPDIR="$(TOPDIR)" libmm$(LIBEXT) lib\libmm$(LIBEXT): mm\libmm$(LIBEXT) $(Q) install mm\libmm$(LIBEXT) lib\libmm$(LIBEXT) diff --git a/nuttx/configs/sam3u-ek/kernel/Makefile b/nuttx/configs/sam3u-ek/kernel/Makefile index 8a2646094..6d99c1753 100644 --- a/nuttx/configs/sam3u-ek/kernel/Makefile +++ b/nuttx/configs/sam3u-ek/kernel/Makefile @@ -116,10 +116,10 @@ $(BOARD_INCLUDE)$(DELIM)user_map.h: $(TOPDIR)$(DELIM)User.map $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h $(Q) echo "/* Memory manager entry points */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h - $(Q) echo "#define CONFIG_USER_MMINIT 0x`grep \" mm_initialize$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h - $(Q) echo "#define CONFIG_USER_MMADDREGION 0x`grep \" mm_addregion$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h - $(Q) echo "#define CONFIG_USER_MMTRYSEM 0x`grep \" mm_trysemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h - $(Q) echo "#define CONFIG_USER_MMGIVESEM 0x`grep \" mm_givesemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + $(Q) echo "#define CONFIG_USER_MMINIT 0x`grep \" umm_initialize$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + $(Q) echo "#define CONFIG_USER_MMADDREGION 0x`grep \" umm_addregion$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + $(Q) echo "#define CONFIG_USER_MMTRYSEM 0x`grep \" umm_trysemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h + $(Q) echo "#define CONFIG_USER_MMGIVESEM 0x`grep \" umm_givesemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h $(Q) echo "#define CONFIG_USER_MALLOC 0x`grep \" malloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h $(Q) echo "#define CONFIG_USER_REALLOC 0x`grep \" realloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h diff --git a/nuttx/configs/sam3u-ek/kernel/kernel.ld b/nuttx/configs/sam3u-ek/kernel/kernel.ld index c288ab047..e0f2169be 100644 --- a/nuttx/configs/sam3u-ek/kernel/kernel.ld +++ b/nuttx/configs/sam3u-ek/kernel/kernel.ld @@ -67,10 +67,10 @@ MEMORY * but be usable both by kernel- and user-space code */ -EXTERN(mm_initialize) -EXTERN(mm_addregion) -EXTERN(mm_trysemaphore) -EXTERN(mm_givesemaphore) +EXTERN(umm_initialize) +EXTERN(umm_addregion) +EXTERN(umm_trysemaphore) +EXTERN(umm_givesemaphore) EXTERN(malloc) EXTERN(realloc) diff --git a/nuttx/include/nuttx/kmalloc.h b/nuttx/include/nuttx/kmalloc.h index 26d7768b3..95ae33e32 100644 --- a/nuttx/include/nuttx/kmalloc.h +++ b/nuttx/include/nuttx/kmalloc.h @@ -43,11 +43,9 @@ #include #include +#include -#ifndef CONFIG_NUTTX_KERNEL -# include -# include -#endif +#include /**************************************************************************** * Public Types @@ -77,10 +75,10 @@ extern "C" #ifndef CONFIG_NUTTX_KERNEL -# define kmm_initialize(h,s) mm_initialize(&g_mmheap,h,s) -# define kmm_addregion(h,s) mm_addregion(&g_mmheap,h,s) -# define kmm_trysemaphore() mm_trysemaphore(&g_mmheap) -# define kmm_givesemaphore() mm_givesemaphore(&g_mmheap) +# define kmm_initialize(h,s) umm_initialize(h,s) +# define kmm_addregion(h,s) umm_addregion(h,s) +# define kmm_trysemaphore() umm_trysemaphore() +# define kmm_givesemaphore() umm_givesemaphore() # define kmalloc(s) malloc(s) # define kzalloc(s) zalloc(s) diff --git a/nuttx/include/nuttx/mm.h b/nuttx/include/nuttx/mm.h index 825ef0313..ac831e2ce 100644 --- a/nuttx/include/nuttx/mm.h +++ b/nuttx/include/nuttx/mm.h @@ -238,6 +238,18 @@ void mm_initialize(FAR struct mm_heap_s *heap, FAR void *heap_start, void mm_addregion(FAR struct mm_heap_s *heap, FAR void *heapstart, size_t heapsize); +/* Functions contained in umm_initialize.c **********************************/ + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) +void umm_initialize(FAR void *heap_start, size_t heap_size); +#endif + +/* Functions contained in umm_addregion.c ***********************************/ + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) +void umm_addregion(FAR void *heapstart, size_t heapsize); +#endif + /* Functions contained in mm_sem.c ******************************************/ void mm_seminitialize(FAR struct mm_heap_s *heap); @@ -245,6 +257,13 @@ 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 umm_semaphore.c ***********************************/ + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) +int umm_trysemaphore(void); +void umm_givesemaphore(void); +#endif + /* Functions contained in mm_malloc.c ***************************************/ #ifdef CONFIG_MM_MULTIHEAP diff --git a/nuttx/libc/Makefile b/nuttx/libc/Makefile index ee015c38a..f565abb9b 100644 --- a/nuttx/libc/Makefile +++ b/nuttx/libc/Makefile @@ -73,6 +73,7 @@ KBIN = libkc$(LIBEXT) BIN = libc$(LIBEXT) all: $(BIN) +.PHONY: kclean uclean clean distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -84,19 +85,15 @@ $(BIN): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) ifneq ($(BIN),$(UBIN)) -.userlib: +$(UBIN): kclean $(Q) $(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) touch .userlib - -$(UBIN): kclean .userlib endif ifneq ($(BIN),$(KBIN)) -.kernlib: +$(KBIN): uclean $(Q) $(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) touch .kernlib - -$(KBIN): uclean .kernlib endif .depend: Makefile $(SRCS) diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig index 9724eb407..991972f32 100644 --- a/nuttx/mm/Kconfig +++ b/nuttx/mm/Kconfig @@ -11,10 +11,32 @@ config MM_MULTIHEAP 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, + the heap comes pre-fragmented). Multiple heaps, on the other hand, supports a separate set of allocators that operate on a separate set of memory regions. +config MM_KERNEL_HEAP + bool "Support a protected, kernel heap" + default y + depends on NUTTX_KERNEL && MM_MULTIHEAP + ---help--- + Partition heap memory into two parts: (1) a protected, kernel-mode + heap accessible only by the NuttX kernel, and (2) an unprotected + user-mode heap for use by applications. If you are only interested + in protected the kernel from read access, then this option is not + necessary. If you wish to secure the kernel data as well, then + this option should be selected. + +config MM_KERNEL_HEAPSIZE + int "Kernal heap size" + default 8192 + depends on MM_KERNEL_HEAP + ---help--- + This is the size of the a protected, kernel-mode heap (in bytes). + The remaining of available memory is given to the unprotected + user-mode heap. This value may need to be aligned to units of the + size of the smallest memory protection region. + config MM_SMALL bool "Small memory model" default n diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile index 4b7412b43..12a237bb7 100644 --- a/nuttx/mm/Makefile +++ b/nuttx/mm/Makefile @@ -40,6 +40,8 @@ CSRCS = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c CSRCS += mm_shrinkchunk.c mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c CSRCS += mm_memalign.c mm_free.c mm_mallinfo.c +CSRCS += umm_initialize.c umm_addregion.c umm_semaphore.c + ifeq ($(CONFIG_NUTTX_KERNEL),y) CSRCS += kmm_initialize.c kmm_addregion.c kmm_semaphore.c CSRCS += kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c @@ -60,6 +62,7 @@ KBIN = libkmm$(LIBEXT) BIN = libmm$(LIBEXT) all: $(BIN) +.PHONY: kclean uclean clean distclean $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -71,19 +74,15 @@ $(BIN): $(OBJS) $(call ARCHIVE, $@, $(OBJS)) ifneq ($(BIN),$(UBIN)) -.userlib: +$(UBIN): kclean $(Q) $(MAKE) $(UBIN) BIN=$(UBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) touch .userlib - -$(UBIN): kclean .userlib endif ifneq ($(BIN),$(KBIN)) -.kernlib: +$(KBIN): uclean $(Q) $(MAKE) $(KBIN) BIN=$(KBIN) TOPDIR=$(TOPDIR) EXTRADEFINES=$(EXTRADEFINES) $(Q) touch .kernlib - -$(KBIN): uclean .kernlib endif .depend: Makefile $(SRCS) diff --git a/nuttx/mm/kmm_addregion.c b/nuttx/mm/kmm_addregion.c index c53fe9cfe..979b285ed 100644 --- a/nuttx/mm/kmm_addregion.c +++ b/nuttx/mm/kmm_addregion.c @@ -107,7 +107,7 @@ typedef void (*kmaddregion_t)(FAR void*, size_t); void kmm_addregion(FAR void *heap_start, size_t heap_size) { - return KADDREGION(&g_kmmheap, heap_start, heap_size); + return KADDREGION(heap_start, heap_size); } #endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */ diff --git a/nuttx/mm/umm_addregion.c b/nuttx/mm/umm_addregion.c new file mode 100644 index 000000000..181723155 --- /dev/null +++ b/nuttx/mm/umm_addregion.c @@ -0,0 +1,81 @@ +/************************************************************************ + * mm/umm_addregion.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) + +/************************************************************************ + * Pre-processor definition + ************************************************************************/ + +/************************************************************************ + * Private Types + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: umm_addregion + * + * Description: + * This is a simple wrapper for the 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 + * + ************************************************************************/ + +void umm_addregion(FAR void *heap_start, size_t heap_size) +{ + mm_addregion(&g_mmheap, heap_start, heap_size); +} + +#endif /* !CONFIG_NUTTX_KERNEL || !__KERNEL__ */ diff --git a/nuttx/mm/umm_initialize.c b/nuttx/mm/umm_initialize.c new file mode 100644 index 000000000..13a1fe015 --- /dev/null +++ b/nuttx/mm/umm_initialize.c @@ -0,0 +1,81 @@ +/************************************************************************ + * mm/umm_initialize.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) + +/************************************************************************ + * Pre-processor definition + ************************************************************************/ + +/************************************************************************ + * Private Types + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: umm_initialize + * + * Description: + * This is a simple wrapper for the 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 + * + ************************************************************************/ + +void umm_initialize(FAR void *heap_start, size_t heap_size) +{ + mm_initialize(&g_mmheap, heap_start, heap_size); +} + +#endif /* !CONFIG_NUTTX_KERNEL || !__KERNEL__ */ diff --git a/nuttx/mm/umm_semaphore.c b/nuttx/mm/umm_semaphore.c new file mode 100644 index 000000000..d554268ab --- /dev/null +++ b/nuttx/mm/umm_semaphore.c @@ -0,0 +1,99 @@ +/************************************************************************ + * mm/umm_semaphore.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include + +#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__) + +/************************************************************************ + * Pre-processor definition + ************************************************************************/ + +/************************************************************************ + * Private Types + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: umm_trysemaphore + * + * Description: + * This is a simple wrapper for the mm_trysemaphore() function. + * + * Parameters: + * None + * + * Return Value: + * OK on success; a negated errno on failure + * + ************************************************************************/ + +int umm_trysemaphore(void) +{ + return mm_trysemaphore(&g_mmheap); +} + +/************************************************************************ + * Name: umm_givesemaphore + * + * Description: + * This is a simple wrapper for the mm_givesemaphore() function. + * + * Parameters: + * None + * + * Return Value: + * OK on success; a negated errno on failure + * + ************************************************************************/ + +void umm_givesemaphore(void) +{ + mm_givesemaphore(&g_mmheap); +} + +#endif /* !CONFIG_NUTTX_KERNEL || __KERNEL__ */ -- cgit v1.2.3