summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/8051/src/up_allocateheap.c6
-rw-r--r--nuttx/arch/arm/src/common/up_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_allocateheap.c17
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_framebuffer.c21
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_usbdev.c11
-rw-r--r--nuttx/arch/arm/src/imx/imx_allocateheap.c11
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c11
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c11
-rw-r--r--nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c9
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c9
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c9
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbdev.c5
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_usbdev.c11
-rw-r--r--nuttx/arch/avr/src/common/up_allocateheap.c13
-rw-r--r--nuttx/arch/hc/src/common/up_allocateheap.c14
-rw-r--r--nuttx/arch/mips/src/common/up_allocateheap.c14
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c7
-rw-r--r--nuttx/arch/rgmp/src/nuttx.c2
-rw-r--r--nuttx/arch/sh/src/common/up_allocateheap.c14
-rw-r--r--nuttx/arch/sim/src/up_allocateheap.c14
-rw-r--r--nuttx/arch/sim/src/up_deviceimage.c21
-rw-r--r--nuttx/arch/x86/src/common/up_allocateheap.c13
-rw-r--r--nuttx/arch/z16/src/common/up_allocateheap.c11
-rw-r--r--nuttx/arch/z80/src/common/up_allocateheap.c11
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_i2c.c13
-rw-r--r--nuttx/arch/z80/src/z8/z8_i2c.c6
31 files changed, 223 insertions, 133 deletions
diff --git a/nuttx/arch/8051/src/up_allocateheap.c b/nuttx/arch/8051/src/up_allocateheap.c
index f2238507a..2f6a89490 100644
--- a/nuttx/arch/8051/src/up_allocateheap.c
+++ b/nuttx/arch/8051/src/up_allocateheap.c
@@ -70,10 +70,8 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside
+ * the heap region.
*
************************************************************/
diff --git a/nuttx/arch/arm/src/common/up_allocateheap.c b/nuttx/arch/arm/src/common/up_allocateheap.c
index d4b763196..12cbfcfa8 100644
--- a/nuttx/arch/arm/src/common/up_allocateheap.c
+++ b/nuttx/arch/arm/src/common/up_allocateheap.c
@@ -68,10 +68,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/dm320/dm320_allocateheap.c b/nuttx/arch/arm/src/dm320/dm320_allocateheap.c
index 5d4b90093..1383b93da 100644
--- a/nuttx/arch/arm/src/dm320/dm320_allocateheap.c
+++ b/nuttx/arch/arm/src/dm320/dm320_allocateheap.c
@@ -1,7 +1,7 @@
/************************************************************
* dm320/dm320_allocateheap.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,10 +68,17 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside
+ * the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both
+ * kernel- and user-space heaps (CONFIG_MM_KERNEL_HEAP=y),
+ * this function provides the size of the unprotected,
+ * user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel
+ * heap must be allocated (and protected) by an analogous
+ * up_allocate_kheap().
*
************************************************************/
diff --git a/nuttx/arch/arm/src/dm320/dm320_framebuffer.c b/nuttx/arch/arm/src/dm320/dm320_framebuffer.c
index 1b1197d53..8b5aec444 100644
--- a/nuttx/arch/arm/src/dm320/dm320_framebuffer.c
+++ b/nuttx/arch/arm/src/dm320/dm320_framebuffer.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/dm320/dm320_framebuffer.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,6 +46,7 @@
#include <debug.h>
#include <nuttx/fb.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/nx/nxglib.h>
#include "up_arch.h"
@@ -674,10 +675,10 @@ static int dm320_allocvideomemory(void)
{
#ifndef CONFIG_DM320_VID0_DISABLE
#ifndef CONFIG_DM320_DISABLE_PINGPONG
- g_vid0base = (FAR void *)malloc(2 * DM320_VID0_FBLEN);
+ g_vid0base = (FAR void *)kmalloc(2 * DM320_VID0_FBLEN);
g_vid0ppbase = (FAR char*)g_vid0base + DM320_VID0_FBLEN;
#else
- g_vid0base = (FAR void *)malloc(DM320_VID0_FBLEN);
+ g_vid0base = (FAR void *)kmalloc(DM320_VID0_FBLEN);
#endif
if (!g_vid0base)
{
@@ -686,7 +687,7 @@ static int dm320_allocvideomemory(void)
#endif
#ifndef CONFIG_DM320_VID1_DISABLE
- g_vid1base = (FAR void *)malloc(DM320_VID1_FBLEN);
+ g_vid1base = (FAR void *)kmalloc(DM320_VID1_FBLEN);
if (!g_vid1base)
{
goto errout;
@@ -694,7 +695,7 @@ static int dm320_allocvideomemory(void)
#endif
#ifndef CONFIG_DM320_OSD0_DISABLE
- g_osd0base = (FAR void *)malloc(DM320_OSD0_FBLEN);
+ g_osd0base = (FAR void *)kmalloc(DM320_OSD0_FBLEN);
if (!g_osd0base)
{
goto errout;
@@ -702,7 +703,7 @@ static int dm320_allocvideomemory(void)
#endif
#ifndef CONFIG_DM320_OSD1_DISABLE
- g_osd1base = (FAR void *)malloc(DM320_OSD1_FBLEN);
+ g_osd1base = (FAR void *)kmalloc(DM320_OSD1_FBLEN);
if (!g_osd1base)
{
goto errout;
@@ -725,7 +726,7 @@ static void dm320_freevideomemory(void)
#ifndef CONFIG_DM320_VID0_DISABLE
if (g_vid0base)
{
- free(g_vid0base);
+ kfree(g_vid0base);
g_vid0base = NULL;
#ifndef CONFIG_DM320_DISABLE_PINGPONG
g_vid0ppbase = NULL;
@@ -736,7 +737,7 @@ static void dm320_freevideomemory(void)
#ifndef CONFIG_DM320_VID1_DISABLE
if (g_vid1base != 0)
{
- free(g_vid1base);
+ kfree(g_vid1base);
g_vid1base = NULL;
}
#endif
@@ -744,7 +745,7 @@ static void dm320_freevideomemory(void)
#ifndef CONFIG_DM320_OSD0_DISABLE
if (g_osd0base != 0)
{
- free(g_osd0base);
+ kfree(g_osd0base);
g_osd0base = NULL;
}
#endif
@@ -752,7 +753,7 @@ static void dm320_freevideomemory(void)
#ifndef CONFIG_DM320_OSD1_DISABLE
if (g_osd1base != 0)
{
- free(g_osd1base);
+ kfree(g_osd1base);
g_osd1base = NULL;
}
#endif
diff --git a/nuttx/arch/arm/src/dm320/dm320_usbdev.c b/nuttx/arch/arm/src/dm320/dm320_usbdev.c
index c924db197..b30aba72c 100644
--- a/nuttx/arch/arm/src/dm320/dm320_usbdev.c
+++ b/nuttx/arch/arm/src/dm320/dm320_usbdev.c
@@ -1,7 +1,7 @@
/*******************************************************************************
* arch/arm/src/dm320/dm320_usbdev.c
*
- * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -1936,7 +1937,7 @@ static FAR struct usbdev_req_s *dm320_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct dm320_ep_s *)ep)->epphy);
- privreq = (FAR struct dm320_req_s *)malloc(sizeof(struct dm320_req_s));
+ privreq = (FAR struct dm320_req_s *)kmalloc(sizeof(struct dm320_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(DM320_TRACEERR_ALLOCFAIL), 0);
@@ -1968,7 +1969,7 @@ static void dm320_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct dm320_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -1987,7 +1988,7 @@ static void *dm320_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
#ifdef CONFIG_USBDEV_DMAMEMORY
return usbdev_dma_alloc(bytes);
#else
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
#endif
@@ -2008,7 +2009,7 @@ static void dm320_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#ifdef CONFIG_USBDEV_DMAMEMORY
usbdev_dma_free(buf);
#else
- free(buf);
+ kfree(buf);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/imx/imx_allocateheap.c b/nuttx/arch/arm/src/imx/imx_allocateheap.c
index 3279ddbd9..37b05eb7f 100644
--- a/nuttx/arch/arm/src/imx/imx_allocateheap.c
+++ b/nuttx/arch/arm/src/imx/imx_allocateheap.c
@@ -72,9 +72,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
- * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
- * called to dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index b09220a53..620b46a8e 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -182,10 +182,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
index 753f82326..938d0c8a7 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -2658,7 +2659,7 @@ static FAR struct usbdev_req_s *lpc17_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc17_ep_s *)ep)->epphy);
- privreq = (FAR struct lpc17_req_s *)malloc(sizeof(struct lpc17_req_s));
+ privreq = (FAR struct lpc17_req_s *)kmalloc(sizeof(struct lpc17_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(LPC17_TRACEERR_ALLOCFAIL), 0);
@@ -2690,7 +2691,7 @@ static void lpc17_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc17_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -2711,7 +2712,7 @@ static FAR void *lpc17_epallocbuffer(FAR struct usbdev_ep_s *ep, uint16_t nbytes
usbtrace(TRACE_EPALLOCBUFFER, privep->epphy);
- /* Find a free DMA description */
+ /* Find a free DMA description */
#error "LOGIC INCOMPLETE"
@@ -2728,7 +2729,7 @@ static FAR void *lpc17_epallocbuffer(FAR struct usbdev_ep_s *ep, uint16_t nbytes
#else
usbtrace(TRACE_EPALLOCBUFFER, privep->epphy);
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
@@ -2767,7 +2768,7 @@ static void lpc17_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#else
usbtrace(TRACE_EPFREEBUFFER, privep->epphy);
- free(buf);
+ kfree(buf);
#endif
}
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
index 78dc86992..da55c67db 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -2622,7 +2623,7 @@ static FAR struct usbdev_req_s *lpc214x_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc214x_ep_s *)ep)->epphy);
- privreq = (FAR struct lpc214x_req_s *)malloc(sizeof(struct lpc214x_req_s));
+ privreq = (FAR struct lpc214x_req_s *)kmalloc(sizeof(struct lpc214x_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_ALLOCFAIL), 0);
@@ -2654,7 +2655,7 @@ static void lpc214x_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc214x_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -2675,7 +2676,7 @@ static FAR void *lpc214x_epallocbuffer(FAR struct usbdev_ep_s *ep, uint16_t nbyt
usbtrace(TRACE_EPALLOCBUFFER, privep->epphy);
- /* Find a free DMA description */
+ /* Find a free DMA description */
#error "LOGIC INCOMPLETE"
@@ -2692,7 +2693,7 @@ static FAR void *lpc214x_epallocbuffer(FAR struct usbdev_ep_s *ep, uint16_t nbyt
#else
usbtrace(TRACE_EPALLOCBUFFER, privep->epphy);
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
@@ -2731,7 +2732,7 @@ static void lpc214x_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#else
usbtrace(TRACE_EPFREEBUFFER, privep->epphy);
- free(buf);
+ kfree(buf);
#endif
}
diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c
index 204fdf6c1..f57c343ef 100644
--- a/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c
@@ -157,10 +157,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE
- * and CONFIG_HEAP_SIZE. If these are not defined, then this function
- * will be called to dynamically set aside the heap region to the end
- * of SRAM.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
* SRAM layout:
* Start of SRAM: .data
diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
index ddeb1bf6b..1449d5e5b 100644
--- a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
+++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
@@ -53,6 +53,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -1949,7 +1950,7 @@ static FAR struct usbdev_req_s *lpc31_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc31_ep_s *)ep)->epphy);
- privreq = (FAR struct lpc31_req_s *)malloc(sizeof(struct lpc31_req_s));
+ privreq = (FAR struct lpc31_req_s *)kmalloc(sizeof(struct lpc31_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_ALLOCFAIL), 0);
@@ -1981,7 +1982,7 @@ static void lpc31_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc31_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -2000,7 +2001,7 @@ static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
#ifdef CONFIG_USBDEV_DMAMEMORY
return usbdev_dma_alloc(bytes);
#else
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
#endif
@@ -2021,7 +2022,7 @@ static void lpc31_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#ifdef CONFIG_USBDEV_DMAMEMORY
usbdev_dma_free(buf);
#else
- free(buf);
+ kfree(buf);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c b/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c
index ef96bcb0c..c33f9f1ed 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_allocateheap.c
@@ -228,10 +228,14 @@ const uint32_t g_heapbase = (uint32_t)&_ebss + CONFIG_IDLETHREAD_STACKSIZE;
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
index d0af116d6..379dbc435 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
@@ -58,6 +58,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -1949,7 +1950,7 @@ static FAR struct usbdev_req_s *lpc43_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc43_ep_s *)ep)->epphy);
- privreq = (FAR struct lpc43_req_s *)malloc(sizeof(struct lpc43_req_s));
+ privreq = (FAR struct lpc43_req_s *)kmalloc(sizeof(struct lpc43_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(LPC43_TRACEERR_ALLOCFAIL), 0);
@@ -1981,7 +1982,7 @@ static void lpc43_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc43_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -2000,7 +2001,7 @@ static void *lpc43_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
#ifdef CONFIG_USBDEV_DMAMEMORY
return usbdev_dma_alloc(bytes);
#else
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
#endif
@@ -2021,7 +2022,7 @@ static void lpc43_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#ifdef CONFIG_USBDEV_DMAMEMORY
usbdev_dma_free(buf);
#else
- free(buf);
+ kfree(buf);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
index a5236e74d..99e2d9e86 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
@@ -94,10 +94,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
index b70a29b44..149de8648 100644
--- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
+++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
@@ -356,10 +356,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index ece965b01..3986106d8 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -4230,7 +4231,7 @@ static FAR struct usbdev_req_s *stm32_ep_allocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct stm32_ep_s *)ep)->epphy);
- privreq = (FAR struct stm32_req_s *)malloc(sizeof(struct stm32_req_s));
+ privreq = (FAR struct stm32_req_s *)kmalloc(sizeof(struct stm32_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(STM32_TRACEERR_ALLOCFAIL), 0);
@@ -4262,7 +4263,7 @@ static void stm32_ep_freereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct stm32_ep_s *)ep)->epphy);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -4281,7 +4282,7 @@ static void *stm32_ep_allocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
#ifdef CONFIG_USBDEV_DMAMEMORY
return usbdev_dma_alloc(bytes);
#else
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
#endif
@@ -4302,7 +4303,7 @@ static void stm32_ep_freebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#ifdef CONFIG_USBDEV_DMAMEMORY
usbdev_dma_free(buf);
#else
- free(buf);
+ kfree(buf);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
index 6036eb3d5..ab3967783 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
@@ -52,6 +52,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -2762,7 +2763,7 @@ static struct usbdev_req_s *stm32_epallocreq(struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, USB_EPNO(ep->eplog));
- privreq = (struct stm32_req_s *)malloc(sizeof(struct stm32_req_s));
+ privreq = (struct stm32_req_s *)kmalloc(sizeof(struct stm32_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(STM32_TRACEERR_ALLOCFAIL), 0);
@@ -2790,7 +2791,7 @@ static void stm32_epfreereq(struct usbdev_ep_s *ep, struct usbdev_req_s *req)
#endif
usbtrace(TRACE_EPFREEREQ, USB_EPNO(ep->eplog));
- free(privreq);
+ kfree(privreq);
}
/****************************************************************************
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
index 0e3ac6487..a5fb64c36 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
@@ -1,7 +1,7 @@
/*******************************************************************************
* arch/arm/src/at90usb/at90usb_usbdev.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -2286,7 +2287,7 @@ static FAR struct usbdev_req_s *avr_epallocreq(FAR struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, ((FAR struct avr_ep_s *)ep)->ep.eplog);
- privreq = (FAR struct avr_req_s *)malloc(sizeof(struct avr_req_s));
+ privreq = (FAR struct avr_req_s *)kmalloc(sizeof(struct avr_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(AVR_TRACEERR_ALLOCFAIL), 0);
@@ -2319,7 +2320,7 @@ static void avr_epfreereq(FAR struct usbdev_ep_s *ep,
#endif
usbtrace(TRACE_EPFREEREQ, ((FAR struct avr_ep_s *)ep)->ep.eplog);
- free(privreq);
+ kfree(privreq);
}
/*******************************************************************************
@@ -2338,7 +2339,7 @@ static void *avr_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
#ifdef CONFIG_USBDEV_DMAMEMORY
return usbdev_dma_alloc(bytes);
#else
- return malloc(bytes);
+ return kmalloc(bytes);
#endif
}
#endif
@@ -2359,7 +2360,7 @@ static void avr_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
#ifdef CONFIG_USBDEV_DMAMEMORY
usbdev_dma_free(buf);
#else
- free(buf);
+ kfree(buf);
#endif
}
#endif
diff --git a/nuttx/arch/avr/src/common/up_allocateheap.c b/nuttx/arch/avr/src/common/up_allocateheap.c
index b4a7cde02..3a67ff6a7 100644
--- a/nuttx/arch/avr/src/common/up_allocateheap.c
+++ b/nuttx/arch/avr/src/common/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/avr/src/common/up_allocateheap.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,9 +68,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
- * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
- * called to dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/hc/src/common/up_allocateheap.c b/nuttx/arch/hc/src/common/up_allocateheap.c
index fc86faca5..b107baaa5 100644
--- a/nuttx/arch/hc/src/common/up_allocateheap.c
+++ b/nuttx/arch/hc/src/common/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/hc/src/common/up_allocateheap.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,10 +67,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/mips/src/common/up_allocateheap.c b/nuttx/arch/mips/src/common/up_allocateheap.c
index f29b2685f..b8c449ff1 100644
--- a/nuttx/arch/mips/src/common/up_allocateheap.c
+++ b/nuttx/arch/mips/src/common/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/common/up_allocateheap.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,10 +68,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
index 8d9f7c058..5e0f2db3b 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/pic32mx/pic32mx_usbdev.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
@@ -57,6 +57,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
@@ -3313,7 +3314,7 @@ static struct usbdev_req_s *pic32mx_epallocreq(struct usbdev_ep_s *ep)
#endif
usbtrace(TRACE_EPALLOCREQ, USB_EPNO(ep->eplog));
- privreq = (struct pic32mx_req_s *)malloc(sizeof(struct pic32mx_req_s));
+ privreq = (struct pic32mx_req_s *)kmalloc(sizeof(struct pic32mx_req_s));
if (!privreq)
{
usbtrace(TRACE_DEVERROR(PIC32MX_TRACEERR_ALLOCFAIL), 0);
@@ -3341,7 +3342,7 @@ static void pic32mx_epfreereq(struct usbdev_ep_s *ep, struct usbdev_req_s *req)
#endif
usbtrace(TRACE_EPFREEREQ, USB_EPNO(ep->eplog));
- free(privreq);
+ kfree(privreq);
}
/****************************************************************************
diff --git a/nuttx/arch/rgmp/src/nuttx.c b/nuttx/arch/rgmp/src/nuttx.c
index 6cb300f82..63e925b8c 100644
--- a/nuttx/arch/rgmp/src/nuttx.c
+++ b/nuttx/arch/rgmp/src/nuttx.c
@@ -161,7 +161,7 @@ int up_use_stack(struct tcb_s *tcb, void *stack, size_t stack_size)
void up_release_stack(struct tcb_s *dtcb)
{
if (dtcb->stack_alloc_ptr) {
- free(dtcb->stack_alloc_ptr);
+ kfree(dtcb->stack_alloc_ptr);
}
dtcb->stack_alloc_ptr = NULL;
diff --git a/nuttx/arch/sh/src/common/up_allocateheap.c b/nuttx/arch/sh/src/common/up_allocateheap.c
index e19b2c18e..ad1935d9a 100644
--- a/nuttx/arch/sh/src/common/up_allocateheap.c
+++ b/nuttx/arch/sh/src/common/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_allocateheap.c
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,10 +67,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/sim/src/up_allocateheap.c b/nuttx/arch/sim/src/up_allocateheap.c
index 47400ec7c..ffdb69518 100644
--- a/nuttx/arch/sim/src/up_allocateheap.c
+++ b/nuttx/arch/sim/src/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* up_allocateheap.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -71,10 +71,14 @@ static uint8_t sim_heap[SIM_HEAP_SIZE];
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/sim/src/up_deviceimage.c b/nuttx/arch/sim/src/up_deviceimage.c
index e32f64927..e1f2210f2 100644
--- a/nuttx/arch/sim/src/up_deviceimage.c
+++ b/nuttx/arch/sim/src/up_deviceimage.c
@@ -43,9 +43,13 @@
# include <zlib.h>
#else
# include <nuttx/config.h>
+
# include <stdlib.h>
# include <debug.h>
# include <zlib.h>
+
+# include <nuttx/kmalloc.h>
+
# include "up_internal.h"
#endif
@@ -55,6 +59,8 @@
#ifdef VFAT_STANDALONE
# define sdbg(format, arg...) printf(format, ##arg)
+# define kmalloc(size) malloc(size)
+# define kfree(mem) free(mem)
#endif
/****************************************************************************
@@ -224,7 +230,8 @@ char *up_deviceimage(void)
/* Allocate a buffer to hold the decompressed buffer. We may have
* to reallocate this a few times to get the size right.
*/
- pbuffer = (char*)malloc(bufsize);
+
+ pbuffer = (char*)kmalloc(bufsize);
/* Set up the input buffer */
@@ -253,7 +260,7 @@ char *up_deviceimage(void)
case Z_STREAM_ERROR:
sdbg("inflate FAILED: ret=%d msg=\"%s\"\n", ret, strm.msg ? strm.msg : "No message" );
(void)inflateEnd(&strm);
- free(pbuffer);
+ kfree(pbuffer);
return NULL;
}
@@ -265,10 +272,10 @@ char *up_deviceimage(void)
if (strm.avail_out == 0)
{
int newbufsize = bufsize + 128*1024;
- char *newbuffer = realloc(pbuffer, newbufsize);
+ char *newbuffer = krealloc(pbuffer, newbufsize);
if (!newbuffer)
{
- free(pbuffer);
+ kfree(pbuffer);
return NULL;
}
else
@@ -285,10 +292,10 @@ char *up_deviceimage(void)
*/
int newbufsize = bufsize - strm.avail_out;
- char *newbuffer = realloc(pbuffer, newbufsize);
+ char *newbuffer = krealloc(pbuffer, newbufsize);
if (!newbuffer)
{
- free(pbuffer);
+ kfree(pbuffer);
return NULL;
}
else
@@ -344,7 +351,7 @@ int main(int argc, char **argv, char **envp)
if (deviceimage)
{
printf("Inflate SUCCEEDED\n");
- free(deviceimage);
+ kfree(deviceimage);
return 0;
}
else
diff --git a/nuttx/arch/x86/src/common/up_allocateheap.c b/nuttx/arch/x86/src/common/up_allocateheap.c
index 74b169df3..b56f9b59a 100644
--- a/nuttx/arch/x86/src/common/up_allocateheap.c
+++ b/nuttx/arch/x86/src/common/up_allocateheap.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/x86/src/common/up_allocateheap.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,9 +68,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
- * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
- * called to dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/z16/src/common/up_allocateheap.c b/nuttx/arch/z16/src/common/up_allocateheap.c
index 62ea870e9..b13740011 100644
--- a/nuttx/arch/z16/src/common/up_allocateheap.c
+++ b/nuttx/arch/z16/src/common/up_allocateheap.c
@@ -83,9 +83,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
- * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
- * called to dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/z80/src/common/up_allocateheap.c b/nuttx/arch/z80/src/common/up_allocateheap.c
index 734d678e7..c3e06ef12 100644
--- a/nuttx/arch/z80/src/common/up_allocateheap.c
+++ b/nuttx/arch/z80/src/common/up_allocateheap.c
@@ -85,9 +85,14 @@
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
- * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
- * called to dynamically set aside the heap region.
+ * This function will be called to dynamically set aside the heap region.
+ *
+ * For the kernel build (CONFIG_NUTTX_KERNEL=y) with both kernel- and
+ * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the
+ * size of the unprotected, user-space heap.
+ *
+ * If a protected kernel-space heap is provided, the kernel heap must be
+ * allocated (and protected) by an analogous up_allocate_kheap().
*
****************************************************************************/
diff --git a/nuttx/arch/z80/src/ez80/ez80_i2c.c b/nuttx/arch/z80/src/ez80/ez80_i2c.c
index dbc817442..6668704dc 100644
--- a/nuttx/arch/z80/src/ez80/ez80_i2c.c
+++ b/nuttx/arch/z80/src/ez80/ez80_i2c.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_i2c.c
*
- * Copyright(C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright(C) 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
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/i2c.h>
+#include <nuttx/kmalloc.h>
#include <arch/io.h>
#include <arch/board/board.h>
@@ -747,10 +748,10 @@ static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
for (retry = 0; retry < 100; retry++)
{
- /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
- * register to 1. The I2C then tests the I2C bus and transmits a START
- * condition when the bus is free.
- */
+ /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
+ * register to 1. The I2C then tests the I2C bus and transmits a START
+ * condition when the bus is free.
+ */
i2c_start();
@@ -920,7 +921,7 @@ FAR struct i2c_dev_s *up_i2cinitialize(int port)
/* Now, allocate an I2C instance for this caller */
- i2c = (FAR struct ez80_i2cdev_s *)malloc(sizeof(FAR struct ez80_i2cdev_s));
+ i2c = (FAR struct ez80_i2cdev_s *)kmalloc(sizeof(FAR struct ez80_i2cdev_s));
if (i2c)
{
/* Initialize the allocated instance */
diff --git a/nuttx/arch/z80/src/z8/z8_i2c.c b/nuttx/arch/z80/src/z8/z8_i2c.c
index e90bd4036..59cd2fc2b 100644
--- a/nuttx/arch/z80/src/z8/z8_i2c.c
+++ b/nuttx/arch/z80/src/z8/z8_i2c.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/z8/z8_i2c.c
*
- * Copyright(C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright(C) 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
@@ -48,6 +48,7 @@
#include <debug.h>
#include <nuttx/i2c.h>
+#include <nuttx/kmalloc.h>
#include <arch/board/board.h>
#include <eZ8.h> /* eZ8 Register definitions */
@@ -592,7 +593,7 @@ FAR struct i2c_dev_s *up_i2cinitialize(int port)
/* Now, allocate an I2C instance for this caller */
- i2c = (FAR struct z8_i2cdev_s *)malloc(sizeof(FAR struct z8_i2cdev_s));
+ i2c = (FAR struct z8_i2cdev_s *)kmalloc(sizeof(FAR struct z8_i2cdev_s));
if (i2c)
{
/* Initialize the allocated instance */
@@ -600,5 +601,6 @@ FAR struct i2c_dev_s *up_i2cinitialize(int port)
i2c->ops = &g_ops;
i2c->brg = g_currbrg;
}
+
return (FAR struct i2c_dev_s *)i2c;
}