summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_svcall.c11
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_svcall.c17
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c14
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.h1
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c12
-rw-r--r--nuttx/configs/open1788/kernel/Makefile2
-rw-r--r--nuttx/configs/sam3u-ek/kernel/Makefile2
-rw-r--r--nuttx/include/assert.h22
-rw-r--r--nuttx/mm/mm_user.c1
-rw-r--r--nuttx/sched/group_create.c4
-rw-r--r--nuttx/sched/group_setupidlefiles.c4
-rw-r--r--nuttx/sched/os_start.c11
13 files changed, 76 insertions, 37 deletions
diff --git a/nuttx/arch/arm/src/armv6-m/up_svcall.c b/nuttx/arch/arm/src/armv6-m/up_svcall.c
index 7c2bf0f2c..b1bf1e4ec 100644
--- a/nuttx/arch/arm/src/armv6-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv6-m/up_svcall.c
@@ -110,12 +110,14 @@ static void dispatch_syscall(void)
{
__asm__ __volatile__
(
- " push {r4}\n" /* Save R4 */
+ " push {r4, r5}\n" /* Save R4 and R5 */
+ " mov r5, lr\n" /* Save lr in R5 */
" ldr r4, =g_stublookup\n" /* R4=The base of the stub lookup table */
" lsl r0, r0, #2\n" /* R0=Offset of the stub for this syscall */
" ldr r4, [r4, r0]\n" /* R4=Address of the stub for this syscall */
- " blx r5\n" /* Call the stub (modifies R14) */
- " pop {r4}\n" /* Restore R4 */
+ " blx r5\n" /* Call the stub (modifies lr) */
+ " mov lr, r5\n" /* Restore lr */
+ " pop {r4, r5}\n" /* Restore R4 and R5*/
" mov r2, r0\n" /* R2=Saves return value in R0 */
" mov r0, #3\n" /* R0=SYS_syscall_return */
" svc 0" /* Return from the syscall */
@@ -321,7 +323,8 @@ int up_svcall(int irq, FAR void *context)
current_regs[REG_R12], current_regs[REG_R13], current_regs[REG_R14], current_regs[REG_R15]);
#ifdef CONFIG_NUTTX_KERNEL
svcdbg("xPSR: %08x BASEPRI: %08x EXEC_RETURN: %08x\n",
- current_regs[REG_XPSR], current_regs[REG_BASEPRI], current_regs[REG_EXC_RETURN]);
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI],
+ current_regs[REG_EXC_RETURN]);
#else
svcdbg("xPSR: %08x BASEPRI: %08x\n",
current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
diff --git a/nuttx/arch/arm/src/armv7-m/up_svcall.c b/nuttx/arch/arm/src/armv7-m/up_svcall.c
index 13cce36ef..8321cd3bb 100644
--- a/nuttx/arch/arm/src/armv7-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv7-m/up_svcall.c
@@ -112,9 +112,13 @@ static void dispatch_syscall(void)
{
__asm__ __volatile__
(
+ " push {r4}\n" /* Save R4 */
+ " mov r4, lr\n" /* Save lr in R4 */
" ldr ip, =g_stublookup\n" /* R12=The base of the stub lookup table */
" ldr ip, [ip, r0, lsl #2]\n" /* R12=The address of the stub for this syscall */
- " blx ip\n" /* Call the stub (modifies R14)*/
+ " blx ip\n" /* Call the stub (modifies lr)*/
+ " mov lr, r4\n" /* Restore lr */
+ " pop {r4}\n" /* Restore r4 */
" mov r2, r0\n" /* R2=Saved return value in R0 */
" mov r0, #3\n" /* R0=SYS_syscall_return */
" svc 0" /* Return from the syscall */
@@ -152,7 +156,7 @@ int up_svcall(int irq, FAR void *context)
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
#ifdef REG_EXC_RETURN
- svcdbg(" PSR: %08x LR: %08x\n", regs[REG_XPSR], current_regs[REG_EXC_RETURN]);
+ svcdbg(" PSR: %08x LR: %08x\n", regs[REG_XPSR], regs[REG_EXC_RETURN]);
#else
svcdbg(" PSR: %08x\n", regs[REG_XPSR]);
#endif
@@ -265,7 +269,7 @@ int up_svcall(int irq, FAR void *context)
rtcb->xcp.sysreturn = 0;
/* The return value must be in R0-R1. dispatch_syscall() temporarily
- * moved the value for R0 to R2.
+ * moved the value for R0 into R2.
*/
current_regs[REG_R0] = current_regs[REG_R2];
@@ -322,7 +326,12 @@ int up_svcall(int irq, FAR void *context)
svcdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
current_regs[REG_R8], current_regs[REG_R9], current_regs[REG_R10], current_regs[REG_R11],
current_regs[REG_R12], current_regs[REG_R13], current_regs[REG_R14], current_regs[REG_R15]);
- svcdbg(" PSR=%08x\n", current_regs[REG_XPSR]);
+#ifdef REG_EXC_RETURN
+ svcdbg(" PSR: %08x LR: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_EXC_RETURN]);
+#else
+ svcdbg(" PSR: %08x\n", current_regs[REG_XPSR]);
+#endif
}
else
{
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index edd5100b3..f316570f5 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -300,10 +300,18 @@ void up_addregion(void)
*/
#ifdef LPC17_AHB_HEAPBASE
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
+
+ /* Yes.. allow user-mode access to the AHB SRAM user heap memory */
+
+ lpc17_mpu_uheap((uintptr_t)LPC17_AHB_HEAPBASE, LPC17_AHB_HEAPSIZE);
+
+#endif
+
+ /* Add the AHB SRAM user heap region. */
- /* Yes... Add the AHB SRAM heap region. */
+ kumm_addregion((FAR void*)LPC17_AHB_HEAPBASE, LPC17_AHB_HEAPSIZE);
- kmm_addregion((FAR void*)LPC17_AHB_HEAPBASE, LPC17_AHB_HEAPSIZE);
#endif
}
#endif
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
index f52a9a35e..b38061404 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.c
@@ -1546,7 +1546,7 @@ static void lpc17_widebus(FAR struct sdio_dev_s *dev, bool wide)
static void lpc17_clock(FAR struct sdio_dev_s *dev, enum sdio_clock_e rate)
{
- uint32_t clock;
+ uint32_t clkcr;
switch (rate)
{
@@ -1554,39 +1554,39 @@ static void lpc17_clock(FAR struct sdio_dev_s *dev, enum sdio_clock_e rate)
default:
case CLOCK_SDIO_DISABLED:
- clock = LPC17_CLCKCR_INIT;
+ clkcr = LPC17_CLCKCR_INIT;
return;
/* Enable in initial ID mode clocking (<400KHz) */
case CLOCK_IDMODE:
- clock = (LPC17_CLCKCR_INIT | SDCARD_CLOCK_CLKEN);
+ clkcr = (LPC17_CLCKCR_INIT | SDCARD_CLOCK_CLKEN);
break;
/* Enable in MMC normal operation clocking */
case CLOCK_MMC_TRANSFER:
- clock = (SDCARD_CLOCK_MMCXFR | SDCARD_CLOCK_CLKEN);
+ clkcr = (SDCARD_CLOCK_MMCXFR | SDCARD_CLOCK_CLKEN);
break;
/* SD normal operation clocking (wide 4-bit mode) */
case CLOCK_SD_TRANSFER_4BIT:
#ifndef CONFIG_SDIO_WIDTH_D1_ONLY
- clock = (SDCARD_CLOCK_SDWIDEXFR | SDCARD_CLOCK_CLKEN);
+ clkcr = (SDCARD_CLOCK_SDWIDEXFR | SDCARD_CLOCK_CLKEN);
break;
#endif
/* SD normal operation clocking (narrow 1-bit mode) */
case CLOCK_SD_TRANSFER_1BIT:
- clock = (SDCARD_CLOCK_SDXFR | SDCARD_CLOCK_CLKEN);
+ clkcr = (SDCARD_CLOCK_SDXFR | SDCARD_CLOCK_CLKEN);
break;
}
/* Set the new clock frequency along with the clock enable/disable bit */
- lpc17_setclock(clock);
+ lpc17_setclock(clkcr);
}
/****************************************************************************
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.h b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.h
index 3cb4132b2..66eb68b9b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_sdcard.h
@@ -124,4 +124,3 @@ void sdio_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect);
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_SDCARD_H */
-
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
index 0c122aeae..86d5fbf36 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
@@ -198,22 +198,22 @@ void up_allocate_kheap(FAR void **heap_start, size_t *heap_size)
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
- /* Add the region */
-
- kmm_addregion((FAR void*)SAM3U_INTSRAM1_BASE, CONFIG_SAM3U_SRAM1_SIZE);
-
/* Allow user access to the heap memory */
sam3u_mpu_uheap(SAM3U_INTSRAM1_BASE, CONFIG_SAM3U_SRAM1_SIZE);
/* Add the region */
-#if CONFIG_MM_REGIONS > 2
- kmm_addregion((FAR void*)SAM3U_NFCSRAM_BASE, CONFIG_SAM3U_NFCSRAM_SIZE);
+ kumm_addregion((FAR void*)SAM3U_INTSRAM1_BASE, CONFIG_SAM3U_SRAM1_SIZE);
+#if CONFIG_MM_REGIONS > 2
/* Allow user access to the heap memory */
sam3u_mpu_uheap(SAM3U_NFCSRAM_BASE, CONFIG_SAM3U_NFCSRAM_SIZE);
+
+ /* Add the region */
+
+ kumm_addregion((FAR void*)SAM3U_NFCSRAM_BASE, CONFIG_SAM3U_NFCSRAM_SIZE);
#endif
}
#endif
diff --git a/nuttx/configs/open1788/kernel/Makefile b/nuttx/configs/open1788/kernel/Makefile
index d3a47e738..16731a24d 100644
--- a/nuttx/configs/open1788/kernel/Makefile
+++ b/nuttx/configs/open1788/kernel/Makefile
@@ -70,7 +70,7 @@ OBJS = $(COBJS)
# Targets:
all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map
-.PHONY: depend clean distclean
+.PHONY: nuttx_user.elf depend clean distclean
$(COBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
diff --git a/nuttx/configs/sam3u-ek/kernel/Makefile b/nuttx/configs/sam3u-ek/kernel/Makefile
index 5ce23a539..da4510a00 100644
--- a/nuttx/configs/sam3u-ek/kernel/Makefile
+++ b/nuttx/configs/sam3u-ek/kernel/Makefile
@@ -70,7 +70,7 @@ OBJS = $(COBJS)
# Targets:
all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map
-.PHONY: depend clean distclean
+.PHONY: nuttx_user.elf depend clean distclean
$(COBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
diff --git a/nuttx/include/assert.h b/nuttx/include/assert.h
index 62ffb3a6e..f3e2854fc 100644
--- a/nuttx/include/assert.h
+++ b/nuttx/include/assert.h
@@ -49,10 +49,12 @@
/* Macro Name: ASSERT, ASSERTCODE, et al. */
-#undef ASSERT
-#undef ASSERTCODE
-#undef DEBUGASSERT
-#undef PANIC
+#undef ASSERT - Assert if the condition is not true
+#undef ASSERTCODE - Assert with an error code if the condition is not true
+#undef VERIFY - Assert if a function returns a negative value
+#undef DEBUGASSERT - Like ASSERT, but only if CONFIG_DEBUG is defined
+#undef DEBUGVERIFY - Like VERIFY, but only if CONFIG_DEBUG is defined
+#undef PANIC - Unconditional error with code
#ifdef CONFIG_HAVE_FILENAME
@@ -62,11 +64,17 @@
# define ASSERTCODE(f, code) \
{ if (!(f)) up_assert_code((const uint8_t *)__FILE__, (int)__LINE__, code); }
+# define VERIFY(f) \
+ { if ((f) < 0) up_assert((const uint8_t *)__FILE__, (int)__LINE__); }
+
# ifdef CONFIG_DEBUG
# define DEBUGASSERT(f) \
{ if (!(f)) up_assert((const uint8_t *)__FILE__, (int)__LINE__); }
+# define DEBUGVERIFY(f) \
+ { if ((f) < 0) up_assert((const uint8_t *)__FILE__, (int)__LINE__); }
# else
# define DEBUGASSERT(f)
+# define DEBUGVERIFY(f) ((void)(f))
# endif /* CONFIG_DEBUG */
# define PANIC(code) \
@@ -79,11 +87,17 @@
# define ASSERTCODE(f, code) \
{ if (!(f)) up_assert_code(code); }
+# define VERIFY(f) \
+ { if ((f) < 0) up_assert(); }
+
# ifdef CONFIG_DEBUG
# define DEBUGASSERT(f) \
{ if (!(f)) up_assert(); }
+# define DEBUGVERIFY(f) \
+ { if ((f) < 0) up_assert(); }
# else
# define DEBUGASSERT(f)
+# define DEBUGVERIFY(f) ((void)(f))
# endif /* CONFIG_DEBUG */
# define PANIC(code) \
diff --git a/nuttx/mm/mm_user.c b/nuttx/mm/mm_user.c
index ed5ba5eb9..d487e4264 100644
--- a/nuttx/mm/mm_user.c
+++ b/nuttx/mm/mm_user.c
@@ -38,6 +38,7 @@
************************************************************************/
#include <nuttx/config.h>
+#include <assert.h>
#include <nuttx/mm.h>
#if !defined(CONFIG_NUTTX_KERNEL) || !defined(__KERNEL__)
diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c
index d18fb82f8..875c36d10 100644
--- a/nuttx/sched/group_create.c
+++ b/nuttx/sched/group_create.c
@@ -225,6 +225,10 @@ int group_allocate(FAR struct task_tcb_s *tcb)
ret = env_dup(group);
if (ret < 0)
{
+#if CONFIG_NFILE_STREAMS > 0 && defined(CONFIG_NUTTX_KERNEL) && \
+ defined(CONFIG_MM_KERNEL_HEAP)
+ kufree(group->tg_streamlist);
+#endif
kfree(group);
tcb->cmn.group = NULL;
return ret;
diff --git a/nuttx/sched/group_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c
index 25ed71c04..2589dc637 100644
--- a/nuttx/sched/group_setupidlefiles.c
+++ b/nuttx/sched/group_setupidlefiles.c
@@ -80,14 +80,14 @@
int group_setupidlefiles(FAR struct task_tcb_s *tcb)
{
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
FAR struct task_group_s *group = tcb->cmn.group;
#endif
#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
int fd;
#endif
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
DEBUGASSERT(group);
#endif
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 6894ddc1b..fbb3b7743 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -39,8 +39,9 @@
#include <sys/types.h>
#include <stdbool.h>
-#include <debug.h>
#include <string.h>
+#include <assert.h>
+#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/compiler.h>
@@ -463,28 +464,28 @@ void os_start(void)
/* Allocate the IDLE group and suppress child status. */
#ifdef HAVE_TASK_GROUP
- (void)group_allocate(&g_idletcb);
+ DEBUGVERIFY(group_allocate(&g_idletcb));
#endif
/* Create stdout, stderr, stdin on the IDLE task. These will be
* inherited by all of the threads created by the IDLE task.
*/
- (void)group_setupidlefiles(&g_idletcb);
+ DEBUGVERIFY(group_setupidlefiles(&g_idletcb));
/* Complete initialization of the IDLE group. Suppress retention
* of child status in the IDLE group.
*/
#ifdef HAVE_TASK_GROUP
- (void)group_initialize(&g_idletcb);
+ DEBUGVERIFY(group_initialize(&g_idletcb));
g_idletcb.cmn.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
#endif
/* Bring Up the System ****************************************************/
/* Create initial tasks and bring-up the system */
- (void)os_bringup();
+ DEBUGVERIFY(os_bringup());
/* The IDLE Loop **********************************************************/
/* When control is return to this point, the system is idle. */