summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/nshlib/nsh_mntcmds.c2
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_svcall.c6
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_mpu.c19
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_svcall.c6
-rw-r--r--nuttx/arch/arm/src/sam3u/Make.defs2
-rw-r--r--nuttx/arch/mips/src/mips32/up_swint0.c6
-rw-r--r--nuttx/configs/open1788/include/board.h3
-rwxr-xr-xnuttx/configs/sam3u-ek/knsh/defconfig3
-rw-r--r--nuttx/include/nuttx/sdio.h12
-rw-r--r--nuttx/include/nuttx/wqueue.h4
-rw-r--r--nuttx/syscall/Makefile3
-rw-r--r--nuttx/syscall/syscall_clock_systimer.c84
-rw-r--r--nuttx/syscall/syscall_funclookup.c13
-rw-r--r--nuttx/syscall/syscall_lookup.h2
14 files changed, 139 insertions, 26 deletions
diff --git a/apps/nshlib/nsh_mntcmds.c b/apps/nshlib/nsh_mntcmds.c
index 8e62229fa..5557dba7e 100644
--- a/apps/nshlib/nsh_mntcmds.c
+++ b/apps/nshlib/nsh_mntcmds.c
@@ -84,7 +84,7 @@
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT) && \
- defined(CONFIG_FS_READABLE) && !defined(CONFIG_NSH_DISABLE_MOUNT)
+ defined(CONFIG_FS_READABLE) && !defined(CONFIG_NSH_DISABLE_DF)
static int df_handler(FAR const char *mountpoint,
FAR struct statfs *statbuf, FAR void *arg)
{
diff --git a/nuttx/arch/arm/src/armv6-m/up_svcall.c b/nuttx/arch/arm/src/armv6-m/up_svcall.c
index 9ce756213..7c2bf0f2c 100644
--- a/nuttx/arch/arm/src/armv6-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv6-m/up_svcall.c
@@ -251,7 +251,7 @@ int up_svcall(int irq, FAR void *context)
* that there is a saved syscall return address.
*/
- DEBUGASSERT(rtcb->xcp.sysreturn != NULL &&
+ DEBUGASSERT(rtcb->xcp.sysreturn != 0 &&
regs[REG_EXC_RETURN] == EXC_RETURN_PRIVTHR);
/* Setup to return to the saved syscall return address in
@@ -260,7 +260,7 @@ int up_svcall(int irq, FAR void *context)
current_regs[REG_PC] = rtcb->xcp.sysreturn;
current_regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
- rtcb->xcp.sysreturn = NULL;
+ rtcb->xcp.sysreturn = 0;
/* The return value must be in R0-R1. dispatch_syscall() temporarily
* moved the value to R2.
@@ -289,7 +289,7 @@ int up_svcall(int irq, FAR void *context)
* there is a no saved syscall return address.
*/
- DEBUGASSERT(rtcb->xcp.sysreturn == NULL &&
+ DEBUGASSERT(rtcb->xcp.sysreturn == 0 &&
regs[REG_EXC_RETURN] == EXC_RETURN_UNPRIVTHR);
/* Setup to return to dispatch_syscall in privileged mode. */
diff --git a/nuttx/arch/arm/src/armv7-m/up_mpu.c b/nuttx/arch/arm/src/armv7-m/up_mpu.c
index 4bb3f21d9..d4b04a444 100644
--- a/nuttx/arch/arm/src/armv7-m/up_mpu.c
+++ b/nuttx/arch/arm/src/armv7-m/up_mpu.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_mpu.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
@@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <stdint.h>
+#include <assert.h>
#include "mpu.h"
#include "up_internal.h"
@@ -58,7 +59,7 @@
* regions (0xff), and 0 means all subregions but one (0x00).
*/
-static const void uint8_t g_regionmap[9] =
+static const uint8_t g_regionmap[9] =
{
0xff, 0x7f, 0x3f, 0x1f, 0x0f, 0x07, 0x03, 0x01, 0x00
};
@@ -106,9 +107,10 @@ unsigned int mpu_allocregion(void)
uint8_t mpu_log2regionsize(size_t size)
{
+ uint32_t l2size;
+
/* The minimum permitted region size is 16 bytes (log2(16) = 4. */
- uint32_t l2size;
for (l2size = 4; l2size < 32 && size > (1 << l2size); size++);
return l2size;
}
@@ -129,7 +131,7 @@ uint8_t mpu_log2regionsize(size_t size)
uint32_t mpu_subregion(size_t size, uint8_t l2size)
{
- unsigned int nsrs
+ unsigned int nsrs;
uint32_t asize;
uint32_t mask;
@@ -140,7 +142,7 @@ uint32_t mpu_subregion(size_t size, uint8_t l2size)
* l2size: Log2 of the actual region size is <= (1 << l2size);
*/
- DEBUGASSERT(lsize > 3 && size <= (1 << l2size));
+ DEBUGASSERT(l2size > 3 && size <= (1 << l2size));
/* Examples with l2size = 12:
*
@@ -153,7 +155,7 @@ uint32_t mpu_subregion(size_t size, uint8_t l2size)
if (l2size < 32)
{
- mask = ((1 << lsize)-1) >> 3; /* Shifted mask */
+ mask = ((1 << l2size)-1) >> 3; /* Shifted mask */
}
/* The 4Gb region size is a special case */
@@ -168,9 +170,6 @@ uint32_t mpu_subregion(size_t size, uint8_t l2size)
}
asize = (size + mask) & ~mask; /* Adjusted size */
- nsrs = asize >> (lsize-3); /* Number of subregions */
+ nsrs = asize >> (l2size-3); /* Number of subregions */
return g_regionmap[nsrs];
}
-
-
-
diff --git a/nuttx/arch/arm/src/armv7-m/up_svcall.c b/nuttx/arch/arm/src/armv7-m/up_svcall.c
index 4da466934..5b56797a9 100644
--- a/nuttx/arch/arm/src/armv7-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv7-m/up_svcall.c
@@ -250,7 +250,7 @@ int up_svcall(int irq, FAR void *context)
* that there is a saved syscall return address.
*/
- DEBUGASSERT(rtcb->xcp.sysreturn != NULL &&
+ DEBUGASSERT(rtcb->xcp.sysreturn != 0 &&
regs[REG_EXC_RETURN] == EXC_RETURN_PRIVTHR);
/* Setup to return to the saved syscall return address in
@@ -259,7 +259,7 @@ int up_svcall(int irq, FAR void *context)
current_regs[REG_PC] = rtcb->xcp.sysreturn;
current_regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
- rtcb->xcp.sysreturn = NULL;
+ rtcb->xcp.sysreturn = 0;
/* The return value must be in R0-R1. dispatch_syscall() temporarily
* moved the value to R2.
@@ -288,7 +288,7 @@ int up_svcall(int irq, FAR void *context)
* there is a no saved syscall return address.
*/
- DEBUGASSERT(rtcb->xcp.sysreturn == NULL &&
+ DEBUGASSERT(rtcb->xcp.sysreturn == 0 &&
regs[REG_EXC_RETURN] == EXC_RETURN_UNPRIVTHR);
/* Setup to return to dispatch_syscall in privileged mode. */
diff --git a/nuttx/arch/arm/src/sam3u/Make.defs b/nuttx/arch/arm/src/sam3u/Make.defs
index 58047af21..1255af237 100644
--- a/nuttx/arch/arm/src/sam3u/Make.defs
+++ b/nuttx/arch/arm/src/sam3u/Make.defs
@@ -56,7 +56,7 @@ CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CHIP_CSRCS += up_mpu.c
+CMN_CSRCS += up_mpu.c
endif
ifeq ($(CONFIG_ELF),y)
diff --git a/nuttx/arch/mips/src/mips32/up_swint0.c b/nuttx/arch/mips/src/mips32/up_swint0.c
index 068bd45ab..4a172fe2a 100644
--- a/nuttx/arch/mips/src/mips32/up_swint0.c
+++ b/nuttx/arch/mips/src/mips32/up_swint0.c
@@ -244,7 +244,7 @@ int up_swint0(int irq, FAR void *context)
*/
#error "Missing logic -- need to test for privileged mode"
- DEBUGASSERT(rtcb->xcp.sysreturn != NULL && ???);
+ DEBUGASSERT(rtcb->xcp.sysreturn != 0 && ???);
/* Setup to return to the saved syscall return address in
* unprivileged mode.
@@ -252,7 +252,7 @@ int up_swint0(int irq, FAR void *context)
current_regs[REG_EPC] = rtcb->xcp.sysreturn;
#error "Missing logic -- need to set for unprivileged mode"
- rtcb->sysreturn = NULL;
+ rtcb->sysreturn = 0;
}
break;
#endif
@@ -276,7 +276,7 @@ int up_swint0(int irq, FAR void *context)
*/
#error "Missing logic -- Need to set unprivileged mode"
- DEBUGASSERT(rtcb->xcp.sysreturn == NULL && ???);
+ DEBUGASSERT(rtcb->xcp.sysreturn == 0 && ???);
/* Setup to return to dispatch_syscall in privileged mode. */
diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h
index 7991d3c09..8ebe31a0f 100644
--- a/nuttx/configs/open1788/include/board.h
+++ b/nuttx/configs/open1788/include/board.h
@@ -76,6 +76,9 @@
/* Select the main oscillator as the frequency source. SYSCLK is then the frequency
* of the main oscillator.
+ *
+ * If BOARD_XTAL_FREQUENCY > 15000000, then the SCS OSCRS bit (bit 4) should also
+ * be set in the BOARD_SCS_VALUE.
*/
#undef CONFIG_LPC17_MAINOSC
diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig
index fa3c1502f..bbd3662c1 100755
--- a/nuttx/configs/sam3u-ek/knsh/defconfig
+++ b/nuttx/configs/sam3u-ek/knsh/defconfig
@@ -182,7 +182,8 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
-CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=50000
CONFIG_SCHED_WORKSTACKSIZE=1024
diff --git a/nuttx/include/nuttx/sdio.h b/nuttx/include/nuttx/sdio.h
index 10612db85..d5b15370d 100644
--- a/nuttx/include/nuttx/sdio.h
+++ b/nuttx/include/nuttx/sdio.h
@@ -45,6 +45,7 @@
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
+
#include <nuttx/wqueue.h>
/****************************************************************************
@@ -658,7 +659,9 @@
* thread.
*
* When this method is called, all callbacks should be disabled until they
- * are enabled via a call to SDIO_CALLBACKENABLE
+ * are enabled via a call to SDIO_CALLBACKENABLE.
+ *
+ * NOTE: High-priority work queue support is required.
*
* Input Parameters:
* dev - Device-specific state data
@@ -670,7 +673,9 @@
*
****************************************************************************/
-#define SDIO_REGISTERCALLBACK(d,c,a) ((d)->registercallback(d,c,a))
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_HPWORK)
+# define SDIO_REGISTERCALLBACK(d,c,a) ((d)->registercallback(d,c,a))
+#endif
/****************************************************************************
* Name: SDIO_DMASUPPORTED
@@ -819,8 +824,11 @@ struct sdio_dev_s
sdio_eventset_t (*eventwait)(FAR struct sdio_dev_s *dev, uint32_t timeout);
void (*callbackenable)(FAR struct sdio_dev_s *dev,
sdio_eventset_t eventset);
+
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_HPWORK)
int (*registercallback)(FAR struct sdio_dev_s *dev,
worker_t callback, void *arg);
+#endif
/* DMA. CONFIG_SDIO_DMA should be set if the driver supports BOTH DMA
* and non-DMA transfer modes. If the driver supports only one mode
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index e76cdfd28..e1b9de91c 100644
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -116,6 +116,10 @@
/* To preserve legacy behavior, CONFIG_SCHED_HPWORK is assumed to be true
* in a flat build (CONFIG_SCHED_KERNEL=n) but must be defined in kernel
* mode in order to build the high priority work queue.
+ *
+ * In the kernel build, it is possible that no kernel work queues will be
+ * built. But in the flat build, the high priority work queue will always
+ * be built.
*/
# undef CONFIG_SCHED_HPWORK
diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
index eb602624e..fe6df054f 100644
--- a/nuttx/syscall/Makefile
+++ b/nuttx/syscall/Makefile
@@ -43,6 +43,7 @@ MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)"
CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv"
STUB_SRCS += syscall_funclookup.c syscall_stublookup.c syscall_nparms.c
+STUB_SRCS += syscall_clock_systimer.c
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
@@ -77,7 +78,7 @@ $(BIN1): $(PROXY_OBJS)
$(call ARCHIVE, $@, $(PROXY_OBJS))
$(BIN2): $(STUB_OBJS)
- $(call ARCHIVE, $@, "$(STUB_OBJS)")
+ $(call ARCHIVE, $@, $(STUB_OBJS))
.depend: Makefile $(SRCS)
$(Q) $(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
diff --git a/nuttx/syscall/syscall_clock_systimer.c b/nuttx/syscall/syscall_clock_systimer.c
new file mode 100644
index 000000000..e92b615a4
--- /dev/null
+++ b/nuttx/syscall/syscall_clock_systimer.c
@@ -0,0 +1,84 @@
+/****************************************************************************
+ * syscall/syscall_stublookup.c
+ *
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <nuttx/clock.h>
+
+#ifndef CONFIG_DISABLE_CLOCK
+
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: syscall_clock_systimer
+ *
+ * Description:
+ * In the kernel build, proxying for clock_systimer() must be handled
+ * specially. In the kernel phase of the build, clock_systimer() is
+ * macro that simply accesses a global variable. In the user phase of
+ * the kernel build, clock_systimer() is a proxy function.
+ *
+ * In order to fill out the table g_funclookup[], this function will stand
+ * in during the kernel phase of the build so that clock_systemer() will
+ * have an address that can be included in the g_funclookup[] table.
+ *
+ ****************************************************************************/
+
+uint32_t syscall_clock_systimer(void)
+{
+ return clock_systimer();
+}
+
+#endif /* !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/syscall/syscall_funclookup.c b/nuttx/syscall/syscall_funclookup.c
index 553381cd7..b768b2445 100644
--- a/nuttx/syscall/syscall_funclookup.c
+++ b/nuttx/syscall/syscall_funclookup.c
@@ -76,6 +76,19 @@
#include <nuttx/clock.h>
+/* clock_systimer is a special case: In the kernel build, proxying for
+ * clock_systimer() must be handled specially. In the kernel phase of
+ * the build, clock_systimer() is macro that simply accesses a global
+ * variable. In the user phase of the kernel build, clock_systimer()
+ * is a proxy function.
+ *
+ * In order to fill out the table g_funclookup[], this function will stand
+ * in during the kernel phase of the build so that clock_systemer() will
+ * have an address that can be included in the g_funclookup[] table.
+ */
+
+uint32_t syscall_clock_systimer(void);
+
/****************************************************************************
* Pre-processor definitions
****************************************************************************/
diff --git a/nuttx/syscall/syscall_lookup.h b/nuttx/syscall/syscall_lookup.h
index 1a958143c..e134c7179 100644
--- a/nuttx/syscall/syscall_lookup.h
+++ b/nuttx/syscall/syscall_lookup.h
@@ -128,7 +128,7 @@ SYSCALL_LOOKUP(up_assert_code, 3, STUB_up_assert_code)
*/
#ifndef CONFIG_DISABLE_CLOCK
- SYSCALL_LOOKUP(clock_systimer, 0, STUB_clock_systimer)
+ SYSCALL_LOOKUP(syscall_clock_systimer, 0, STUB_clock_systimer)
SYSCALL_LOOKUP(clock_getres, 2, STUB_clock_getres)
SYSCALL_LOOKUP(clock_gettime, 2, STUB_clock_gettime)
SYSCALL_LOOKUP(clock_settime, 2, STUB_clock_settime)