summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-02 15:58:14 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-02 15:58:14 -0600
commita608530a1a5d6f6eb694c1e1aea613db53192ebc (patch)
tree4b19c15bfe8190d1aa9fc96f6e055ff58b4090ae /nuttx
parent3904a887d4aaced2f4858e2742df5f0eb5ae820a (diff)
downloadpx4-nuttx-a608530a1a5d6f6eb694c1e1aea613db53192ebc.tar.gz
px4-nuttx-a608530a1a5d6f6eb694c1e1aea613db53192ebc.tar.bz2
px4-nuttx-a608530a1a5d6f6eb694c1e1aea613db53192ebc.zip
Add support for delivery of use-mode signals in the kernel build.
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/arm/include/armv7-a/irq.h9
-rw-r--r--nuttx/arch/arm/src/a1x/Make.defs2
-rw-r--r--nuttx/arch/arm/src/armv7-a/arm_addrenv.c6
-rw-r--r--nuttx/arch/arm/src/armv7-a/arm_syscall.c21
-rw-r--r--nuttx/arch/arm/src/armv7-a/crt0.c52
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_signal_handler.S2
-rw-r--r--nuttx/arch/arm/src/sama5/Make.defs2
-rw-r--r--nuttx/include/nuttx/addrenv.h64
-rw-r--r--nuttx/include/nuttx/arch.h4
-rw-r--r--nuttx/include/nuttx/mm.h2
-rw-r--r--nuttx/mm/umm_addregion.c4
-rw-r--r--nuttx/mm/umm_brkaddr.c4
-rw-r--r--nuttx/mm/umm_calloc.c4
-rw-r--r--nuttx/mm/umm_extend.c4
-rw-r--r--nuttx/mm/umm_free.c4
-rw-r--r--nuttx/mm/umm_initialize.c6
-rw-r--r--nuttx/mm/umm_mallinfo.c4
-rw-r--r--nuttx/mm/umm_malloc.c4
-rw-r--r--nuttx/mm/umm_memalign.c4
-rw-r--r--nuttx/mm/umm_realloc.c4
-rw-r--r--nuttx/mm/umm_sbrk.c4
-rw-r--r--nuttx/mm/umm_sem.c4
-rw-r--r--nuttx/mm/umm_zalloc.c4
23 files changed, 159 insertions, 59 deletions
diff --git a/nuttx/arch/arm/include/armv7-a/irq.h b/nuttx/arch/arm/include/armv7-a/irq.h
index 3373819df..00e7244ae 100755
--- a/nuttx/arch/arm/include/armv7-a/irq.h
+++ b/nuttx/arch/arm/include/armv7-a/irq.h
@@ -240,6 +240,15 @@ struct xcptcontext
uint32_t saved_pc;
uint32_t saved_cpsr;
+
+# ifdef CONFIG_BUILD_KERNEL
+ /* This is the saved address to use when returning from a user-space
+ * signal handler.
+ */
+
+ uint32_t sigreturn;
+
+# endif
#endif
/* Register save area */
diff --git a/nuttx/arch/arm/src/a1x/Make.defs b/nuttx/arch/arm/src/a1x/Make.defs
index 17aa9bbe2..c06e3a6c8 100644
--- a/nuttx/arch/arm/src/a1x/Make.defs
+++ b/nuttx/arch/arm/src/a1x/Make.defs
@@ -83,7 +83,7 @@ CMN_CSRCS += arm_va2pte.c
endif
ifeq ($(CONFIG_BUILD_KERNEL),y)
-CMN_CSRCS += up_task_start.c up_pthread_start.c
+CMN_CSRCS += up_task_start.c up_pthread_start.c up_signal_dispatch.c
endif
ifeq ($(CONFIG_ARCH_ADDRENV),y)
diff --git a/nuttx/arch/arm/src/armv7-a/arm_addrenv.c b/nuttx/arch/arm/src/armv7-a/arm_addrenv.c
index bdb6c291d..1c1bba0a3 100644
--- a/nuttx/arch/arm/src/armv7-a/arm_addrenv.c
+++ b/nuttx/arch/arm/src/armv7-a/arm_addrenv.c
@@ -332,7 +332,7 @@ static void up_addrenv_destroy_region(FAR uintptr_t **list,
* needed by the task. This region may be read/write only. NOTE: The
* actual size of the data region that is allocated will include a
* OS private reserved region at the beginning. The size of the
- * private, reserved region is give by ARCH_DATA_RESERVE.
+ * private, reserved region is give by ARCH_DATA_RESERVE_SIZE.
* addrenv - The location to return the representation of the task address
* environment.
*
@@ -378,7 +378,7 @@ int up_addrenv_create(size_t textsize, size_t datasize,
ret = up_addrenv_create_region(addrenv->data, ARCH_DATA_NSECTS,
CONFIG_ARCH_DATA_VBASE,
- datasize + ARCH_DATA_RESERVE,
+ datasize + ARCH_DATA_RESERVE_SIZE,
MMU_L2_UDATAFLAGS);
if (ret < 0)
{
@@ -495,7 +495,7 @@ int up_addrenv_vdata(FAR group_addrenv_t *addrenv, uintptr_t textsize,
/* Not much to do in this case */
DEBUGASSERT(addrenv && vdata);
- *vdata = (FAR void *)(CONFIG_ARCH_DATA_VBASE + ARCH_DATA_RESERVE);
+ *vdata = (FAR void *)(CONFIG_ARCH_DATA_VBASE + ARCH_DATA_RESERVE_SIZE);
return OK;
}
diff --git a/nuttx/arch/arm/src/armv7-a/arm_syscall.c b/nuttx/arch/arm/src/armv7-a/arm_syscall.c
index 0295ffafe..846849b33 100644
--- a/nuttx/arch/arm/src/armv7-a/arm_syscall.c
+++ b/nuttx/arch/arm/src/armv7-a/arm_syscall.c
@@ -47,6 +47,7 @@
#include <arch/irq.h>
#include <nuttx/sched.h>
+#include <nuttx/addrenv.h>
#include "arm.h"
#include "svcall.h"
@@ -128,7 +129,7 @@ static void dispatch_syscall(void)
" add sp, sp, #16\n" /* Destroy the stack frame */
" mov r2, r0\n" /* R2=Save return value in R2 */
" mov r0, #0\n" /* R0=SYS_syscall_return */
- " svc #0x900001" /* Return from the SYSCALL */
+ " svc #0x900001\n" /* Return from the SYSCALL */
);
}
#endif
@@ -202,7 +203,7 @@ uint32_t *arm_syscall(uint32_t *regs)
case SYS_syscall_return:
{
- struct tcb_s *rtcb = sched_self();
+ FAR struct tcb_s *rtcb = sched_self();
int index = (int)rtcb->xcp.nsyscalls - 1;
/* Make sure that there is a saved SYSCALL return address. */
@@ -293,6 +294,7 @@ uint32_t *arm_syscall(uint32_t *regs)
break;
#endif
+#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
/* R0=SYS_signal_handler: This a user signal handler callback
*
* void signal_handler(_sa_sigaction_t sighand, int signo,
@@ -307,12 +309,9 @@ uint32_t *arm_syscall(uint32_t *regs)
* ucontext (on the stack)
*/
-#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
case SYS_signal_handler:
{
-#warning Missing logic
-#if 0
- struct tcb_s *rtcb = sched_self();
+ FAR struct tcb_s *rtcb = sched_self();
/* Remember the caller's return address */
@@ -323,7 +322,7 @@ uint32_t *arm_syscall(uint32_t *regs)
* unprivileged mode.
*/
- regs[REG_PC] = (uint32_t)USERSPACE->signal_handler;
+ regs[REG_PC] = (uint32_t)ARCH_DATA_RESERVE->ar_sigtramp;
cpsr = regs[REG_CPSR] & ~PSR_MODE_MASK;
regs[REG_CPSR] = cpsr | PSR_MODE_USR;
@@ -340,11 +339,11 @@ uint32_t *arm_syscall(uint32_t *regs)
*/
regs[REG_R3] = *(uint32_t*)(regs[REG_SP+4]);
-#endif
}
break;
#endif
+#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
/* R0=SYS_signal_handler_return: This a user signal handler callback
*
* void signal_handler_return(void);
@@ -354,12 +353,9 @@ uint32_t *arm_syscall(uint32_t *regs)
* R0 = SYS_signal_handler_return
*/
-#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
case SYS_signal_handler_return:
{
-#warning Missing logic
-#if 0
- struct tcb_s *rtcb = sched_self();
+ FAR struct tcb_s *rtcb = sched_self();
/* Set up to return to the kernel-mode signal dispatching logic. */
@@ -369,7 +365,6 @@ uint32_t *arm_syscall(uint32_t *regs)
cpsr = regs[REG_CPSR] & ~PSR_MODE_MASK;
regs[REG_CPSR] = cpsr | PSR_MODE_SVC;
rtcb->xcp.sigreturn = 0;
-#endif
}
break;
#endif
diff --git a/nuttx/arch/arm/src/armv7-a/crt0.c b/nuttx/arch/arm/src/armv7-a/crt0.c
index cda894433..8b661708e 100644
--- a/nuttx/arch/arm/src/armv7-a/crt0.c
+++ b/nuttx/arch/arm/src/armv7-a/crt0.c
@@ -41,6 +41,8 @@
#include <sys/types.h>
+#include <nuttx/addrenv.h>
+
#ifdef CONFIG_BUILD_KERNEL
/****************************************************************************
@@ -62,6 +64,48 @@ extern main_t main;
****************************************************************************/
/****************************************************************************
+ * Name: up_signal_handler
+ *
+ * Description:
+ * This function is the user-space, signal handler trampoline function. It
+ * is called from up_signal_dispatch() in user-mode.
+ *
+ * R0-R3, R11 - volatile registers need not be preserved.
+ * R4-R10 - static registers must be preserved
+ * R12-R14 - LR and SP must be preserved
+ *
+ * Inputs:
+ * R0 = sighand
+ * The address user-space signal handling function
+ * R1-R3 = signo, info, and ucontext
+ * Standard arguments to be passed to the signal handling function.
+ *
+ * Return:
+ * None. This function does not return in the normal sense. It returns
+ * via the SYS_signal_handler_return (see svcall.h)
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_SIGNALS
+static void sig_trampoline(void) naked_function;
+static void sig_trampoline(void)
+{
+ __asm__ __volatile__
+ (
+ " push {lr}\n" /* Save LR on the stack */
+ " mov ip, r0\n" /* IP=sighand */
+ " mov r0, r1\n" /* R0=signo */
+ " mov r1, r2\n" /* R1=info */
+ " mov r2, r3\n" /* R2=ucontext */
+ " blx ip\n" /* Call the signal handler */
+ " pop {r2}\n" /* Recover LR in R2 */
+ " mov lr, r2\n" /* Restore LR */
+ " mov r0, #4\n" /* SYS_signal_handler_return
+ " svc #0x900001\n" /* Return from the signal handler */
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -89,6 +133,14 @@ void _start(int argc, FAR char *argv[])
{
int ret;
+#ifndef CONFIG_DISABLE_SIGNALS
+ /* Initialize the reserved area at the beginning of the .bss/.data region
+ * that is visible to the RTOS.
+ */
+
+ ADDRENV_DATA_RESERVE->ar_sigtramp = (addrenv_sigtramp_t)sig_trampoline;
+#endif
+
/* Call C++ constructors */
/* Setup so that C++ destructors called on task exit */
/* REVISIT: Missing logic */
diff --git a/nuttx/arch/arm/src/armv7-m/up_signal_handler.S b/nuttx/arch/arm/src/armv7-m/up_signal_handler.S
index 38a0bd35d..e220ddf10 100644
--- a/nuttx/arch/arm/src/armv7-m/up_signal_handler.S
+++ b/nuttx/arch/arm/src/armv7-m/up_signal_handler.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/srcm/armv7-m/up_signal_handler.S
+ * arch/arm/src/armv7-m/up_signal_handler.S
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/sama5/Make.defs b/nuttx/arch/arm/src/sama5/Make.defs
index dc4544df7..241bb6a60 100644
--- a/nuttx/arch/arm/src/sama5/Make.defs
+++ b/nuttx/arch/arm/src/sama5/Make.defs
@@ -85,7 +85,7 @@ CMN_CSRCS += arm_va2pte.c
endif
ifeq ($(CONFIG_BUILD_KERNEL),y)
-CMN_CSRCS += up_task_start.c up_pthread_start.c
+CMN_CSRCS += up_task_start.c up_pthread_start.c up_signal_dispatch.c
endif
ifeq ($(CONFIG_ARCH_ADDRENV),y)
diff --git a/nuttx/include/nuttx/addrenv.h b/nuttx/include/nuttx/addrenv.h
index 49a46c897..a5e1de34b 100644
--- a/nuttx/include/nuttx/addrenv.h
+++ b/nuttx/include/nuttx/addrenv.h
@@ -42,6 +42,11 @@
#include <nuttx/config.h>
+#ifdef CONFIG_BUILD_KERNEL
+# include <signal.h>
+# include <nuttx/mm.h>
+#endif
+
#ifdef CONFIG_ARCH_ADDRENV
/****************************************************************************
@@ -98,18 +103,20 @@
/* Reserved .bss/.data region. In the kernel build (CONFIG_BUILD_KERNEL),
* the region at the beginning of the .bss/.data region is reserved for use
- * by the OS. This reserved region contains only the task group's heap
- * memory management data structures.
+ * by the OS. This reserved region contains support for:
*
- * We don't use sizeof(struct mm_heap_s) but, instead, a nice even number
- * that we must be assure is greater than or equal to
- * sizeof(struct mm_heap_s)
+ * 1. The task group's heap memory management data structures and
+ * 2. Support for delivery of signals.
+ *
+ * We don't use sizeof(struct addrenv_reserve_s) but, instead, a nice
+ * even number that we must be assure is greater than or equal to
+ * sizeof(struct addrenv_reserve_s)
*/
#ifdef CONFIG_BUILD_KERNEL
-# define ARCH_DATA_RESERVE 512
+# define ARCH_DATA_RESERVE_SIZE 512
#else
-# define ARCH_DATA_RESERVE 0
+# define ARCH_DATA_RESERVE_SIZE 0
#endif
/* Heap region */
@@ -155,11 +162,50 @@
#define ARCH_SCRATCH_VBASE (CONFIG_ARCH_STACK_VBASE + ARCH_STACK_SIZE)
/****************************************************************************
- * Private Data
+ * Public Types
****************************************************************************/
+/* Reserved .bss/.data region. In the kernel build (CONFIG_BUILD_KERNEL),
+ * the region at the beginning of the .bss/.data region is reserved for use
+ * by the OS. This reserved region contains support for:
+ *
+ * 1. The task group's heap memory management data structures and
+ * 2. Support for delivery of signals.
+ */
+
+#ifdef CONFIG_BUILD_KERNEL
+#ifndef CONFIG_DISABLE_SIGNALS
+/* This is the type of the signal handler trampoline routine. This
+ * trampoline is called directly from kernel logic. It simply forwards the
+ * signal information to the real signal handler. When the signal handler
+ * returns, this function issues a system call in order to return in kernel
+ * mode.
+ */
+
+typedef void (*addrenv_sigtramp_t)(_sa_sigaction_t sighand, int signo,
+ FAR siginfo_t *info, FAR void *ucontext);
+#endif
+
+/* This structure describes the format of the .bss/.data reserved area */
+
+struct addrenv_reserve_s
+{
+#ifndef CONFIG_DISABLE_SIGNALS
+ addrenv_sigtramp_t ar_sigtramp; /* Signal trampoline */
+#endif
+ struct mm_heap_s ar_usrheap; /* User space heap structure */
+};
+
+/* Each instance of this structure resides at the beginning of the user-
+ * space .bss/.data region. This macro is provided to simplify access:
+ */
+
+#define ARCH_DATA_RESERVE \
+ ((FAR struct addrenv_reserve_s *)CONFIG_ARCH_TEXT_VBASE)
+#endif
+
/****************************************************************************
- * Private Functions
+ * Public Data
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index d9d8c3736..9344383a8 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -763,7 +763,7 @@ uintptr_t pgalloc(uintptr_t brkaddr, unsigned int npages);
* needed by the task. This region may be read/write only. NOTE: The
* actual size of the data region that is allocated will include a
* OS private reserved region at the beginning. The size of the
- * private, reserved region is give by ARCH_DATA_RESERVE.
+ * private, reserved region is give by ARCH_DATA_RESERVE_SIZE.
* addrenv - The location to return the representation of the task address
* environment.
*
@@ -838,7 +838,7 @@ int up_addrenv_vtext(FAR group_addrenv_t *addrenv, FAR void **vtext);
* beginning of the data region is reserved for use by the OS. The
* returned address will be at a offset from the actual allocated base
* address to account for the OS private region. The size of that
- * offset is given by ARCH_DATA_RESERVE
+ * offset is given by ARCH_DATA_RESERVE_SIZE
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
diff --git a/nuttx/include/nuttx/mm.h b/nuttx/include/nuttx/mm.h
index fb93c002c..6d9d8daa6 100644
--- a/nuttx/include/nuttx/mm.h
+++ b/nuttx/include/nuttx/mm.h
@@ -328,10 +328,8 @@ void mm_givesemaphore(FAR struct mm_heap_s *heap);
/* Functions contained in umm_sem.c ****************************************/
-#ifdef MM_KERNEL_USRHEAP_INIT
int umm_trysemaphore(void);
void umm_givesemaphore(void);
-#endif
/* Functions contained in kmm_sem.c ****************************************/
diff --git a/nuttx/mm/umm_addregion.c b/nuttx/mm/umm_addregion.c
index a0eb3002c..7710f2aa0 100644
--- a/nuttx/mm/umm_addregion.c
+++ b/nuttx/mm/umm_addregion.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_brkaddr.c b/nuttx/mm/umm_brkaddr.c
index 8bf047c56..ae1fc1c2f 100644
--- a/nuttx/mm/umm_brkaddr.c
+++ b/nuttx/mm/umm_brkaddr.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_calloc.c b/nuttx/mm/umm_calloc.c
index 2acf1c9d1..665720947 100644
--- a/nuttx/mm/umm_calloc.c
+++ b/nuttx/mm/umm_calloc.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_extend.c b/nuttx/mm/umm_extend.c
index 6982ed813..9e9f2c63e 100644
--- a/nuttx/mm/umm_extend.c
+++ b/nuttx/mm/umm_extend.c
@@ -50,11 +50,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_free.c b/nuttx/mm/umm_free.c
index e0f9f4faf..6d1cd6bc6 100644
--- a/nuttx/mm/umm_free.c
+++ b/nuttx/mm/umm_free.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_initialize.c b/nuttx/mm/umm_initialize.c
index 9deaf61fa..3fdda2dde 100644
--- a/nuttx/mm/umm_initialize.c
+++ b/nuttx/mm/umm_initialize.c
@@ -60,11 +60,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
@@ -100,7 +100,7 @@ struct mm_heap_s g_mmheap;
void umm_initialize(FAR void *heap_start, size_t heap_size)
{
- DEBUGASSERT(ARCH_DATA_RESERVE >= sizeof(struct mm_heap_s));
+ DEBUGASSERT(ARCH_DATA_RESERVE_SIZE >= sizeof(struct addrenv_reserve_s));
mm_initialize(USR_HEAP, heap_start, heap_size);
}
diff --git a/nuttx/mm/umm_mallinfo.c b/nuttx/mm/umm_mallinfo.c
index 3a85b3229..2ccee5973 100644
--- a/nuttx/mm/umm_mallinfo.c
+++ b/nuttx/mm/umm_mallinfo.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_malloc.c b/nuttx/mm/umm_malloc.c
index 8a0bdfec7..6d99e75ab 100644
--- a/nuttx/mm/umm_malloc.c
+++ b/nuttx/mm/umm_malloc.c
@@ -53,11 +53,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_memalign.c b/nuttx/mm/umm_memalign.c
index cd098d12c..4a13bfe91 100644
--- a/nuttx/mm/umm_memalign.c
+++ b/nuttx/mm/umm_memalign.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_realloc.c b/nuttx/mm/umm_realloc.c
index 9fdad8fee..0652b172a 100644
--- a/nuttx/mm/umm_realloc.c
+++ b/nuttx/mm/umm_realloc.c
@@ -52,11 +52,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_sbrk.c b/nuttx/mm/umm_sbrk.c
index 9c26a3de4..3266b09b9 100644
--- a/nuttx/mm/umm_sbrk.c
+++ b/nuttx/mm/umm_sbrk.c
@@ -56,11 +56,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_sem.c b/nuttx/mm/umm_sem.c
index 6242f1719..98997f461 100644
--- a/nuttx/mm/umm_sem.c
+++ b/nuttx/mm/umm_sem.c
@@ -50,11 +50,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */
diff --git a/nuttx/mm/umm_zalloc.c b/nuttx/mm/umm_zalloc.c
index 0c2ddddeb..ebe232e22 100644
--- a/nuttx/mm/umm_zalloc.c
+++ b/nuttx/mm/umm_zalloc.c
@@ -53,11 +53,11 @@
* group. In this build configuration, the user heap structure lies
* in a reserved region at the beginning of the .bss/.data address
* space (CONFIG_ARCH_DATA_VBASE). The size of that region is given by
- * ARCH_DATA_RESERVE
+ * ARCH_DATA_RESERVE_SIZE
*/
# include <nuttx/addrenv.h>
-# define USR_HEAP ((FAR struct mm_heap_s *)CONFIG_ARCH_DATA_VBASE)
+# define USR_HEAP (&ARCH_DATA_RESERVE->ar_usrheap)
#else
/* Otherwise, the user heap data structures are in common .bss */