summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/samv7/sam_allocateheap.c12
-rw-r--r--nuttx/arch/arm/src/samv7/sam_serial.c20
-rw-r--r--nuttx/configs/samv71-xult/README.txt63
-rw-r--r--nuttx/configs/samv71-xult/nsh/Make.defs10
-rw-r--r--nuttx/configs/samv71-xult/nsh/defconfig6
-rw-r--r--nuttx/configs/samv71-xult/scripts/flash-dtcm.ld (renamed from nuttx/configs/samv71-xult/scripts/flash.ld)8
-rw-r--r--nuttx/configs/samv71-xult/scripts/flash-sram.ld119
-rw-r--r--nuttx/configs/samv71-xult/scripts/kernel-space.ld2
-rw-r--r--nuttx/configs/samv71-xult/scripts/memory.ld6
-rw-r--r--nuttx/configs/samv71-xult/src/samv71-xult.h4
10 files changed, 204 insertions, 46 deletions
diff --git a/nuttx/arch/arm/src/samv7/sam_allocateheap.c b/nuttx/arch/arm/src/samv7/sam_allocateheap.c
index e63b38e80..47cb12c08 100644
--- a/nuttx/arch/arm/src/samv7/sam_allocateheap.c
+++ b/nuttx/arch/arm/src/samv7/sam_allocateheap.c
@@ -128,11 +128,17 @@
/* Check internal SRAM configuration */
-#if CONFIG_RAM_END > (SAM_DTCM_BASE+SAMV7_SRAM_SIZE)
+#ifdef CONFIG_ARMV7M_DTCM
+# define SRAM_BASE SAM_DTCM_BASE
+#else
+# define SRAM_BASE SAM_SRAM_BASE
+#endif
+
+#if CONFIG_RAM_END > (SRAM_BASE+SAMV7_SRAM_SIZE)
# error "CONFIG_RAM_END is beyond the end of SRAM"
# undef CONFIG_RAM_END
-# define CONFIG_RAM_END (SAM_DTCM_BASE+SAMV7_SRAM_SIZE)
-#elif CONFIG_RAM_END < (SAM_DTCM_BASE+SAMV7_SRAM_SIZE)
+# define CONFIG_RAM_END (SRAM_BASE+SAMV7_SRAM_SIZE)
+#elif CONFIG_RAM_END < (SRAM_BASE+SAMV7_SRAM_SIZE)
# warning "CONFIG_RAM_END is before end of SRAM... not all of SRAM used"
#endif
diff --git a/nuttx/arch/arm/src/samv7/sam_serial.c b/nuttx/arch/arm/src/samv7/sam_serial.c
index 579efe09a..224e887ff 100644
--- a/nuttx/arch/arm/src/samv7/sam_serial.c
+++ b/nuttx/arch/arm/src/samv7/sam_serial.c
@@ -177,13 +177,13 @@
#if defined(CONFIG_SAMV7_UART1) && !defined(UART1_ASSIGNED)
# define TTYS2_DEV g_uart1port /* UART1 is ttyS2 */
# define UART1_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART2) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART2) && !defined(UART2_ASSIGNED)
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART3) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART3) && !defined(UART3_ASSIGNED)
# define TTYS2_DEV g_uart3port /* UART3 is ttyS2 */
# define UART3_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART4) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART4) && !defined(UART4_ASSIGNED)
# define TTYS2_DEV g_uart4port /* UART4 is ttyS2 */
# define UART4_ASSIGNED 1
#elif defined(CONFIG_SAMV7_USART0) && !defined(USART0_ASSIGNED)
@@ -202,13 +202,13 @@
* these could also be the console.
*/
-#if defined(CONFIG_SAMV7_UART2) && !defined(UART1_ASSIGNED)
+#if defined(CONFIG_SAMV7_UART2) && !defined(UART2_ASSIGNED)
# define TTYS3_DEV g_uart2port /* UART2 is ttyS3 */
# define UART2_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART3) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART3) && !defined(UART3_ASSIGNED)
# define TTYS3_DEV g_uart3port /* UART3 is ttyS3 */
# define UART3_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART4) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART4) && !defined(UART4_ASSIGNED)
# define TTYS3_DEV g_uart4port /* UART4 is ttyS3 */
# define UART4_ASSIGNED 1
#elif defined(CONFIG_SAMV7_USART0) && !defined(USART0_ASSIGNED)
@@ -227,10 +227,10 @@
* these could also be the console.
*/
-#if defined(CONFIG_SAMV7_UART3) && !defined(UART1_ASSIGNED)
+#if defined(CONFIG_SAMV7_UART3) && !defined(UART3_ASSIGNED)
# define TTYS4_DEV g_uart3port /* UART3 is ttyS4 */
# define UART3_ASSIGNED 1
-#elif defined(CONFIG_SAMV7_UART4) && !defined(UART1_ASSIGNED)
+#elif defined(CONFIG_SAMV7_UART4) && !defined(UART4_ASSIGNED)
# define TTYS4_DEV g_uart4port /* UART4 is ttyS4 */
# define UART4_ASSIGNED 1
#elif defined(CONFIG_SAMV7_USART0) && !defined(USART0_ASSIGNED)
@@ -249,7 +249,7 @@
* of these could also be the console.
*/
-#if defined(CONFIG_SAMV7_UART4) && !defined(UART1_ASSIGNED)
+#if defined(CONFIG_SAMV7_UART4) && !defined(UART4_ASSIGNED)
# define TTYS5_DEV g_uart4port /* UART4 is ttyS5 */
# define UART4_ASSIGNED 1
#elif defined(CONFIG_SAMV7_USART0) && !defined(USART0_ASSIGNED)
@@ -1003,7 +1003,7 @@ static int sam_interrupt(struct uart_dev_s *dev)
int passes;
bool handled;
- DEBUGASSERT(dev && priv->priv);
+ DEBUGASSERT(dev && dev->priv);
priv = (struct sam_dev_s*)dev->priv;
/* Loop until there are no characters to be transferred or, until we have
diff --git a/nuttx/configs/samv71-xult/README.txt b/nuttx/configs/samv71-xult/README.txt
index b073a5fd9..72c1e42ad 100644
--- a/nuttx/configs/samv71-xult/README.txt
+++ b/nuttx/configs/samv71-xult/README.txt
@@ -11,6 +11,7 @@ Contents
- Board Features
- Serial Console
- LEDs and Buttons
+ - Debugging
- Configurations
Board Features
@@ -170,33 +171,55 @@ NOTES:
use the SW1, PB12 has to be configured as a normal regular I/O pin in
the MATRIX module. For more information see the SAM V71 datasheet.
+Debugging
+=========
+
+The on-board EDBG appears to work only with Atmel Studio. You can however,
+simply connect a SAM-ICE or J-Link to the JTAG/SWD connector on the board
+and that works great. The only tricky thing is getting the correct
+orientation of the JTAG connection.
+
+I have been using Atmel Studio to write code to flash then I use the Segger
+J-Link GDB server to debug. I have been using the 'Device Programming' I
+available under the Atmel Studio 'Tool' menu. I have to disconnect the
+SAM-ICE while programming with the EDBG. I am sure that you could come up
+with a GDB server-only solution if you wanted.
+
+I run GDB like this from the directory containing the NuttX ELF file:
+
+ arm-none-eabi-gdb
+ (gdb) target remote localhost:2331
+ (gdb) mon reset
+ (gdb) file nuttx
+ (gdb) ... start debugging ...
+
Configurations
==============
- Information Common to All Configurations
- ----------------------------------------
- Each SAMV71-XULT configuration is maintained in a sub-directory and
- can be selected as follow:
+Information Common to All Configurations
+----------------------------------------
+Each SAMV71-XULT configuration is maintained in a sub-directory and
+can be selected as follow:
- cd tools
- ./configure.sh samv71-xult/<subdir>
- cd -
- . ./setenv.sh
+ cd tools
+ ./configure.sh samv71-xult/<subdir>
+ cd -
+ . ./setenv.sh
- Before sourcing the setenv.sh file above, you should examine it and perform
- edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
- than holds your toolchain binaries.
+Before sourcing the setenv.sh file above, you should examine it and perform
+edits as necessary so that TOOLCHAIN_BIN is the correct path to the directory
+than holds your toolchain binaries.
- And then build NuttX by simply typing the following. At the conclusion of
- the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
+And then build NuttX by simply typing the following. At the conclusion of
+the make, the nuttx binary will reside in an ELF file called, simply, nuttx.
- make oldconfig
- make
+ make oldconfig
+ make
- The <subdir> that is provided above as an argument to the tools/configure.sh
- must be is one of the following.
+The <subdir> that is provided above as an argument to the tools/configure.sh
+must be is one of the following.
- NOTES:
+NOTES:
1. These configurations use the mconf-based configuration tool. To
change any of these configurations using that tool, you should:
@@ -225,8 +248,8 @@ Configurations
You an get the free devkitARM toolchain from http://devkitpro.org/ or
http://sourceforge.net/projects/devkitpro/
- Configuration sub-directories
- -----------------------------
+Configuration sub-directories
+-----------------------------
nsh:
diff --git a/nuttx/configs/samv71-xult/nsh/Make.defs b/nuttx/configs/samv71-xult/nsh/Make.defs
index d8794ab95..3ef742504 100644
--- a/nuttx/configs/samv71-xult/nsh/Make.defs
+++ b/nuttx/configs/samv71-xult/nsh/Make.defs
@@ -37,6 +37,12 @@ include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+ifeq ($(CONFIG_ARMV7M_DTCM),y)
+ LDSCRIPT = flash-dtcm.ld
+else
+ LDSCRIPT = flash-sram.ld
+endif
+
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
@@ -44,13 +50,13 @@ ifeq ($(WINTOOL),y)
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
- ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/flash.ld}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
- ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/flash.ld
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
CC = $(CROSSDEV)gcc
diff --git a/nuttx/configs/samv71-xult/nsh/defconfig b/nuttx/configs/samv71-xult/nsh/defconfig
index a2222654b..de0f8a754 100644
--- a/nuttx/configs/samv71-xult/nsh/defconfig
+++ b/nuttx/configs/samv71-xult/nsh/defconfig
@@ -255,7 +255,7 @@ CONFIG_ARCH_HAVE_RAMVECTORS=y
#
# Board Settings
#
-CONFIG_BOARD_LOOPSPERMSEC=11990
+CONFIG_BOARD_LOOPSPERMSEC=42445
# CONFIG_ARCH_CALIBRATION is not set
#
@@ -278,7 +278,7 @@ CONFIG_BOOT_RUNFROMFLASH=y
#
# Boot Memory Configuration
#
-CONFIG_RAM_START=0x20000000
+CONFIG_RAM_START=0x20400000
CONFIG_RAM_SIZE=393216
# CONFIG_ARCH_HAVE_SDRAM is not set
@@ -595,7 +595,7 @@ CONFIG_FAT_MAXFNAME=32
# Memory Management
#
# CONFIG_MM_SMALL is not set
-CONFIG_MM_REGIONS=2
+CONFIG_MM_REGIONS=1
# CONFIG_ARCH_HAVE_HEAP2 is not set
# CONFIG_GRAN is not set
diff --git a/nuttx/configs/samv71-xult/scripts/flash.ld b/nuttx/configs/samv71-xult/scripts/flash-dtcm.ld
index 38c283b09..a999cbfa5 100644
--- a/nuttx/configs/samv71-xult/scripts/flash.ld
+++ b/nuttx/configs/samv71-xult/scripts/flash-dtcm.ld
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/samv71-xult/scripts/flash.ld
+ * configs/samv71-xult/scripts/flash-dtcm.ld
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,7 +33,7 @@
*
****************************************************************************/
-/* The SAMV71Q21 has 2048Kb of FLASH beginning at address 0x0400:0000 and
+/* The SAMV71Q21 has 2048Kb of FLASH beginning at address 0x0040:0000 and
* 384Kb of SRAM beginining at 0x2040:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
@@ -46,12 +46,14 @@
MEMORY
{
- flash (rx) : ORIGIN = 0x04000000, LENGTH = 2048K
+ flash (rx) : ORIGIN = 0x00400000, LENGTH = 2048K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 384K
}
OUTPUT_ARCH(arm)
+EXTERN(_vectors)
ENTRY(_stext)
+
SECTIONS
{
.text : {
diff --git a/nuttx/configs/samv71-xult/scripts/flash-sram.ld b/nuttx/configs/samv71-xult/scripts/flash-sram.ld
new file mode 100644
index 000000000..a89924ced
--- /dev/null
+++ b/nuttx/configs/samv71-xult/scripts/flash-sram.ld
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * configs/samv71-xult/scripts/flash-sram.ld
+ *
+ * Copyright (C) 2015 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.
+ *
+ ****************************************************************************/
+
+/* The SAMV71Q21 has 2048Kb of FLASH beginning at address 0x0040:0000 and
+ * 384Kb of SRAM beginining at 0x2040:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0400:0000 address range (Assuming that ITCM is not enable).
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x00400000, LENGTH = 2048K
+ sram (rwx) : ORIGIN = 0x20400000, LENGTH = 384K
+}
+
+OUTPUT_ARCH(arm)
+EXTERN(_vectors)
+ENTRY(_stext)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/samv71-xult/scripts/kernel-space.ld b/nuttx/configs/samv71-xult/scripts/kernel-space.ld
index d027da8c8..b24c585a6 100644
--- a/nuttx/configs/samv71-xult/scripts/kernel-space.ld
+++ b/nuttx/configs/samv71-xult/scripts/kernel-space.ld
@@ -38,7 +38,9 @@
*/
OUTPUT_ARCH(arm)
+EXTERN(_vectors)
ENTRY(_stext)
+
SECTIONS
{
.text : {
diff --git a/nuttx/configs/samv71-xult/scripts/memory.ld b/nuttx/configs/samv71-xult/scripts/memory.ld
index fe54e9e59..ba736a8eb 100644
--- a/nuttx/configs/samv71-xult/scripts/memory.ld
+++ b/nuttx/configs/samv71-xult/scripts/memory.ld
@@ -33,7 +33,7 @@
*
****************************************************************************/
-/* The SAMV71Q21 has 2048Kb of FLASH beginning at address 0x0400:0000 and
+/* The SAMV71Q21 has 2048Kb of FLASH beginning at address 0x0040:0000 and
* 384Kb of SRAM beginining at 0x2040:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
@@ -73,8 +73,8 @@ MEMORY
{
/* 2048KiB of internal FLASH */
- kflash (rx) : ORIGIN = 0x04000000, LENGTH = 1M
- uflash (rx) : ORIGIN = 0x04100000, LENGTH = 1M
+ kflash (rx) : ORIGIN = 0x00400000, LENGTH = 1M
+ uflash (rx) : ORIGIN = 0x00500000, LENGTH = 1M
/* 384Kb of internal SRAM */
diff --git a/nuttx/configs/samv71-xult/src/samv71-xult.h b/nuttx/configs/samv71-xult/src/samv71-xult.h
index ad24f4717..f1eafba7d 100644
--- a/nuttx/configs/samv71-xult/src/samv71-xult.h
+++ b/nuttx/configs/samv71-xult/src/samv71-xult.h
@@ -131,9 +131,9 @@
* ------ ----------- ---------------------
*/
-#define GPIO_LED0 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
+#define GPIO_LED0 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOA | GPIO_PIN23)
-#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
+#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOC | GPIO_PIN9)
/* Buttons