summaryrefslogtreecommitdiff
path: root/nuttx/configs/sam3u-ek
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-10 23:42:49 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-10 23:42:49 +0000
commit6157a0e4fd667b835dc74d291019dd61840213cd (patch)
tree029c000a13501c7904b1c5afa38ac99928540dac /nuttx/configs/sam3u-ek
parentf6fffbd5b0a83bd161e8f6417a4d034f72268217 (diff)
downloadpx4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.tar.gz
px4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.tar.bz2
px4-nuttx-6157a0e4fd667b835dc74d291019dd61840213cd.zip
Remove user_map.h; replace with a header at the beginning of the user-space blob. User work queue no started by os_brinup() on behalf of the application
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5727 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/sam3u-ek')
-rw-r--r--nuttx/configs/sam3u-ek/kernel/Makefile52
-rw-r--r--nuttx/configs/sam3u-ek/kernel/kernel.ld4
-rw-r--r--nuttx/configs/sam3u-ek/kernel/up_userspace.c129
-rwxr-xr-xnuttx/configs/sam3u-ek/knsh/defconfig9
-rw-r--r--nuttx/configs/sam3u-ek/src/up_leds.c3
5 files changed, 152 insertions, 45 deletions
diff --git a/nuttx/configs/sam3u-ek/kernel/Makefile b/nuttx/configs/sam3u-ek/kernel/Makefile
index 6d99c1753..d6349fe99 100644
--- a/nuttx/configs/sam3u-ek/kernel/Makefile
+++ b/nuttx/configs/sam3u-ek/kernel/Makefile
@@ -61,16 +61,24 @@ USER_LDFLAGS = --undefined=$(ENTRYPT) --entry=$(ENTRYPT) $(USER_LDSCRIPT)
USER_LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(USERLIBS))))
USER_LIBGCC = "${shell $(CC) -print-libgcc-file-name}"
-# Targets:
+# Source files
+
+CSRCS = up_userspace.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
+OBJS = $(COBJS)
-all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map $(BOARD_INCLUDE)$(DELIM)user_map.h
+# Targets:
+all: $(TOPDIR)$(DELIM)nuttx_user.elf $(TOPDIR)$(DELIM)User.map
.PHONY: depend clean distclean
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
# Create the nuttx_user.elf file containing all of the user-mode code
-nuttx_user.elf:
- $(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC)
+nuttx_user.elf: $(OBJS)
+ $(Q) $(LD) -o $@ $(USER_LDFLAGS) $(USER_LIBPATHS) $(OBJS) --start-group $(USER_LDLIBS) --end-group $(USER_LIBGCC)
$(TOPDIR)$(DELIM)nuttx_user.elf: nuttx_user.elf
@echo "LD: nuttx_user.elf"
@@ -93,41 +101,6 @@ $(TOPDIR)$(DELIM)User.map: nuttx_user.elf
$(Q) $(NM) nuttx_user.elf >$(TOPDIR)$(DELIM)User.map
$(Q) $(CROSSDEV)size nuttx_user.elf
-$(BOARD_INCLUDE)$(DELIM)user_map.h: $(TOPDIR)$(DELIM)User.map
- @echo "MK: user_map.h"
- $(Q) echo "/* configs$(DELIM)$(CONFIG_ARCH_BOARD)$(DELIM)include$(DELIM)user_map.h" > $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo " *" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo " * This is an auto-generated file.. Do not edit this file!" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo " */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#ifndef __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define __ARCH_BOARD_USER_MAP_H" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "/* General memory map */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_ENTRYPOINT 0x`grep \" $(ENTRYPT)\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_TEXTSTART 0x`grep \" _stext\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_TEXTEND 0x`grep \" _etext$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_DATASOURCE 0x`grep \" _eronly$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_DATADESTSTART 0x`grep \" _sdata$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_DATADESTEND 0x`grep \" _edata$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_BSSSTART 0x`grep \" _sbss\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_BSSEND 0x`grep \" _ebss$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "/* Memory manager entry points */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_MMINIT 0x`grep \" umm_initialize$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_MMADDREGION 0x`grep \" umm_addregion$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_MMTRYSEM 0x`grep \" umm_trysemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_MMGIVESEM 0x`grep \" umm_givesemaphore$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_MALLOC 0x`grep \" malloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_REALLOC 0x`grep \" realloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_ZALLOC 0x`grep \" zalloc$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#define CONFIG_USER_FREE 0x`grep \" free$\" $(TOPDIR)$(DELIM)User.map | cut -d' ' -f1`" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
- $(Q) echo "#endif /* __ARCH_BOARD_USER_MAP_H */" >> $(BOARD_INCLUDE)$(DELIM)user_map.h
-
.depend:
depend: .depend
@@ -139,4 +112,3 @@ clean:
$(call CLEAN)
distclean: clean
-
diff --git a/nuttx/configs/sam3u-ek/kernel/kernel.ld b/nuttx/configs/sam3u-ek/kernel/kernel.ld
index e0f2169be..1fadbbf57 100644
--- a/nuttx/configs/sam3u-ek/kernel/kernel.ld
+++ b/nuttx/configs/sam3u-ek/kernel/kernel.ld
@@ -81,6 +81,10 @@ OUTPUT_ARCH(arm)
SECTIONS
{
+ .userspace : {
+ *(.userspace)
+ } > uflash
+
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
diff --git a/nuttx/configs/sam3u-ek/kernel/up_userspace.c b/nuttx/configs/sam3u-ek/kernel/up_userspace.c
new file mode 100644
index 000000000..abccd5afc
--- /dev/null
+++ b/nuttx/configs/sam3u-ek/kernel/up_userspace.c
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * configs/sam3u-ek/kernel/up_userspace.c
+ *
+ * Copyright (C) 2013 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 <stdlib.h>
+
+#include <nuttx/userspace.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/mm.h>
+
+#if defined(CONFIG_NUTTX_KERNEL) && !defined(__KERNEL__)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_NUTTX_USERSPACE
+# error "CONFIG_NUTTX_USERSPACE not defined"
+#endif
+
+#if CONFIG_NUTTX_USERSPACE != 0x00090000
+# error "CONFIG_NUTTX_USERSPACE must be 0x00090000 to match kernel.ld"
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* These 'addresses' of these values are setup by the linker script. They are
+ * not actual uint32_t storage locations! They are only used meaningfully in the
+ * following way:
+ *
+ * - The linker script defines, for example, the symbol_sdata.
+ * - The declareion extern uint32_t _sdata; makes C happy. C will believe
+ * that the value _sdata is the address of a uint32_t variable _data (it is
+ * not!).
+ * - We can recoved the linker value then by simply taking the address of
+ * of _data. like: uint32_t *pdata = &_sdata;
+ */
+
+extern uint32_t _stext; /* Start of .text */
+extern uint32_t _etext; /* End_1 of .text + .rodata */
+extern const uint32_t _eronly; /* End+1 of read only section (.text + .rodata) */
+extern uint32_t _sdata; /* Start of .data */
+extern uint32_t _edata; /* End+1 of .data */
+extern uint32_t _sbss; /* Start of .bss */
+extern uint32_t _ebss; /* End+1 of .bss */
+
+/* This is the user space entry point */
+
+int CONFIG_USER_ENTRYPOINT(int argc, char *argv[]);
+
+const struct userspace_s userspace __attribute__ ((section (".userspace"))) =
+{
+ /* General memory map */
+
+ .us_entrypoint = (main_t)CONFIG_USER_ENTRYPOINT,
+ .us_textstart = (uintptr_t)&_stext,
+ .us_textend = (uintptr_t)&_etext,
+ .us_datasource = (uintptr_t)&_eronly,
+ .us_datastart = (uintptr_t)&_sdata,
+ .us_dataend = (uintptr_t)&_edata,
+ .us_bssstart = (uintptr_t)&_sbss,
+ .us_bssend = (uintptr_t)&_ebss,
+
+ /* Memory manager entry points (declared in include/nuttx/mm.h) */
+
+ .mm_initialize = umm_initialize,
+ .mm_addregion = umm_addregion,
+ .mm_trysemaphore = umm_trysemaphore,
+ .mm_givesemaphore = umm_givesemaphore,
+
+ /* Memory manager entry points (declared in include/stdlib.h) */
+
+ .mm_malloc = malloc,
+ .mm_realloc = realloc,
+ .mm_zalloc = zalloc,
+ .mm_free = free,
+
+ /* User-space work queue support (declared in include/nuttx/wqueue.h) */
+
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK)
+ .work_usrstart = work_usrstart;
+#endif
+};
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+ #endif /* CONFIG_NUTTX_KERNEL && !__KERNEL__ */
diff --git a/nuttx/configs/sam3u-ek/knsh/defconfig b/nuttx/configs/sam3u-ek/knsh/defconfig
index 7b0963ce0..93d436e54 100755
--- a/nuttx/configs/sam3u-ek/knsh/defconfig
+++ b/nuttx/configs/sam3u-ek/knsh/defconfig
@@ -16,18 +16,19 @@ CONFIG_HOST_LINUX=y
#
# Build Configuration
#
-CONFIG_APPS_DIR="../apps"
+# CONFIG_APPS_DIR="../apps"
CONFIG_BUILD_2PASS=y
CONFIG_PASS1_TARGET="all"
CONFIG_PASS1_BUILDIR="configs/sam3u-ek/kernel"
CONFIG_PASS1_OBJECT=""
CONFIG_NUTTX_KERNEL=y
+CONFIG_NUTTX_USERSPACE=0x00090000
#
# Binary Output Formats
#
# CONFIG_RRLOAD_BINARY is not set
-# CONFIG_INTELHEX_BINARY=y
+# CONFIG_INTELHEX_BINARY is not set
# CONFIG_MOTOROLA_SREC is not set
# CONFIG_RAW_BINARY is not set
@@ -350,7 +351,9 @@ CONFIG_FS_FAT=y
#
# Memory Management
#
-# CONFIG_MM_MULTIHEAP is not set
+CONFIG_MM_MULTIHEAP=y
+CONFIG_MM_KERNEL_HEAP=y
+CONFIG_MM_KERNEL_HEAPSIZE=8192
# CONFIG_MM_SMALL is not set
CONFIG_MM_REGIONS=3
# CONFIG_GRAN is not set
diff --git a/nuttx/configs/sam3u-ek/src/up_leds.c b/nuttx/configs/sam3u-ek/src/up_leds.c
index 72c565bd1..0b02ae20f 100644
--- a/nuttx/configs/sam3u-ek/src/up_leds.c
+++ b/nuttx/configs/sam3u-ek/src/up_leds.c
@@ -94,7 +94,6 @@
static const uint8_t g_ledon[8] =
{
-
(LED0_OFF |LED1_OFF |LED2_OFF), /* LED_STARTED */
(LED0_ON |LED1_OFF |LED2_ON), /* LED_HEAPALLOCATE */
(LED0_OFF |LED1_ON |LED2_OFF), /* LED_IRQSENABLED */
@@ -108,7 +107,6 @@ static const uint8_t g_ledon[8] =
static const uint8_t g_ledoff[8] =
{
-
(LED0_OFF |LED1_OFF |LED2_OFF), /* LED_STARTED (does not happen) */
(LED0_ON |LED1_OFF |LED2_ON), /* LED_HEAPALLOCATE (does not happen) */
(LED0_OFF |LED1_ON |LED2_OFF), /* LED_IRQSENABLED (does not happen) */
@@ -145,6 +143,7 @@ static void up_setled(uint16_t pinset, uint8_t state)
default:
return;
}
+
sam3u_gpiowrite(pinset, polarity);
}